From 94e2a5d3c29412bf4ad8769dc5d2929258c68f76 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 20 Oct 2022 17:12:57 +0200 Subject: [PATCH 01/83] - improved SPI TFT and XPT2046 support (HAL handling rework based on library sources + (electrical) testing) brought to you by Martin Turski, company owner of EirDev (turningtides@outlook.de) this adds support for the Makerbase MKS TS35-R V2.0 screen in combination with the MKS Robin E3D V1.1 board. proper testing has shown that this hardware combination works very well with the Marlin firmware. previously the bus negotiations of various Marlin components was conflicting so much that this use-case was a head-ache! Adds proper baudrate determination between hardware specifications and board clock frequencies. - new configuration option: TOUCH_BAUDRATE - new configuration option: TFT_BAUDRATE_READ - new configuration option: TFT_BAUDRATE_WRITE Buy MKS Makerbase TS35-R V2.0 screen: https://de.aliexpress.com/item/1005003634231986.html Buy MKS Makerbase Robin E3D V1.1 board: https://de.aliexpress.com/item/4000781744682.html https://green-candy.osdn.jp/external/promo/mks_robin_e3d_v1_1_with_ts35r_v2_0.png Simply connect the screen across the EXP1/EXP2 connectors, flash the properly configured firmware and give it a go! Interupt-driven SPI DMA has not been tested. Also I have not tested every configuration combination. I would appreciate some verification by the Marlin FW community. --- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 324 +++++++++++++++--- Marlin/src/HAL/STM32/tft/tft_spi.h | 24 +- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 209 +++++++++-- Marlin/src/HAL/STM32/tft/xpt2046.h | 9 +- Marlin/src/inc/Conditionals_LCD.h | 8 + Marlin/src/lcd/tft_io/tft_io.cpp | 12 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 61 +++- 7 files changed, 565 insertions(+), 82 deletions(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index e455164c7736..ba9016cfc18a 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -34,43 +34,177 @@ SPI_HandleTypeDef TFT_SPI::SPIx; DMA_HandleTypeDef TFT_SPI::DMAtx; +uint8_t TFT_SPI::clkdiv_write; +#if PIN_EXISTS(TFT_MISO) +uint8_t TFT_SPI::clkdiv_read; +#endif + +bool TFT_SPI::active_transfer; +bool TFT_SPI::active_dma; + +uint8_t TFT_SPI::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) +{ + if ( speed >= (spibasefreq / 2) ) + { + return SPI_BAUDRATEPRESCALER_2; + } + else if ( speed >= (spibasefreq / 4) ) + { + return SPI_BAUDRATEPRESCALER_4; + } + else if ( speed >= (spibasefreq / 8) ) + { + return SPI_BAUDRATEPRESCALER_8; + } + else if ( speed >= (spibasefreq / 16) ) + { + return SPI_BAUDRATEPRESCALER_16; + } + else if ( speed >= (spibasefreq / 32) ) + { + return SPI_BAUDRATEPRESCALER_32; + } + else if ( speed >= (spibasefreq / 64) ) + { + return SPI_BAUDRATEPRESCALER_64; + } + else if ( speed >= (spibasefreq / 128) ) + { + return SPI_BAUDRATEPRESCALER_128; + } + else + { + return SPI_BAUDRATEPRESCALER_256; + } +} + +extern "C" { + #include +} + void TFT_SPI::Init() { + SPI_TypeDef *spiInstance; OUT_WRITE(TFT_A0_PIN, HIGH); OUT_WRITE(TFT_CS_PIN, HIGH); if ((spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK)) == NP) return; + if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI)) return; #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO)) return; #endif + // SPI can have different baudrates depending on read or write functionality. + +#if PIN_EXISTS(TFT_MISO) + // static clkdiv_read variable. + bool has_clkdiv_read = false; +#endif + // static clkdiv_write variable. + bool has_clkdiv_write = false; + +#if (PIN_EXISTS(TFT_MISO) && defined(TFT_BAUDRATE_READ)) || defined(TFT_BAURDATE_WRITE) + spi_t tmp_spi; + tmp_spi.pin_sclk = digitalPinToPinName(TFT_SCK_PIN); + uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); + +#if PIN_EXISTS(TFT_MISO) && TFT_BAUDRATE_READ + clkdiv_read = _GetClockDivider(spibasefreq, TFT_BAUDRATE_READ); + has_clkdiv_read = true; +#endif + +#ifdef TFT_BAUDRATE_WRITE + clkdiv_write = _GetClockDivider(spibasefreq, TFT_BAUDRATE_WRITE); + has_clkdiv_write = true; +#endif + +#endif + + if ( !has_clkdiv_write ) + { +#ifdef SPI1_BASE + if (spiInstance == SPI1) + { + clkdiv_write = SPI_BAUDRATEPRESCALER_4; + has_clkdiv_write = true; + } +#endif + + if ( !has_clkdiv_write ) + { + clkdiv_write = SPI_BAUDRATEPRESCALER_2; + } + } + +#if PIN_EXISTS(TFT_MISO) + if ( !has_clkdiv_read ) + { + clkdiv_read = clkdiv_write; + } +#endif + SPIx.Instance = spiInstance; SPIx.State = HAL_SPI_STATE_RESET; SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; - SPIx.Init.Direction = (TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2; + SPIx.Init.Direction = (TFT_MISO_PIN != NC && TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; + //SPIx.Init.BaudRatePrescaler = clkdiv; SPIx.Init.CLKPhase = SPI_PHASE_1EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_LOW; - SPIx.Init.DataSize = SPI_DATASIZE_8BIT; + //SPIx.Init.DataSize = SPI_DATASIZE_8BIT; SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB; SPIx.Init.TIMode = SPI_TIMODE_DISABLE; SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; SPIx.Init.CRCPolynomial = 10; + DMAtx.Init.Direction = DMA_MEMORY_TO_PERIPH; + DMAtx.Init.PeriphInc = DMA_PINC_DISABLE; + DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + DMAtx.Init.Mode = DMA_NORMAL; + DMAtx.Init.Priority = DMA_PRIORITY_LOW; + #ifdef STM32F4xx + DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif + + active_transfer = false; + active_dma = false; +} + +// Call before any HAL initialization (DMA or SPI). +void TFT_SPI::HALPrepare(eSPIMode spiMode) +{ + uint8_t clkdiv = 1; +#if PIN_EXISTS(TFT_MISO) + if (spiMode == eSPIMode::READ) + { + clkdiv = clkdiv_read; + } +#endif + if (spiMode == eSPIMode::WRITE) + { + clkdiv = clkdiv_write; + } + + SPIx.Init.BaudRatePrescaler = clkdiv; + pinmap_pinout(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK); pinmap_pinout(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI); #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO); #endif + //pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_SPI_SSEL); + pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); #ifdef SPI1_BASE if (SPIx.Instance == SPI1) { __HAL_RCC_SPI1_CLK_ENABLE(); + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); #ifdef STM32F1xx __HAL_RCC_DMA1_CLK_ENABLE(); DMAtx.Instance = DMA1_Channel3; @@ -79,12 +213,14 @@ void TFT_SPI::Init() { DMAtx.Instance = DMA2_Stream3; DMAtx.Init.Channel = DMA_CHANNEL_3; #endif - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; } #endif + #ifdef SPI2_BASE if (SPIx.Instance == SPI2) { __HAL_RCC_SPI2_CLK_ENABLE(); + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); #ifdef STM32F1xx __HAL_RCC_DMA1_CLK_ENABLE(); DMAtx.Instance = DMA1_Channel5; @@ -95,9 +231,12 @@ void TFT_SPI::Init() { #endif } #endif + #ifdef SPI3_BASE if (SPIx.Instance == SPI3) { __HAL_RCC_SPI3_CLK_ENABLE(); + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); #ifdef STM32F1xx __HAL_RCC_DMA2_CLK_ENABLE(); DMAtx.Instance = DMA2_Channel2; @@ -109,23 +248,92 @@ void TFT_SPI::Init() { } #endif - HAL_SPI_Init(&SPIx); + #ifdef SPI4_BASE + if (SPIx.Instance == SPI4) { + __HAL_RCC_SPI4_CLK_ENABLE(); + __HAL_RCC_SPI4_FORCE_RESET(); + __HAL_RCC_SPI4_RELEASE_RESET(); + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAtx.Instance = DMA2_Channel4; + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAtx.Instance = DMA2_Stream5; + DMAtx.Init.Channel = DMA_CHANNEL_0; + #endif + } + #endif +} - DMAtx.Init.Direction = DMA_MEMORY_TO_PERIPH; - DMAtx.Init.PeriphInc = DMA_PINC_DISABLE; - DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; - DMAtx.Init.Mode = DMA_NORMAL; - DMAtx.Init.Priority = DMA_PRIORITY_LOW; - #ifdef STM32F4xx - DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; +void TFT_SPI::HALDismantle(void) +{ + #ifdef SPI1_BASE + if (SPIx.Instance == SPI1) { + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); + __HAL_RCC_SPI1_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_DISABLE(); + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_DISABLE(); + #endif + } + #endif + + #ifdef SPI2_BASE + if (SPIx.Instance == SPI2) { + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); + __HAL_RCC_SPI2_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_DISABLE(); + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_DISABLE(); + #endif + } + #endif + + #ifdef SPI3_BASE + if (SPIx.Instance == SPI3) { + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); + __HAL_RCC_SPI3_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_DISABLE(); + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_DISABLE(); + #endif + } + #endif + + #ifdef SPI4_BASE + if (SPIx.Instance == SPI4) { + __HAL_RCC_SPI4_FORCE_RESET(); + __HAL_RCC_SPI4_RELEASE_RESET(); + __HAL_RCC_SPI4_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_DISABLE(); + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_DISABLE(); + #endif #endif } -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.Init.DataSize = DataSize == DATASIZE_8BIT ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT; +void TFT_SPI::DataTransferBegin(uint16_t DataSize, eSPIMode spiMode) { + HALPrepare(spiMode); + SPIx.Init.DataSize = ( DataSize == DATASIZE_8BIT ) ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT; HAL_SPI_Init(&SPIx); WRITE(TFT_CS_PIN, LOW); + active_transfer = true; +} + +void TFT_SPI::DataTransferEnd(void) +{ + // TODO: apply strong integrity to the active_transfer variable! + HAL_SPI_DeInit(&SPIx); + HALDismantle(); + WRITE(TFT_CS_PIN, HIGH); + active_transfer = false; } #ifdef TFT_DEFAULT_DRIVER @@ -148,11 +356,9 @@ uint32_t TFT_SPI::GetID() { uint32_t TFT_SPI::ReadID(uint16_t Reg) { uint32_t Data = 0; #if PIN_EXISTS(TFT_MISO) - uint32_t BaudRatePrescaler = SPIx.Init.BaudRatePrescaler; uint32_t i; - SPIx.Init.BaudRatePrescaler = SPIx.Instance == SPI1 ? SPI_BAUDRATEPRESCALER_8 : SPI_BAUDRATEPRESCALER_4; - DataTransferBegin(DATASIZE_8BIT); + DataTransferBegin(DATASIZE_8BIT, eSPIMode::READ); WriteReg(Reg); if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_RX(&SPIx); @@ -171,44 +377,63 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { __HAL_SPI_DISABLE(&SPIx); DataTransferEnd(); - - SPIx.Init.BaudRatePrescaler = BaudRatePrescaler; #endif return Data >> 7; } bool TFT_SPI::isBusy() { - #ifdef STM32F1xx - volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; - #elif defined(STM32F4xx) - volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; - #endif - if (dmaEnabled) { - if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) + if (active_dma) + { + #ifdef STM32F1xx + volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; + #elif defined(STM32F4xx) + volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; + #endif + #if 0 + if (dmaEnabled) { + if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) + Abort(); + } + else Abort(); + #endif + return dmaEnabled; } else + { + #if 0 Abort(); - return dmaEnabled; + #endif + return false; + } } void TFT_SPI::Abort() { - // Wait for any running spi - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} - while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} - // First, abort any running dma - HAL_DMA_Abort(&DMAtx); - // DeInit objects - HAL_DMA_DeInit(&DMAtx); - HAL_SPI_DeInit(&SPIx); - // Deselect CS - DataTransferEnd(); + if (active_transfer) + { + // Wait for any running spi + while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { } + while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) { } + if (active_dma) + { + // First, abort any running dma + HAL_DMA_Abort(&DMAtx); + HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + // DeInit objects + HAL_DMA_DeInit(&DMAtx); + active_dma = false; + } + // Deselect CS + DataTransferEnd(); + } } void TFT_SPI::Transmit(uint16_t Data) { +#if PIN_EXISTS(TFT_MISO) if (TFT_MISO_PIN == TFT_MOSI_PIN) SPI_1LINE_TX(&SPIx); +#endif __HAL_SPI_ENABLE(&SPIx); @@ -217,28 +442,36 @@ void TFT_SPI::Transmit(uint16_t Data) { while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} +#if PIN_EXISTS(TFT_MISO) if (TFT_MISO_PIN != TFT_MOSI_PIN) __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read +#endif } void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { + // Wait last dma finish, to start another while (isBusy()) { /* nada */ } - DMAtx.Init.MemInc = MemoryIncrease; - HAL_DMA_Init(&DMAtx); - +#if PIN_EXISTS(TFT_MISO) if (TFT_MISO_PIN == TFT_MOSI_PIN) SPI_1LINE_TX(&SPIx); +#endif DataTransferBegin(); + DMAtx.Init.MemInc = MemoryIncrease; + HAL_DMA_Init(&DMAtx); + active_dma = true; + HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); + __HAL_SPI_ENABLE(&SPIx); SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + Abort(); } @@ -246,14 +479,17 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun void TFT_SPI::TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DMAtx.Init.MemInc = MemoryIncrease; - HAL_DMA_Init(&DMAtx); - +#if PIN_EXISTS(TFT_MISO) if (TFT_MISO_PIN == TFT_MOSI_PIN) SPI_1LINE_TX(&SPIx); +#endif DataTransferBegin(); + DMAtx.Init.MemInc = MemoryIncrease; + HAL_DMA_Init(&DMAtx); + active_dma = true; + HAL_NVIC_SetPriority(DMA2_Stream3_IRQn, 5, 0); HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); HAL_DMA_Start_IT(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index de051e229459..ce853c968880 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -41,6 +41,13 @@ #define TFT_IO_DRIVER TFT_SPI class TFT_SPI { + + enum class eSPIMode + { + READ, + WRITE + }; + private: static SPI_HandleTypeDef SPIx; @@ -52,6 +59,19 @@ class TFT_SPI { static void TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); #endif + static void HALPrepare(eSPIMode spiMode); + static void HALDismantle(void); + + static uint8_t _GetClockDivider( uint32_t spibasefreq, uint32_t speed ); + +#if PIN_EXISTS(TFT_MISO) + static uint8_t clkdiv_read; +#endif + static uint8_t clkdiv_write; + + static bool active_transfer; + static bool active_dma; + public: static DMA_HandleTypeDef DMAtx; @@ -60,8 +80,8 @@ class TFT_SPI { static bool isBusy(); static void Abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); - static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); }; + static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT, eSPIMode spiMode = eSPIMode::WRITE); + static void DataTransferEnd(); static void DataTransferAbort(); static void WriteData(uint16_t Data) { Transmit(Data); } diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index cf4a8f18e9ac..f4edb3af2942 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -35,6 +35,46 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } SPI_HandleTypeDef XPT2046::SPIx; +uint8_t XPT2046::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) +{ + if ( speed >= (spibasefreq / 2) ) + { + return SPI_BAUDRATEPRESCALER_2; + } + else if ( speed >= (spibasefreq / 4) ) + { + return SPI_BAUDRATEPRESCALER_4; + } + else if ( speed >= (spibasefreq / 8) ) + { + return SPI_BAUDRATEPRESCALER_8; + } + else if ( speed >= (spibasefreq / 16) ) + { + return SPI_BAUDRATEPRESCALER_16; + } + else if ( speed >= (spibasefreq / 32) ) + { + return SPI_BAUDRATEPRESCALER_32; + } + else if ( speed >= (spibasefreq / 64) ) + { + return SPI_BAUDRATEPRESCALER_64; + } + else if ( speed >= (spibasefreq / 128) ) + { + return SPI_BAUDRATEPRESCALER_128; + } + else + { + return SPI_BAUDRATEPRESCALER_256; + } +} + +extern "C" { + #include +} + void XPT2046::Init() { SPI_TypeDef *spiInstance; @@ -49,14 +89,37 @@ void XPT2046::Init() { if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI)) spiInstance = NP; if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO)) spiInstance = NP; - SPIx.Instance = spiInstance; + SPIx.Instance = spiInstance; + + if (spiInstance) { + uint8_t clkdiv; +#ifdef TOUCH_BAUDRATE + spi_t tmp_spi; + tmp_spi.pin_sclk = digitalPinToPinName(TOUCH_SCK_PIN); + uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); + + clkdiv = _GetClockDivider(spibasefreq, TOUCH_BAUDRATE); +#else + bool has_clkdiv = false; + + #ifdef SPI1_BASE + if (spiInstance == SPI1) + { + clkdiv = SPI_BAUDRATEPRESCALER_16; + has_clkdiv = true; + } + #endif + if ( !has_clkdiv ) + { + clkdiv = SPI_BAUDRATEPRESCALER_8; + } +#endif - if (SPIx.Instance) { SPIx.State = HAL_SPI_STATE_RESET; SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; SPIx.Init.Direction = SPI_DIRECTION_2LINES; - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; + SPIx.Init.BaudRatePrescaler = clkdiv; SPIx.Init.CLKPhase = SPI_PHASE_2EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_HIGH; SPIx.Init.DataSize = SPI_DATASIZE_8BIT; @@ -64,30 +127,8 @@ void XPT2046::Init() { SPIx.Init.TIMode = SPI_TIMODE_DISABLE; SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; SPIx.Init.CRCPolynomial = 10; - - pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); - pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI); - pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO); - - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_CLK_ENABLE(); - SPIx.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; - } - #endif - #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_CLK_ENABLE(); - } - #endif - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_CLK_ENABLE(); - } - #endif } else { - SPIx.Instance = nullptr; SET_INPUT(TOUCH_MISO_PIN); SET_OUTPUT(TOUCH_MOSI_PIN); SET_OUTPUT(TOUCH_SCK_PIN); @@ -96,6 +137,124 @@ void XPT2046::Init() { getRawData(XPT2046_Z1); } +void XPT2046::HALPrepare(void) +{ + pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); + pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI); + pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO); + + pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TOUCH_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TOUCH_SCK_PIN)), GPIO_PULLDOWN); + + #ifdef SPI1_BASE + if (SPIx.Instance == SPI1) { + __HAL_RCC_SPI1_CLK_ENABLE(); + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); + } + #endif + #ifdef SPI2_BASE + if (SPIx.Instance == SPI2) { + __HAL_RCC_SPI2_CLK_ENABLE(); + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); + } + #endif + #ifdef SPI3_BASE + if (SPIx.Instance == SPI3) { + __HAL_RCC_SPI3_CLK_ENABLE(); + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); + } + #endif + #ifdef SPI4_BASE + if (SPIx.Instance == SPI4) { + __HAL_RCC_SPI4_CLK_ENABLE(); + __HAL_RCC_SPI4_FORCE_RESET(); + __HAL_RCC_SPI4_RELEASE_RESET(); + } + #endif + #ifdef SPI5_BASE + if (SPIx.Instance == SPI5) { + __HAL_RCC_SPI5_CLK_ENABLE(); + __HAL_RCC_SPI5_FORCE_RESET(); + __HAL_RCC_SPI5_RELEASE_RESET(); + } + #endif + #ifdef SPI6_BASE + if (SPIx.Instance == SPI6) { + __HAL_RCC_SPI6_CLK_ENABLE(); + __HAL_RCC_SPI6_FORCE_RESET(); + __HAL_RCC_SPI6_RELEASE_RESET(); + } + #endif +} + +void XPT2046::HALDismantle(void) +{ + #ifdef SPI1_BASE + if (SPIx.Instance == SPI1) { + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); + __HAL_RCC_SPI1_CLK_DISABLE(); + } + #endif + #ifdef SPI2_BASE + if (SPIx.Instance == SPI2) { + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); + __HAL_RCC_SPI2_CLK_DISABLE(); + } + #endif + #ifdef SPI3_BASE + if (SPIx.Instance == SPI3) { + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); + __HAL_RCC_SPI3_CLK_DISABLE(); + } + #endif + #ifdef SPI4_BASE + if (SPIx.Instance == SPI4) { + __HAL_RCC_SPI4_FORCE_RESET(); + __HAL_RCC_SPI4_RELEASE_RESET(); + __HAL_RCC_SPI4_CLK_DISABLE(); + } + #endif + #ifdef SPI5_BASE + if (SPIx.Instance == SPI5) { + __HAL_RCC_SPI5_FORCE_RESET(); + __HAL_RCC_SPI5_RELEASE_RESET(); + __HAL_RCC_SPI5_CLK_DISABLE(); + } + #endif + #ifdef SPI6_BASE + if (SPIx.Instance == SPI6) { + __HAL_RCC_SPI6_FORCE_RESET(); + __HAL_RCC_SPI6_RELEASE_RESET(); + __HAL_RCC_SPI6_CLK_DISABLE(); + } + #endif +} + +void XPT2046::DataTransferBegin(void) + { + if (SPIx.Instance) + { + HALPrepare(); + HAL_SPI_Init(&SPIx); + } + WRITE(TOUCH_CS_PIN, LOW); +} + +void XPT2046::DataTransferEnd(void) +{ + WRITE(TOUCH_CS_PIN, HIGH); + if (SPIx.Instance) + { + HAL_SPI_DeInit(&SPIx); + HALDismantle(); + } +} + bool XPT2046::isTouched() { return isBusy() ? false : ( #if PIN_EXISTS(TOUCH_INT) diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 71de6b00251b..87f09063f683 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -64,17 +64,22 @@ class XPT2046 { private: static SPI_HandleTypeDef SPIx; + static uint8_t _GetClockDivider(uint32_t spibasefreq, uint32_t speed); + static bool isBusy() { return false; } static uint16_t getRawData(const XPTCoordinate coordinate); static bool isTouched(); - static void DataTransferBegin() { if (SPIx.Instance) { HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; + static void DataTransferBegin(); + static void DataTransferEnd(); static uint16_t HardwareIO(uint16_t data); static uint16_t SoftwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); } + static void HALPrepare(void); + static void HALDismantle(void); + public: static void Init(); static bool getRawPoint(int16_t *x, int16_t *y); diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index b21eca30b292..ebab8e9497e3 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1481,6 +1481,11 @@ #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 #define TFT_INTERFACE_SPI + #define TFT_BAUDRATE_READ 8000000 // Hz + #define TFT_BAUDRATE_WRITE 32000000 // Hz + #if defined(MKS_TS35_V2_0) && defined(TOUCH_SCREEN) + #define TFT_TOUCH_DEVICE_XPT2046 + #endif #elif EITHER(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 @@ -1623,6 +1628,9 @@ #undef TOUCH_SCREEN_CALIBRATION #undef TOUCH_CALIBRATION_AUTO_SAVE #endif + #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && ENABLED(TFT_INTERFACE_SPI) + #define TOUCH_BAUDRATE 2500000 // Hz + #endif #if !HAS_GRAPHICAL_TFT #undef TOUCH_SCREEN #if ENABLED(TFT_CLASSIC_UI) diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index acb78c3e6e9f..6f6d0f74da6a 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -166,6 +166,8 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym switch (lcd_id) { case LTDC_RGB: + io.DataTransferBegin(DATASIZE_8BIT); + io.WriteReg(0x01); io.WriteData(Xmin); io.WriteReg(0x02); @@ -175,6 +177,8 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym io.WriteReg(0x04); io.WriteData(Ymax); io.WriteReg(0x00); + + io.DataTransferEnd(); break; case ST7735: // ST7735 160x128 case ST7789: // ST7789V 320x240 @@ -201,6 +205,8 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym // RAMWR: Memory Write io.WriteReg(ILI9341_RAMWR); + + io.DataTransferEnd(); break; case R61505: // R61505U 320x240 case ILI9328: // ILI9328 320x240 @@ -222,12 +228,12 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym io.WriteData(Xmin); io.WriteReg(ILI9328_RAMWR); + + io.DataTransferEnd(); break; default: break; } - - io.DataTransferEnd(); } void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { @@ -243,7 +249,7 @@ void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { continue; } data = *Sequence++; - if (data == 0x7FFF) return; + if (data == 0x7FFF) break; if (data == 0xFFFF) io.WriteData(0xFFFF); else if (data & 0x8000) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 642c97bb1144..497e5e561259 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -53,16 +53,26 @@ // // Limit Switches // +#ifndef NO_STOP_PINS +#if !defined(X_STOP_PIN) #define X_STOP_PIN PA12 +#endif +#if !defined(Y_STOP_PIN) #define Y_STOP_PIN PA11 +#endif +#if !defined(Z_STOP_PIN) #define Z_STOP_PIN PC6 +#endif +#endif // // Z Probe // +#if HAS_BED_PROBE #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PB1 #endif +#endif // // Steppers @@ -180,15 +190,16 @@ #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) #if ENABLED(MKS_MINI_12864) + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define LCD_BACKLIGHT_PIN -1 #define LCD_RESET_PIN -1 #define DOGLCD_A0 EXP1_07_PIN @@ -198,6 +209,12 @@ #elif ENABLED(FYSETC_MINI_12864_2_1) + #define BTN_ENC EXP1_02_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define LCD_PINS_DC EXP1_04_PIN #define DOGLCD_CS EXP1_03_PIN #define DOGLCD_A0 LCD_PINS_DC @@ -210,6 +227,38 @@ #define SOFTWARE_SPI //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + #elif ENABLED(MKS_TS35_V2_0) + + // DISPLAY PINS. + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN + + // SPI BUS PINS. + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN -1 // has to be custom soldered to work! + #define TFT_MOSI_PIN EXP2_06_PIN + #define TOUCH_SCK_PIN TFT_SCK_PIN + #define TOUCH_MISO_PIN EXP2_01_PIN + #define TOUCH_MOSI_PIN TFT_MOSI_PIN + + // SPI BUS CHIP-SELECT PINS. + #define TFT_CS_PIN EXP1_07_PIN + #define TOUCH_CS_PIN EXP1_05_PIN + + #define TOUCH_INT_PIN EXP1_06_PIN + + // Disable any LCD related PINs config + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 + + #ifndef TFT_BUFFERSIZE + #define TFT_BUFFER_SIZE 1200 + #endif + #ifndef TFT_QUEUE_SIZE + #define TFT_QUEUE_SIZE 6144 + #endif + #else #define LCD_PINS_D4 EXP1_05_PIN @@ -262,4 +311,4 @@ #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN #define SD_MOSI_PIN EXP2_06_PIN -#define SD_SS_PIN EXP2_04_PIN +#define SD_SS_PIN EXP2_04_PIN \ No newline at end of file From 9096c4b7fdb58b4e3284257c5b20ff423d0e09c1 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 20 Oct 2022 21:06:01 +0200 Subject: [PATCH 02/83] - fixed SPI bus support across the board, so it is possible to have TMC drivers on the same SPI bus as TFT, Touch, SD, etc brought to you by Martin Turski, company owner of EirDev (turningtides@outlook.de). In this commit the SPI support has been improved in all of Marlin - across ALL the boards! - so that the big problem of connecting peripherals on the same SPI bus is tackled. I have tested the commit on my MKS Makerbase Robin E3D V1.1 board and all SPI components have successfully initialized, are successfully communicating and it works quite nicely. I invite you to test your own board using this commit. I tested the TMC2130 drivers in SPI mode and there is no issue when using them. Also connected as a MKS Makerbase TS35-R V2.0 screen. Have fun! --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 5 +++++ Marlin/src/HAL/DUE/HAL_SPI.cpp | 10 +++++++++ Marlin/src/HAL/DUE/inc/SanityCheck.h | 2 +- Marlin/src/HAL/ESP32/HAL_SPI.cpp | 3 +++ Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp | 4 +++- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 5 +++++ Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 2 +- .../u8g/u8g_com_HAL_LPC1768_hw_spi.cpp | 1 + .../u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 1 + Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 4 ++++ Marlin/src/HAL/STM32/HAL_SPI.cpp | 11 +++++++++- Marlin/src/HAL/STM32/MarlinSPI.cpp | 4 ++++ Marlin/src/HAL/STM32/MarlinSPI.h | 2 +- Marlin/src/HAL/STM32F1/HAL_SPI.cpp | 4 ++++ Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 4 ++++ Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 4 ++++ Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 4 ++++ Marlin/src/HAL/shared/HAL_SPI.h | 3 +++ Marlin/src/MarlinCore.cpp | 3 --- Marlin/src/feature/tmc_util.h | 8 +++---- Marlin/src/module/stepper/trinamic.cpp | 4 ++-- Marlin/src/module/temperature.cpp | 5 +++++ Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 20 ++++++++---------- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 20 ++++++++---------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 8 +++---- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 20 ++++++++---------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 20 ++++++++---------- Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 18 +++++++--------- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 20 ++++++++---------- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 20 ++++++++---------- .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 20 ++++++++---------- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 20 ++++++++---------- Marlin/src/pins/lpc1769/pins_FLY_CDY.h | 20 ++++++++---------- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 20 ++++++++---------- Marlin/src/pins/pinsDebug_list.h | 12 +++++------ Marlin/src/pins/ramps/pins_RAMPS.h | 20 ++++++++---------- Marlin/src/pins/ramps/pins_RAMPS_S_12.h | 20 ++++++++---------- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 16 +++++++------- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 20 ++++++++---------- Marlin/src/pins/sam/pins_ARCHIM2.h | 20 ++++++++---------- Marlin/src/pins/samd/pins_RAMPS_144.h | 20 ++++++++---------- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 20 ++++++++---------- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 19 ++++++++--------- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 18 +++++++--------- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h | 20 ++++++++---------- .../pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h | 21 +++++++++---------- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 20 ++++++++---------- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 20 ++++++++---------- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 20 ++++++++---------- Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h | 20 ++++++++---------- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 20 ++++++++---------- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 20 ++++++++---------- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 20 ++++++++---------- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 20 ++++++++---------- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 20 ++++++++---------- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 20 ++++++++---------- Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h | 20 ++++++++---------- Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h | 20 ++++++++---------- .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 18 +++++++--------- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 20 ++++++++---------- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 20 ++++++++---------- Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h | 6 +++--- .../src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h | 6 +++--- .../src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h | 6 +++--- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 18 +++++++--------- .../pins/stm32h7/pins_BTT_SKR_SE_BX_common.h | 20 ++++++++---------- .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 20 ++++++++---------- Marlin/src/sd/Sd2Card.cpp | 1 + .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 8 +++++-- 69 files changed, 460 insertions(+), 468 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index dc98f2f79e71..6c813f7b8700 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -81,6 +81,10 @@ void spiBegin() { SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X); } + void spiClose() { + // nop. + } + /** SPI receive a byte */ uint8_t spiRec() { SPDR = 0xFF; @@ -186,6 +190,7 @@ void spiBegin() { #define nop asm volatile ("\tnop\n") void spiInit(uint8_t) { /* do nothing */ } + void spiClose() { /* do nothing */ } // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index f5bcaacee505..47181b018057 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -521,6 +521,8 @@ WRITE(SD_SCK_PIN, LOW); } + void spiClose() {} + /** Begin SPI transaction, set clock, bit order, data mode */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // TODO: to be implemented @@ -568,6 +570,10 @@ spiInitialized = true; } + void spiClose() { + // TODO? + } + void spiBegin() { if (spiInitialized) return; @@ -783,6 +789,10 @@ SPI0->SPI_CSR[0] = SPI_CSR_SCBR(spiDivider[1]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW; // U8G default to 4MHz } + void spiClose() { + // TODO? + } + void spiBegin() { spiInit(); } static uint8_t spiTransfer(uint8_t data) { diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 1f5acc360c72..1de13600e7f9 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -64,7 +64,7 @@ * Usually the hardware SPI pins are only available to the LCD. This makes the DUE hard SPI used at the same time * as the TMC2130 soft SPI the most common setup. */ -#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SW_##P == SD_MOSI_PIN || TMC_SW_##P == SD_MISO_PIN || TMC_SW_##P == SD_SCK_PIN)) +#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SPI_##P == SD_MOSI_PIN || TMC_SPI_##P == SD_MISO_PIN || TMC_SPI_##P == SD_SCK_PIN)) #if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130) #if ENABLED(TMC_USE_SW_SPI) diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 868ab1b6712d..b39df72c630a 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -76,6 +76,9 @@ void spiInit(uint8_t spiRate) { SPI.begin(); } +void spiClose() { +} + uint8_t spiRec() { SPI.beginTransaction(spiConfig); uint8_t returnByte = SPI.transfer(0xFF); diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index bd7ecdc9f217..25143044afdf 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -63,7 +63,9 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt } switch (msg) { - case U8G_COM_MSG_STOP: break; + case U8G_COM_MSG_STOP: + spiClose(); + break; case U8G_COM_MSG_INIT: OUT_WRITE(DOGLCD_CS, HIGH); diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 29f9b43afef0..6d1be8d1548f 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -80,6 +80,9 @@ SPI_speed = swSpiInit(spiRate, SD_SCK_PIN, SD_MOSI_PIN); } + void spiClose() { + } + uint8_t spiRec() { return spiTransfer(0xFF); } void spiRead(uint8_t*buf, uint16_t nbyte) { @@ -123,6 +126,8 @@ SPI.begin(); } + void spiClose() { SPI.end(); } + static uint8_t doio(uint8_t b) { return SPI.transfer(b & 0x00FF) & 0x00FF; } diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 8265d58a6e8f..453b5631d5cc 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -95,7 +95,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #if USING_HW_SERIAL0 #define IS_TX0(P) (P == P0_02) #define IS_RX0(P) (P == P0_03) - #if IS_TX0(TMC_SW_MISO) || IS_RX0(TMC_SW_MOSI) + #if IS_TX0(TMC_SPI_MISO) || IS_RX0(TMC_SPI_MOSI) #error "Serial port pins (0) conflict with Trinamic SPI pins!" #elif HAS_PRUSA_MMU1 && (IS_TX0(E_MUX1_PIN) || IS_RX0(E_MUX0_PIN)) #error "Serial port pins (0) conflict with Multi-Material-Unit multiplexer pins!" diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 0118f92847de..6a4bf5cea44e 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -73,6 +73,7 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { switch (msg) { case U8G_COM_MSG_STOP: + spiClose(); break; case U8G_COM_MSG_INIT: diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index ce7b33801931..b6b4018dc699 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -94,6 +94,7 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar break; case U8G_COM_MSG_STOP: + spiClose(); break; case U8G_COM_MSG_RESET: diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 77f4d5ecd513..2d6123911c31 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -82,6 +82,10 @@ sdSPI.begin(); } + void spiClose() { + sdSPI.end(); + } + /** * @brief Receives a single byte from the SPI port. * diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 40d320d5e822..5ddeb0016cea 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -81,6 +81,10 @@ static SPISettings spiConfig; SPI.begin(); } + void spiClose() { + SPI.end(); + } + // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } @@ -171,7 +175,12 @@ static SPISettings spiConfig; SPI.setMOSI(SD_MOSI_PIN); SPI.setSCLK(SD_SCK_PIN); - SPI.begin(); + SPI.beginTransaction(spiConfig); + } + + void spiClose() { + // Terminates SPI activity. + SPI.end(); } /** diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index f7c603d77e5c..0c9e107b2d22 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -47,6 +47,10 @@ void MarlinSPI::begin(void) { spi_init(&_spi, _speed, _dataMode, _bitOrder, _dataSize); } +void MarlinSPI::end(void) { + spi_deinit(&_spi); +} + void MarlinSPI::setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc) { _dmaHandle.Init.Direction = direction; _dmaHandle.Init.PeriphInc = DMA_PINC_DISABLE; diff --git a/Marlin/src/HAL/STM32/MarlinSPI.h b/Marlin/src/HAL/STM32/MarlinSPI.h index fbd3585ff447..81430eff2be8 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.h +++ b/Marlin/src/HAL/STM32/MarlinSPI.h @@ -67,7 +67,7 @@ class MarlinSPI { } void begin(void); - void end(void) {} + void end(void); byte transfer(uint8_t _data); uint8_t dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length); diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index abb348d743c5..678cc1d7cbef 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -102,6 +102,10 @@ void spiInit(uint8_t spiRate) { SPI.setDataMode(SPI_MODE0); } +void spiClose() { + SPI.end(); +} + /** * @brief Receive a single byte from the SPI port. * diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 415c69222986..355186dfe8b7 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -70,6 +70,10 @@ void spiInit(uint8_t spiRate) { SPI.begin(); } +void spiClose() { + SPI.end(); +} + // SPI receive a byte uint8_t spiRec() { SPI.beginTransaction(spiConfig); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index d80f57b2c436..312da3db5914 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -70,6 +70,10 @@ void spiInit(uint8_t spiRate) { SPI.begin(); } +void spiClose() { + SPI.end(); +} + uint8_t spiRec() { SPI.beginTransaction(spiConfig); uint8_t returnByte = SPI.transfer(0xFF); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 9dcb812faf0c..534bd73b6d8f 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -85,6 +85,10 @@ void spiInit(uint8_t spiRate) { SPI.begin(); } +void spiClose() { + SPI.end(); +} + uint8_t spiRec() { SPI.beginTransaction(spiConfig); uint8_t returnByte = SPI.transfer(0xFF); diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 6611f9ec4e0f..3b1c83f57050 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -64,6 +64,9 @@ void spiBegin(); // Configure SPI for specified SPI speed void spiInit(uint8_t spiRate); +// Terminates SPI connection. +void spiClose(); + // Write single byte to SPI void spiSend(uint8_t b); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index ea57e3ccd782..142a1daee579 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1247,9 +1247,6 @@ void setup() { #endif #if HAS_TMC_SPI - #if DISABLED(TMC_USE_SW_SPI) - SETUP_RUN(SPI.begin()); - #endif SETUP_RUN(tmc_init_cs_pins()); #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index c10bab62749d..393b556f2833 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -91,11 +91,11 @@ class TMCMarlin : public TMC, public TMCStorage { TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t axis_chain_index) : TMC(cs_pin, RS, axis_chain_index) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index, bool softSPI) : + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index, softSPI) {} uint16_t rms_current() { return TMC::rms_current(); } void rms_current(uint16_t mA) { diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index bf36f83cd872..9bf10e83553f 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -46,9 +46,9 @@ enum StealthIndex : uint8_t { // AI = Axis Enum Index // SWHW = SW/SH UART selection #if ENABLED(TMC_USE_SW_SPI) - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SW_MOSI, TMC_SW_MISO, TMC_SW_SCK, ST##_CHAIN_POS) + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, true) #else - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, false) #endif #if ENABLED(TMC_SERIAL_MULTIPLEXER) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 349264606aec..e7b63e0355a5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3059,6 +3059,11 @@ void Temperature::disable_all_heaters() { if (i > 0) max_tc_temp <<= 8; // shift left if not the last byte } + #if !HAS_MAXTC_SW_SPI + // Need to terminate our work. + spiClose(); + #endif + MAXTC_CS_WRITE(HIGH); // Disable MAXTC #else #if HAS_MAX6675_LIBRARY diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 3616b7a27c43..5a43ee85ac28 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -247,18 +247,16 @@ #endif /** - * Default pins for TMC software SPI + * Default pins for TMC SPI */ -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 66 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index 10a610ff95f7..783a207b083d 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -77,18 +77,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_18 // ETH - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_17 // ETH - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_15 // ETH - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_18 // ETH +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_17 // ETH +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_15 // ETH #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index d11224315bb7..2006900bae5b 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -164,11 +164,11 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. - #define TMC_USE_SW_SPI - #define TMC_SW_MOSI EXP2_06_PIN - #define TMC_SW_MISO EXP2_01_PIN + //#define TMC_USE_SW_SPI + #define TMC_SPI_MOSI EXP2_06_PIN + #define TMC_SPI_MISO EXP2_01_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SW_SCK EXP2_02_PIN + #define TMC_SPI_SCK EXP2_02_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. //#define TMC_SW_SCK P2_06 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 031a42f7989c..85d7d0f16ecb 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -137,18 +137,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P4_28 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index aac839808119..644ca80651c5 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -194,18 +194,16 @@ #define TEMP_BED_PIN P0_25_A2 // A2 (T2) - (69) - TEMP_BED_PIN // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_17 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_17 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index cf12a98aef28..33b22522b4ca 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -300,16 +300,14 @@ // Hardware SPI is on EXP2. See if you can make it work: // https://github.com/makerbase-mks/MKS-SBASE/issues/25 #define TMC_USE_SW_SPI - #if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_03 // AUX1 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_02 // AUX1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_26 // TH4 - #endif + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_03 // AUX1 + #endif + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_02 // AUX1 + #endif + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_26 // TH4 #endif #endif diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 4e9f98c85285..b365e7c9583c 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -132,18 +132,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P4_28 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P4_28 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index fe424c800a5a..4952a07c3b1e 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -97,18 +97,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_00 // ETH - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_08 // ETH - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_09 // ETH - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_00 // ETH +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_08 // ETH +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_09 // ETH #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index 237dfaec36fb..f9755f8677a5 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -68,18 +68,16 @@ #define E0_CS_PIN P1_04 // Ethernet Expansion - Pin 12 // -// Default pins for TMC software SPI +// Default pins for TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index ea2e0b708251..3997cccec2d3 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -85,18 +85,16 @@ #define E2_CS_PIN P1_18 // FET 6 // -// Default pins for TMC software SPI +// Default pins for TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 // Ethernet Expansion - Pin 5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P1_17 // Ethernet Expansion - Pin 6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P1_08 // Ethernet Expansion - Pin 7 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index ec0b14af9043..f0d904811dd9 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -92,18 +92,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P0_20 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_19 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_21 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P0_20 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_19 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_21 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 2f25d8b5fdd3..358a1d87b1f6 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -146,18 +146,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI P1_16 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO P0_05 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK P0_04 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI P1_16 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO P0_05 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 077c94a60f8c..8d18e41bf108 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -489,14 +489,14 @@ REPORT_NAME_DIGITAL(__LINE__, EXP3_10_PIN) #endif -#if _EXISTS(TMC_SW_MISO) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_MISO) +#if _EXISTS(TMC_SPI_MISO) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_MISO) #endif -#if _EXISTS(TMC_SW_MOSI) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_MOSI) +#if _EXISTS(TMC_SPI_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_MOSI) #endif -#if _EXISTS(TMC_SW_SCK) - REPORT_NAME_DIGITAL(__LINE__, TMC_SW_SCK) +#if _EXISTS(TMC_SPI_SCK) + REPORT_NAME_DIGITAL(__LINE__, TMC_SPI_SCK) #endif #if _EXISTS(TFTGLCD_CS) REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_CS) diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index a0edb01a2a36..b9dbd2a531a5 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -311,18 +311,16 @@ #endif // -// TMC software SPI +// TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 66 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index f41573b527cd..2d28ec87552d 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -216,18 +216,16 @@ #endif // -// TMC software SPI +// TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 51 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 50 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 53 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 51 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 50 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 53 #endif // diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index f81cc6039aed..779a21ebd7f9 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -148,19 +148,17 @@ #endif // -// Default pins for TMC software SPI +// Default pins for TMC SPI // -//#if ENABLED(TMC_USE_SW_SPI) -// #ifndef TMC_SW_MOSI -// #define TMC_SW_MOSI 66 +// #ifndef TMC_SPI_MOSI +// #define TMC_SPI_MOSI 66 // #endif -// #ifndef TMC_SW_MISO -// #define TMC_SW_MISO 44 +// #ifndef TMC_SPI_MISO +// #define TMC_SPI_MISO 44 // #endif -// #ifndef TMC_SW_SCK -// #define TMC_SW_SCK 64 +// #ifndef TMC_SPI_SCK +// #define TMC_SPI_SCK 64 // #endif -//#endif // // Temperature Sensors diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index b68e3edb4567..0ddb1f69a431 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -180,18 +180,16 @@ #endif // -// TMC software SPI +// TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 66 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 64 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 66 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 310dd8e2ac27..4c0330e51285 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -145,19 +145,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers. +// SPI pins for TMC2130 stepper drivers. // Required for the Archim2 board. // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 28 // PD3 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 26 // PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 27 // PD2 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 28 // PD3 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 26 // PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 27 // PD2 #endif // diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 2c42506a5f4d..e70c69ef82e9 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -164,18 +164,16 @@ #endif // -// TMC software SPI +// TMC SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI 58 // Mega/Due:66 - AGCM4:58 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO 44 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK 56 // Mega/Due:64 - AGCM4:56 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI 58 // Mega/Due:66 - AGCM4:58 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO 44 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK 56 // Mega/Due:64 - AGCM4:56 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index f9c9de4f031e..3845645abb68 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -94,18 +94,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 4e343fa8cdff..ce1d0d66d72d 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -68,16 +68,15 @@ #define E0_DIR_PIN PB0 #define E0_ENABLE_PIN PC4 -#if ENABLED(TMC_USE_SW_SPI) // Shared with EXP2 - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif +// Shared with EXP2 +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 #endif #if HAS_TMC_UART // Shared with EXP1 diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index f39850f755f1..665ca0402536 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -83,16 +83,14 @@ #define E0_CS_PIN PC2 #endif -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_06_PIN - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_01_PIN - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_02_PIN - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI EXP2_06_PIN +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO EXP2_01_PIN +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK EXP2_02_PIN #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index 77c2b792157a..c158e619d08e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -50,18 +50,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h index 2ad68a01405c..29118ae53f8f 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -50,18 +50,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers +// Software and hardware actually, they are connected to SPI2 bus. // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_V1_1_common.h" // ... MKS_ROBIN_E3_common diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 89525d93ef48..8d48bcca4764 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -112,18 +112,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 8dba94313651..712b7773ab8a 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -122,18 +122,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index 048570102baf..b5341082f4ea 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -105,18 +105,16 @@ #define E2_CS_PIN PG9 #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index ed602d8d011e..d03e38f05151 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -88,18 +88,16 @@ #define E0_DIR_PIN PB14 // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 2147dd9b4fa7..5cdf4d00d27c 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -108,18 +108,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB13 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index fe03ec8983ff..d1ac2557bde8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -202,18 +202,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PG15 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PG15 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index 35287050b891..e001c2c0413a 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -260,18 +260,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PA7 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PA5 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 78a137b35d4d..8265f170861e 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -172,18 +172,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PC12 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PC11 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PC10 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC12 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PC11 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC10 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 7ac9156f405b..52ab56e5c48f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -272,18 +272,16 @@ #endif // SPINDLE_FEATURE || LASER_FEATURE // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA14 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE15 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA14 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE15 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index 8d5e094122f4..f0c9d0c16a95 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -235,18 +235,16 @@ #endif // -// Trinamic Software SPI +// Trinamic SPI // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_SCK - #define TMC_SW_SCK EXP2_02_PIN - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO EXP2_01_PIN - #endif - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI EXP2_06_PIN - #endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK EXP2_02_PIN +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO EXP2_01_PIN +#endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI EXP2_06_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index a9ce1383d8ca..f42672c96cec 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -53,19 +53,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // #define TMC_USE_SW_SPI -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE13 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE12 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #include "pins_FYSETC_S6.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index 009bfb248dfe..7c702106cdfe 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -101,19 +101,17 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // #define TMC_USE_SW_SPI -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE13 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE12 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #if HOTENDS > 3 || E_STEPPERS > 3 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 8a9b72225d79..416fece66aad 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -134,16 +134,14 @@ #if HAS_TMC_SPI #define TMC_USE_SW_SPI #endif -#if ENABLED(TMC_USE_SW_SPI) - #if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1 - #define TMC_SW_MOSI PE14 - #endif - #if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1 - #define TMC_SW_MISO PE13 - #endif - #if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1 - #define TMC_SW_SCK PE12 - #endif +#if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 + #define TMC_SPI_MOSI PE14 +#endif +#if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 + #define TMC_SPI_MISO PE13 +#endif +#if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 + #define TMC_SPI_SCK PE12 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 32d8a47488b9..6029f1c91b33 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -51,22 +51,20 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // This board only supports SW SPI for stepper drivers // #if HAS_TMC_SPI #define TMC_USE_SW_SPI #endif -#if ENABLED(TMC_USE_SW_SPI) - #if !defined(TMC_SW_MOSI) || TMC_SW_MOSI == -1 - #define TMC_SW_MOSI PD14 - #endif - #if !defined(TMC_SW_MISO) || TMC_SW_MISO == -1 - #define TMC_SW_MISO PD1 - #endif - #if !defined(TMC_SW_SCK) || TMC_SW_SCK == -1 - #define TMC_SW_SCK PD0 - #endif +#if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 + #define TMC_SPI_MOSI PD14 +#endif +#if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 + #define TMC_SPI_MISO PD1 +#endif +#if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 + #define TMC_SPI_SCK PD0 #endif #include "pins_MKS_ROBIN_NANO_V3_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 873ba3e90d66..cac9c22fe5b5 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -113,18 +113,16 @@ #endif // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PD14 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PD1 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PD0 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h index d00b21c30b24..26510508a90c 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h @@ -200,9 +200,9 @@ // #if HAS_TMC_SPI #define TMC_USE_SW_SPI - #define TMC_SW_MOSI PE14 - #define TMC_SW_MISO PE13 - #define TMC_SW_SCK PE12 + #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MISO PE13 + #define TMC_SPI_SCK PE12 #endif // diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h index 06bf09402c06..7d598fc2ab99 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h @@ -171,9 +171,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SW_MISO MISO_PIN -#define TMC_SW_MOSI MOSI_PIN -#define TMC_SW_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h index d16d7b200bd6..386da6ec1492 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h @@ -168,9 +168,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SW_MISO MISO_PIN -#define TMC_SW_MOSI MOSI_PIN -#define TMC_SW_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 12871becbb40..5c50e51a2631 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -91,16 +91,14 @@ #define E2_ENABLE_PIN PD0 #define E2_CS_PIN PD1 -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PA7 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PA6 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PA5 #endif // diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h index 1ee7846c9315..918f159522ca 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h @@ -93,18 +93,16 @@ #define E1_CS_PIN PC8 // -// Software SPI pins for TMC2130 stepper drivers +// 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 +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC6 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PG3 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC7 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index eaceafe29ee3..d6cb4fef2e72 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -262,18 +262,16 @@ #endif // SPINDLE_FEATURE || LASER_FEATURE // -// Software SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130 stepper drivers // -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PE13 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PE15 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PE14 - #endif +#ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE13 +#endif +#ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE15 +#endif +#ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE14 #endif #if HAS_TMC_UART diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 2d84c95a3d19..7df5510821fd 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -163,6 +163,7 @@ uint32_t DiskIODriver_SPI_SD::cardSize() { void DiskIODriver_SPI_SD::chipDeselect() { extDigitalWrite(chipSelectPin_, HIGH); spiSend(0xFF); // Ensure MISO goes high impedance + spiClose(); } void DiskIODriver_SPI_SD::chipSelect() { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 09fd57b15467..9229da69ab69 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -121,12 +121,12 @@ bool MAX3421e::start() { const uint8_t revision = regRd(rREVISION); if (revision == 0x00 || revision == 0xFF) { SERIAL_ECHOLNPGM("Revision register appears incorrect on MAX3421e initialization. Got ", revision); - return false; + goto fail; } if (!reset()) { SERIAL_ECHOLNPGM("OSCOKIRQ hasn't asserted in time"); - return false; + goto fail; } // Delay a minimum of 1 second to ensure any capacitors are drained. @@ -149,7 +149,11 @@ bool MAX3421e::start() { // GPX pin on. This is done here so that busprobe will fail if we have a switch connected. regWr(rPINCTL, bmFDUPSPI | bmINTLEVEL); + spiClose(); return true; +fail: + spiClose(); + return false; } // Probe bus to determine device presence and speed. Switch host to this speed. From 39eb97b357d0bfbf41e92136b77f177f3267453d Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 21 Oct 2022 02:14:49 +0200 Subject: [PATCH 03/83] - (temporarily?) linking to my updated TMCStepper repository to fix compilation for other people aswell --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index 5f30db8a2f08..667581117459 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -18,7 +18,7 @@ MARLIN_TEST_BUILD = src_filter=+ POSTMORTEM_DEBUGGING = src_filter=+ + build_flags=-funwind-tables MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/master.zip -HAS_TRINAMIC_CONFIG = TMCStepper@~0.7.3 +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/quiret/TMCStepper@~0.7.3 src_filter=+ + + + + HAS_T(RINAMIC_CONFIG|MC_SPI) = src_filter=+ HAS_STEALTHCHOP = src_filter=+ From f9fb193f9784df949d436f5390a2fd2f05646225 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 21 Oct 2022 02:59:36 +0200 Subject: [PATCH 04/83] - added support for boards whose SPI pins stay anonymous/defaults --- Marlin/src/module/stepper/trinamic.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 9bf10e83553f..2face373166e 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -47,9 +47,14 @@ enum StealthIndex : uint8_t { // SWHW = SW/SH UART selection #if ENABLED(TMC_USE_SW_SPI) #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, true) +#else +#if !defined(TMC_SPI_MISO) || !defined(TMC_SPI_MOSI) || !defined(TMC_SPI_SCK) + // define in case the pins are unknown/not-definable/fixed. + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) #else #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, false) #endif +#endif #if ENABLED(TMC_SERIAL_MULTIPLEXER) #define TMC_UART_HW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(&ST##_HARDWARE_SERIAL, float(ST##_RSENSE), ST##_SLAVE_ADDRESS, SERIAL_MUL_PIN1, SERIAL_MUL_PIN2) From 57c05741ab15886a99295cdf009c5105c6ebdf85 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 27 Oct 2022 09:40:52 +0200 Subject: [PATCH 05/83] - added MKS TS35 V2.0 rotary encoder buttons support (the TS35-R model lacks them) --- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 497e5e561259..22f64520b753 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -229,6 +229,12 @@ #elif ENABLED(MKS_TS35_V2_0) + // OPTIONAL CONTROLS BESIDE THE TOUCH SCREEN + // (the TS35-R V2.0 model does not have them) + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + // DISPLAY PINS. #define TFT_A0_PIN EXP1_08_PIN #define TFT_BACKLIGHT_PIN EXP1_03_PIN From 77ead05c306ecda34c4db2a131e6c60caa6941b6 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 27 Oct 2022 11:30:53 +0200 Subject: [PATCH 06/83] - fix for TMC2660 SPI stepper driver (it is an odd-ball that does not support chaining) --- Marlin/src/feature/tmc_util.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 393b556f2833..a96f3100ca20 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -290,8 +290,11 @@ class TMCMarlin : public TMC266 TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t) : TMC2660Stepper(cs_pin, RS) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t) : - TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : + TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) + {} + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t, bool softSPI) : + TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) {} uint16_t rms_current() { return TMC2660Stepper::rms_current(); } void rms_current(const uint16_t mA) { From 8fea5ee625731026ff7cc94d8928a3564d3ee865 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 15:53:52 +0200 Subject: [PATCH 07/83] - further global SPI improvements (all platforms + many Marlin functions) - added more reliability ensurances to the SD card stuff --- Marlin/Configuration.h | 1659 +++--------- Marlin/Configuration_adv.h | 2410 ++++++----------- Marlin/src/HAL/AVR/HAL_SPI.cpp | 8 +- Marlin/src/HAL/DUE/HAL_SPI.cpp | 140 +- .../dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp | 6 +- Marlin/src/HAL/ESP32/HAL_SPI.cpp | 6 +- Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp | 2 +- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 26 +- .../u8g/u8g_com_HAL_LPC1768_hw_spi.cpp | 2 +- .../u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 3 +- Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 9 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 11 +- Marlin/src/HAL/STM32/msc_sd.cpp | 52 +- Marlin/src/HAL/STM32/sdio.cpp | 16 +- Marlin/src/HAL/STM32F1/HAL_SPI.cpp | 3 +- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 11 +- Marlin/src/HAL/STM32F1/sdio.cpp | 8 +- Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 13 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 13 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 13 +- Marlin/src/HAL/shared/HAL_SPI.h | 6 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 23 + Marlin/src/sd/Sd2Card.cpp | 6 +- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 17 +- 24 files changed, 1450 insertions(+), 3013 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 87a98298a58e..92f5882dcca2 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -34,6 +34,7 @@ * - Extra features * * Advanced settings can be found in Configuration_adv.h + * */ #define CONFIGURATION_H_VERSION 02010200 @@ -42,25 +43,35 @@ //=========================================================================== /** - * Here are some useful links to help get your machine configured and calibrated: - * - * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all - * - * Průša Calculator: https://blog.prusaprinters.org/calculator_3416/ - * - * Calibration Guides: https://reprap.org/wiki/Calibration - * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide - * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap - * https://youtu.be/wAL9d7FgInk + * Here are some standard links for getting your machine calibrated: * - * Calibration Objects: https://www.thingiverse.com/thing:5573 - * https://www.thingiverse.com/thing:1278865 + * https://reprap.org/wiki/Calibration + * https://youtu.be/wAL9d7FgInk + * http://calculator.josefprusa.cz + * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * https://www.thingiverse.com/thing:5573 + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * https://www.thingiverse.com/thing:298812 */ +//=========================================================================== +//============================= DELTA Printer =============================== +//=========================================================================== +// For a Delta printer start with one of the configuration files in the +// config/examples/delta directory and customize for your machine. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a SCARA printer start with the configuration files in +// config/examples/SCARA and customize for your machine. +// + // @section info // Author info of this build printed to the host during boot and M115 -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "EirDev" // Who made the changes. //#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes) /** @@ -85,11 +96,6 @@ // @section machine -// Choose the name from boards.h that matches your setup -#ifndef MOTHERBOARD - #define MOTHERBOARD BOARD_RAMPS_14_EFB -#endif - /** * Select the serial port on the board to use for communication with the host. * This allows the connection of wireless adapters (for instance) to non-default port pins. @@ -101,9 +107,13 @@ #define SERIAL_PORT 0 /** - * Serial Port Baud Rate - * This is the default communication speed for all serial ports. - * Set the baud rate defaults for additional serial ports below. + * Select a secondary serial port on the board to use for communication with the host. + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_2 -1 + +/** + * This setting determines the communication speed of the printer. * * 250000 works in most cases, but you might try a lower speed if * you commonly experience drop-outs during host printing. @@ -113,27 +123,14 @@ */ #define BAUDRATE 250000 -//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate - -/** - * Select a secondary serial port on the board to use for communication with the host. - * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. - * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_2 -1 -//#define BAUDRATE_2 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE - -/** - * Select a third serial port on the board to use for communication with the host. - * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_3 1 -//#define BAUDRATE_3 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE - // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH +// Choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_RAMPS_14_EFB +#endif + // Name displayed in the LCD "Ready" message and Info menu //#define CUSTOM_MACHINE_NAME "3D Printer" @@ -141,88 +138,6 @@ // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" -// @section stepper drivers - -/** - * Stepper Drivers - * - * These settings allow Marlin to tune stepper driver timing and enable advanced options for - * stepper drivers that support them. You may also override timing options in Configuration_adv.h. - * - * Use TMC2208/TMC2208_STANDALONE for TMC2225 drivers and TMC2209/TMC2209_STANDALONE for TMC2226 drivers. - * - * Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100, - * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, - * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, - * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, - * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE - * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] - */ -#define X_DRIVER_TYPE A4988 -#define Y_DRIVER_TYPE A4988 -#define Z_DRIVER_TYPE A4988 -//#define X2_DRIVER_TYPE A4988 -//#define Y2_DRIVER_TYPE A4988 -//#define Z2_DRIVER_TYPE A4988 -//#define Z3_DRIVER_TYPE A4988 -//#define Z4_DRIVER_TYPE A4988 -//#define I_DRIVER_TYPE A4988 -//#define J_DRIVER_TYPE A4988 -//#define K_DRIVER_TYPE A4988 -//#define U_DRIVER_TYPE A4988 -//#define V_DRIVER_TYPE A4988 -//#define W_DRIVER_TYPE A4988 -#define E0_DRIVER_TYPE A4988 -//#define E1_DRIVER_TYPE A4988 -//#define E2_DRIVER_TYPE A4988 -//#define E3_DRIVER_TYPE A4988 -//#define E4_DRIVER_TYPE A4988 -//#define E5_DRIVER_TYPE A4988 -//#define E6_DRIVER_TYPE A4988 -//#define E7_DRIVER_TYPE A4988 - -/** - * Additional Axis Settings - * - * Define AXISn_ROTATES for all axes that rotate or pivot. - * Rotational axis coordinates are expressed in degrees. - * - * AXISn_NAME defines the letter used to refer to the axis in (most) G-code commands. - * By convention the names and roles are typically: - * 'A' : Rotational axis parallel to X - * 'B' : Rotational axis parallel to Y - * 'C' : Rotational axis parallel to Z - * 'U' : Secondary linear axis parallel to X - * 'V' : Secondary linear axis parallel to Y - * 'W' : Secondary linear axis parallel to Z - * - * Regardless of these settings the axes are internally named I, J, K, U, V, W. - */ -#ifdef I_DRIVER_TYPE - #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] - #define AXIS4_ROTATES -#endif -#ifdef J_DRIVER_TYPE - #define AXIS5_NAME 'B' // :['B', 'C', 'U', 'V', 'W'] - #define AXIS5_ROTATES -#endif -#ifdef K_DRIVER_TYPE - #define AXIS6_NAME 'C' // :['C', 'U', 'V', 'W'] - #define AXIS6_ROTATES -#endif -#ifdef U_DRIVER_TYPE - #define AXIS7_NAME 'U' // :['U', 'V', 'W'] - //#define AXIS7_ROTATES -#endif -#ifdef V_DRIVER_TYPE - #define AXIS8_NAME 'V' // :['V', 'W'] - //#define AXIS8_ROTATES -#endif -#ifdef W_DRIVER_TYPE - #define AXIS9_NAME 'W' // :['W'] - //#define AXIS9_ROTATES -#endif - // @section extruder // This defines the number of extruders @@ -242,23 +157,34 @@ //#define SINGLENOZZLE_STANDBY_FAN #endif -// @section multi-material - /** - * Multi-Material Unit - * Set to one of these predefined models: + * Pruša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. * - * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version) - * PRUSA_MMU2 : Průša MMU2 - * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5) - * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) - * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs + //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs +#endif + +/** + * Pruša Multi-Material Unit v2 * * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. - * See additional options in Configuration_adv.h. - * :["PRUSA_MMU1", "PRUSA_MMU2", "PRUSA_MMU2S", "EXTENDABLE_EMU_MMU2", "EXTENDABLE_EMU_MMU2S"] + * Requires EXTRUDERS = 5 + * + * For additional configuration see Configuration_adv.h */ -//#define MMU_MODEL PRUSA_MMU2 +//#define PRUSA_MMU2 // A dual extruder that uses a single stepper motor //#define SWITCHING_EXTRUDER @@ -276,7 +202,6 @@ #define SWITCHING_NOZZLE_SERVO_NR 0 //#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo) - #define SWITCHING_NOZZLE_SERVO_DWELL 2500 // Dwell time to wait for servo to make physical move #endif /** @@ -299,6 +224,7 @@ #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // (mm) Distance to move beyond the parking point to grab the extruder + //#define MANUAL_SOLENOID_CONTROL // Manual control of docking solenoids with M380 S / M381 #if ENABLED(PARKING_EXTRUDER) @@ -380,7 +306,6 @@ #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands //#define GRADIENT_MIX // Support for gradient mixing with M166 and LCD - //#define MIXING_PRESETS // Assign 8 default V-tool presets for 2 or 3 MIXING_STEPPERS #if ENABLED(GRADIENT_MIX) //#define GRADIENT_VTOOL // Add M166 T to use a V-tool index as a Gradient alias #endif @@ -393,7 +318,7 @@ //#define HOTEND_OFFSET_Y { 0.0, 5.00 } // (mm) relative Y-offset for each nozzle //#define HOTEND_OFFSET_Z { 0.0, 0.00 } // (mm) relative Z-offset for each nozzle -// @section psu control +// @section machine /** * Power Supply Control @@ -405,20 +330,10 @@ //#define PSU_NAME "Power Supply" #if ENABLED(PSU_CONTROL) - //#define MKS_PWC // Using the MKS PWC add-on - //#define PS_OFF_CONFIRM // Confirm dialog when power off - //#define PS_OFF_SOUND // Beep 1s when power off #define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box - //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 - //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power - //#define LED_POWEROFF_TIMEOUT 10000 // (ms) Turn off LEDs after power-off, with this amount of delay - - //#define POWER_OFF_TIMER // Enable M81 D to power off after a delay - //#define POWER_OFF_WAIT_FOR_COOLDOWN // Enable M81 S to power off only after cooldown - - //#define PSU_POWERUP_GCODE "M355 S1" // G-code to run after power-on (e.g., case light on) - //#define PSU_POWEROFF_GCODE "M355 S0" // G-code to run before power-off (e.g., case light off) + //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 + //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power //#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin #if ENABLED(AUTO_POWER_CONTROL) @@ -426,115 +341,80 @@ #define AUTO_POWER_E_FANS #define AUTO_POWER_CONTROLLERFAN #define AUTO_POWER_CHAMBER_FAN - #define AUTO_POWER_COOLER_FAN - #define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration - //#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time. - #endif - #if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) - //#define AUTO_POWER_E_TEMP 50 // (°C) PSU on if any extruder is over this temperature - //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) PSU on if the chamber is over this temperature - //#define AUTO_POWER_COOLER_TEMP 26 // (°C) PSU on if the cooler is over this temperature + //#define AUTO_POWER_E_TEMP 50 // (°C) Turn on PSU over this temperature + //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) Turn on PSU over this temperature + #define POWER_TIMEOUT 30 #endif #endif +// @section temperature + //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== -// @section temperature /** - * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table + * --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table * * Temperature sensors available: * - * SPI RTD/Thermocouple Boards - IMPORTANT: Read the NOTE below! - * ------- - * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) - * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. - * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) - * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) - * - * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, - * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, - * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the - * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. - * - * Analog Themocouple Boards - * ------- - * -4 : AD8495 with Thermocouple - * -1 : AD595 with Thermocouple - * - * Analog Thermistors - 4.7kΩ pullup - Normal - * ------- - * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors - * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA - * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE - * 2 : 200kΩ ATC Semitec 204GT-2 - * 202 : 200kΩ Copymaster 3D - * 3 : ???Ω Mendel-parts thermistor - * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! - * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C - * 501 : 100kΩ Zonestar - Tronxy X3A - * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M - * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor - * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor - * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor - * 512 : 100kΩ RPW-Ultra hotend - * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) - * 7 : 100kΩ Honeywell 135-104LAG-J01 - * 71 : 100kΩ Honeywell 135-104LAF-J01 - * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT - * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 - * 10 : 100kΩ RS PRO 198-961 - * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% - * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed - * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% - * 15 : 100kΩ Calibrated for JGAurora A5 hotend - * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 - * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input - * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input - * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 - * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 - * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 - * 66 : 4.7MΩ Dyze Design / Trianglelab T-D500 500°C High Temperature Thermistor - * 67 : 500kΩ SliceEngineering 450°C Thermistor - * 68 : PT100 amplifier board from Dyze Design - * 70 : 100kΩ bq Hephestos 2 - * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 - * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor - * - * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. - * ------- (but gives greater accuracy and more stable PID) - * 51 : 100kΩ EPCOS (1kΩ pullup) - * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) - * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) - * - * Analog Thermistors - 10kΩ pullup - Atypical - * ------- - * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor - * - * Analog RTDs (Pt100/Pt1000) - * ------- - * 110 : Pt100 with 1kΩ pullup (atypical) - * 147 : Pt100 with 4.7kΩ pullup - * 1010 : Pt1000 with 1kΩ pullup (atypical) - * 1022 : Pt1000 with 2.2kΩ pullup - * 1047 : Pt1000 with 4.7kΩ pullup (E3D) - * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. - * NOTE: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. - * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v ADC reference voltage (STM32, LPC176x....) and 5V INA826 amplifier board supply. - * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. - * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x - * - * Custom/Dummy/Other Thermal Sensors - * ------ + * -5 : PT100 / PT1000 with MAX31865 (only for sensors 0-1) + * -3 : thermocouple with MAX31855 (only for sensors 0-1) + * -2 : thermocouple with MAX6675 (only for sensors 0-1) + * -4 : thermocouple with AD8495 + * -1 : thermocouple with AD595 * 0 : not used + * 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup) + * 331 : (3.3V scaled thermistor 1 table for MEGA) + * 332 : (3.3V scaled thermistor 1 table for DUE) + * 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) + * 202 : 200k thermistor - Copymaster 3D + * 3 : Mendel-parts thermistor (4.7k pullup) + * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! + * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup) + * 501 : 100K Zonestar (Tronxy X3A) Thermistor + * 502 : 100K Zonestar Thermistor used by hot bed in Zonestar Pruša P802M + * 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup) + * 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) + * 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup) + * 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup) + * 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) + * 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) + * 10 : 100k RS thermistor 198-961 (4.7k pullup) + * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup) + * 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) + * 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE" + * 15 : 100k thermistor calibration for JGAurora A5 hotend + * 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 + * 20 : Pt100 with circuit in the Ultimainboard V2.x with 5v excitation (AVR) + * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....) + * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) + * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) + * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x + * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 + * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup + * 66 : 4.7M High Temperature thermistor from Dyze Design + * 67 : 450C thermistor from SliceEngineering + * 70 : the 100K thermistor found in the bq Hephestos 2 + * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor + * 99 : 100k thermistor with a 10K pull-up resistor (found on some Wanhao i3 machines) + * + * 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k. + * (but gives greater accuracy and more stable PID) + * 51 : 100k thermistor - EPCOS (1k pullup) + * 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup) + * 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) + * + * 1047 : Pt1000 with 4k7 pullup (E3D) + * 1010 : Pt1000 with 1k pullup (non standard) + * 147 : Pt100 with 4k7 pullup + * 110 : Pt100 with 1k pullup (non standard) + * * 1000 : Custom - Specify parameters in Configuration_adv.h * - * !!! Use these for Testing or Development purposes. NEVER for production machine. !!! + * Use these for Testing or Development purposes. NEVER for production machine. * 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below. * 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below. - * */ #define TEMP_SENSOR_0 1 #define TEMP_SENSOR_1 0 @@ -547,61 +427,23 @@ #define TEMP_SENSOR_BED 0 #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 -#define TEMP_SENSOR_COOLER 0 -#define TEMP_SENSOR_BOARD 0 -#define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 -#define DUMMY_THERMISTOR_998_VALUE 25 +#define DUMMY_THERMISTOR_998_VALUE 25 #define DUMMY_THERMISTOR_999_VALUE 100 -// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 -#if TEMP_SENSOR_IS_MAX_TC(0) - #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) - #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 -#endif -#if TEMP_SENSOR_IS_MAX_TC(1) - #define MAX31865_SENSOR_OHMS_1 100 - #define MAX31865_CALIBRATION_OHMS_1 430 -#endif -#if TEMP_SENSOR_IS_MAX_TC(2) - #define MAX31865_SENSOR_OHMS_2 100 - #define MAX31865_CALIBRATION_OHMS_2 430 -#endif - -#if HAS_E_TEMP_SENSOR - #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 - #define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer - #define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -#endif - -#if TEMP_SENSOR_BED - #define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 - #define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer - #define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -#endif +// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings +// from the two sensors differ too much the print will be aborted. +//#define TEMP_SENSOR_1_AS_REDUNDANT +#define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 -#if TEMP_SENSOR_CHAMBER - #define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191 - #define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer - #define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -#endif +#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 +#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer +#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target -/** - * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) - * - * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another - * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C), - * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting - * the Bed sensor (-1) will disable bed heating/monitoring. - * - * For selecting source/target use: COOLER, PROBE, BOARD, CHAMBER, BED, E0, E1, E2, E3, E4, E5, E6, E7 - */ -#if TEMP_SENSOR_REDUNDANT - #define TEMP_SENSOR_REDUNDANT_SOURCE E1 // The sensor that will provide the redundant reading. - #define TEMP_SENSOR_REDUNDANT_TARGET E0 // The sensor that we are providing a redundant reading for. - #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. -#endif +#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 +#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer +#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. @@ -614,7 +456,6 @@ #define HEATER_6_MINTEMP 5 #define HEATER_7_MINTEMP 5 #define BED_MINTEMP 5 -#define CHAMBER_MINTEMP 5 // Above this temperature the heater will be switched off. // This can protect components from overheating, but NOT from shorts and failures. @@ -628,93 +469,35 @@ #define HEATER_6_MAXTEMP 275 #define HEATER_7_MAXTEMP 275 #define BED_MAXTEMP 150 -#define CHAMBER_MAXTEMP 60 - -/** - * Thermal Overshoot - * During heatup (and printing) the temperature can often "overshoot" the target by many degrees - * (especially before PID tuning). Setting the target temperature too close to MAXTEMP guarantees - * a MAXTEMP shutdown! Use these values to forbid temperatures being set too close to MAXTEMP. - */ -#define HOTEND_OVERSHOOT 15 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT -#define BED_OVERSHOOT 10 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT -#define COOLER_OVERSHOOT 2 // (°C) Forbid temperatures closer than OVERSHOOT //=========================================================================== //============================= PID Settings ================================ //=========================================================================== +// PID Tuning Guide here: https://reprap.org/wiki/PID_Tuning -// @section hotend temp - -// Enable PIDTEMP for PID control or MPCTEMP for Predictive Model. -// temperature control. Disable both for bang-bang heating. -#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning -//#define MPCTEMP // ** EXPERIMENTAL ** - +// Comment the following line to disable PID and enable bang-bang. +#define PIDTEMP #define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current #define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current #define PID_K1 0.95 // Smoothing factor within any PID loop #if ENABLED(PIDTEMP) - //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation. - //#define PID_PARAMS_PER_HOTEND // Use separate PID parameters for each extruder (useful for mismatched extruders) - // Set/get with G-code: M301 E[extruder number, 0-2] - + //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) + //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) + //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + // Set/get with gcode: M301 E[extruder number, 0-2] #if ENABLED(PID_PARAMS_PER_HOTEND) - // Specify up to one value per hotend here, according to your setup. - // If there are fewer values, the last one applies to the remaining hotends. - #define DEFAULT_Kp_LIST { 22.20, 22.20 } - #define DEFAULT_Ki_LIST { 1.08, 1.08 } - #define DEFAULT_Kd_LIST { 114.00, 114.00 } + // Specify between 1 and HOTENDS values per array. + // If fewer than EXTRUDER values are provided, the last element will be repeated. + #define DEFAULT_Kp_LIST { 22.20, 20.0 } + #define DEFAULT_Ki_LIST { 1.08, 1.0 } + #define DEFAULT_Kd_LIST { 114.00, 112.0 } #else #define DEFAULT_Kp 22.20 #define DEFAULT_Ki 1.08 #define DEFAULT_Kd 114.00 #endif -#endif - -/** - * Model Predictive Control for hotend - * - * Use a physical model of the hotend to control temperature. When configured correctly - * this gives better responsiveness and stability than PID and it also removes the need - * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. - * @section mpctemp - */ -#if ENABLED(MPCTEMP) - //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) - //#define MPC_AUTOTUNE_MENU // Add MPC auto-tuning to the "Advanced Settings" menu. (~350 bytes of flash) - - #define MPC_MAX BANG_MAX // (0..255) Current to nozzle while MPC is active. - #define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers. - - #define MPC_INCLUDE_FAN // Model the fan speed? - - // Measured physical constants from M306 - #define MPC_BLOCK_HEAT_CAPACITY { 16.7f } // (J/K) Heat block heat capacities. - #define MPC_SENSOR_RESPONSIVENESS { 0.22f } // (K/s per ∆K) Rate of change of sensor temperature from heat block. - #define MPC_AMBIENT_XFER_COEFF { 0.068f } // (W/K) Heat transfer coefficients from heat block to room air with fan off. - #if ENABLED(MPC_INCLUDE_FAN) - #define MPC_AMBIENT_XFER_COEFF_FAN255 { 0.097f } // (W/K) Heat transfer coefficients from heat block to room air with fan on full. - #endif - - // For one fan and multiple hotends MPC needs to know how to apply the fan cooling effect. - #if ENABLED(MPC_INCLUDE_FAN) - //#define MPC_FAN_0_ALL_HOTENDS - //#define MPC_FAN_0_ACTIVE_HOTEND - #endif - - #define FILAMENT_HEAT_CAPACITY_PERMM { 5.6e-3f } // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). - //#define FILAMENT_HEAT_CAPACITY_PERMM { 3.6e-3f } // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). - - // Advanced options - #define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization. - #define MPC_MIN_AMBIENT_CHANGE 1.0f // (K/s) Modeled ambient temperature rate of change, when correcting model inaccuracies. - #define MPC_STEADYSTATE 0.5f // (K/s) Temperature change rate for steady state logic to be enforced. - - #define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center at first layer height. - #define MPC_TUNING_END_Z 10.0f // (mm) M306 Autotuning final Z position. -#endif +#endif // PIDTEMP //=========================================================================== //====================== PID > Bed Temperature Control ====================== @@ -732,7 +515,6 @@ * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W * heater. If your configuration is significantly different than this and you don't understand * the issues involved, don't use bed PID until someone else verifies that your hardware works. - * @section bed temp */ //#define PIDTEMPBED @@ -748,73 +530,32 @@ #if ENABLED(PIDTEMPBED) //#define MIN_BED_POWER 0 - //#define PID_BED_DEBUG // Print Bed PID debug data to the serial port. + //#define PID_BED_DEBUG // Sends debug data to the serial port. - // 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) - // from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) #define DEFAULT_bedKp 10.00 #define DEFAULT_bedKi .023 #define DEFAULT_bedKd 305.4 + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from pidautotune + //#define DEFAULT_bedKp 97.1 + //#define DEFAULT_bedKi 1.41 + //#define DEFAULT_bedKd 1675.16 + // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. #endif // PIDTEMPBED -//=========================================================================== -//==================== PID > Chamber Temperature Control ==================== -//=========================================================================== - -/** - * PID Chamber Heating - * - * If this option is enabled set PID constants below. - * If this option is disabled, bang-bang will be used and CHAMBER_LIMIT_SWITCHING will enable - * hysteresis. - * - * The PID frequency will be the same as the extruder PWM. - * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz, - * which is fine for driving a square wave into a resistive load and does not significantly - * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 200W - * heater. If your configuration is significantly different than this and you don't understand - * the issues involved, don't use chamber PID until someone else verifies that your hardware works. - * @section chamber temp - */ -//#define PIDTEMPCHAMBER -//#define CHAMBER_LIMIT_SWITCHING - -/** - * Max Chamber Power - * Applies to all forms of chamber control (PID, bang-bang, and bang-bang with hysteresis). - * When set to any value below 255, enables a form of PWM to the chamber heater that acts like a divider - * so don't use it unless you are OK with PWM on your heater. (See the comment on enabling PIDTEMPCHAMBER) - */ -#define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber heater; 255=full current - -#if ENABLED(PIDTEMPCHAMBER) - #define MIN_CHAMBER_POWER 0 - //#define PID_CHAMBER_DEBUG // Print Chamber PID debug data to the serial port. - - // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element - // and placed inside the small Creality printer enclosure tent. - // - #define DEFAULT_chamberKp 37.04 - #define DEFAULT_chamberKi 1.40 - #define DEFAULT_chamberKd 655.17 - // M309 P37.04 I1.04 D655.17 - - // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles. -#endif // PIDTEMPCHAMBER - -#if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) +#if EITHER(PIDTEMP, PIDTEMPBED) + //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. - - //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of flash) - //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of flash) #endif -// @section safety +// @section extruder /** * Prevent extrusion if the temperature is below EXTRUDE_MINTEMP. @@ -853,7 +594,6 @@ #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders #define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed #define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber -#define THERMAL_PROTECTION_COOLER // Enable thermal protection for the laser cooling //=========================================================================== //============================= Mechanical Settings ========================= @@ -870,166 +610,12 @@ //#define COREZX //#define COREZY //#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 -//#define MARKFORGED_YX - -// Enable for a belt style printer with endless "Z" motion -//#define BELTPRINTER - -// Enable for Polargraph Kinematics -//#define POLARGRAPH -#if ENABLED(POLARGRAPH) - #define POLARGRAPH_MAX_BELT_LEN 1035.0 - #define POLAR_SEGMENTS_PER_SECOND 5 -#endif - -// @section delta - -// Enable for DELTA kinematics and configure below -//#define DELTA -#if ENABLED(DELTA) - - // Make delta curves from many straight lines (linear interpolation). - // This is a trade-off between visible corners (not enough segments) - // and processor overload (too many expensive sqrt calls). - #define DELTA_SEGMENTS_PER_SECOND 200 - - // After homing move down to a height where XY movement is unconstrained - //#define DELTA_HOME_TO_SAFE_ZONE - - // Delta calibration menu - // uncomment to add three points calibration menu option. - // See http://minow.blogspot.com/index.html#4918805519571907051 - //#define DELTA_CALIBRATION_MENU - - // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) - //#define DELTA_AUTO_CALIBRATION - - // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them - - #if ENABLED(DELTA_AUTO_CALIBRATION) - // set the default number of probe points : n*n (1 -> 7) - #define DELTA_CALIBRATION_DEFAULT_POINTS 4 - #endif - - #if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) - // Set the steprate for papertest probing - #define PROBE_MANUALLY_STEP 0.05 // (mm) - #endif - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 140.0 // (mm) - - // Maximum reachable area - #define DELTA_MAX_RADIUS 140.0 // (mm) - - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 250.0 // (mm) - - // Distance between bed and nozzle Z home position - #define DELTA_HEIGHT 250.00 // (mm) Get this value from G33 auto calibrate - - #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS 124.0 // (mm) Get this value from G33 auto calibrate - - // Trim adjustments for individual towers - // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 - // measured in degrees anticlockwise looking from above the printer - #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate - - // Delta radius and diagonal rod adjustments (mm) - //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } -#endif - -// @section scara - -/** - * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013. - * Implemented and slightly reworked by JCERNY in June, 2014. - * - * Mostly Printed SCARA is an open source design by Tyler Williams. See: - * https://www.thingiverse.com/thing:2487048 - * https://www.thingiverse.com/thing:1241491 - */ -//#define MORGAN_SCARA -//#define MP_SCARA -#if EITHER(MORGAN_SCARA, MP_SCARA) - // If movement is choppy try lowering this value - #define SCARA_SEGMENTS_PER_SECOND 200 - - // Length of inner and outer support arms. Measure arm lengths precisely. - #define SCARA_LINKAGE_1 150 // (mm) - #define SCARA_LINKAGE_2 150 // (mm) - - // SCARA tower offset (position of Tower relative to bed zero position) - // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. - #define SCARA_OFFSET_X 100 // (mm) - #define SCARA_OFFSET_Y -56 // (mm) - - #if ENABLED(MORGAN_SCARA) - - //#define DEBUG_SCARA_KINEMATICS - #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly - - // Radius around the center where the arm cannot reach - #define MIDDLE_DEAD_ZONE_R 0 // (mm) - - #define THETA_HOMING_OFFSET 0 // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 - #define PSI_HOMING_OFFSET 0 // Calculated from Calibration Guide and M364 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 - - #elif ENABLED(MP_SCARA) - - #define SCARA_OFFSET_THETA1 12 // degrees - #define SCARA_OFFSET_THETA2 131 // degrees - - #endif - -#endif - -// @section tpara - -// Enable for TPARA kinematics and configure below -//#define AXEL_TPARA -#if ENABLED(AXEL_TPARA) - #define DEBUG_ROBOT_KINEMATICS - #define ROBOT_SEGMENTS_PER_SECOND 200 - - // Length of inner and outer support arms. Measure arm lengths precisely. - #define ROBOT_LINKAGE_1 120 // (mm) - #define ROBOT_LINKAGE_2 120 // (mm) - - // SCARA tower offset (position of Tower relative to bed zero position) - // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. - #define ROBOT_OFFSET_X 0 // (mm) - #define ROBOT_OFFSET_Y 0 // (mm) - #define ROBOT_OFFSET_Z 0 // (mm) - - #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly - - // Radius around the center where the arm cannot reach - #define MIDDLE_DEAD_ZONE_R 0 // (mm) - - // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 - #define THETA_HOMING_OFFSET 0 - #define PSI_HOMING_OFFSET 0 -#endif - -// @section machine - -// Articulated robot (arm). Joints are directly mapped to axes with no kinematics. -//#define ARTICULATED_ROBOT_ARM - -// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire -// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics). -//#define FOAMCUTTER_XYUV //=========================================================================== //============================== Endstop Settings =========================== //=========================================================================== -// @section endstops +// @section homing // Specify here all the endstop connectors that are connected to any endstop or probe. // Almost all printers will be using one per axis. Probes will use one or more of the @@ -1037,44 +623,20 @@ #define USE_XMIN_PLUG #define USE_YMIN_PLUG #define USE_ZMIN_PLUG -//#define USE_IMIN_PLUG -//#define USE_JMIN_PLUG -//#define USE_KMIN_PLUG -//#define USE_UMIN_PLUG -//#define USE_VMIN_PLUG -//#define USE_WMIN_PLUG //#define USE_XMAX_PLUG //#define USE_YMAX_PLUG //#define USE_ZMAX_PLUG -//#define USE_IMAX_PLUG -//#define USE_JMAX_PLUG -//#define USE_KMAX_PLUG -//#define USE_UMAX_PLUG -//#define USE_VMAX_PLUG -//#define USE_WMAX_PLUG // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS #if DISABLED(ENDSTOPPULLUPS) // Disable ENDSTOPPULLUPS to set pullups individually - //#define ENDSTOPPULLUP_XMIN - //#define ENDSTOPPULLUP_YMIN - //#define ENDSTOPPULLUP_ZMIN - //#define ENDSTOPPULLUP_IMIN - //#define ENDSTOPPULLUP_JMIN - //#define ENDSTOPPULLUP_KMIN - //#define ENDSTOPPULLUP_UMIN - //#define ENDSTOPPULLUP_VMIN - //#define ENDSTOPPULLUP_WMIN //#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_ZMAX - //#define ENDSTOPPULLUP_IMAX - //#define ENDSTOPPULLUP_JMAX - //#define ENDSTOPPULLUP_KMAX - //#define ENDSTOPPULLUP_UMAX - //#define ENDSTOPPULLUP_VMAX - //#define ENDSTOPPULLUP_WMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -1082,24 +644,12 @@ //#define ENDSTOPPULLDOWNS #if DISABLED(ENDSTOPPULLDOWNS) // Disable ENDSTOPPULLDOWNS to set pulldowns individually - //#define ENDSTOPPULLDOWN_XMIN - //#define ENDSTOPPULLDOWN_YMIN - //#define ENDSTOPPULLDOWN_ZMIN - //#define ENDSTOPPULLDOWN_IMIN - //#define ENDSTOPPULLDOWN_JMIN - //#define ENDSTOPPULLDOWN_KMIN - //#define ENDSTOPPULLDOWN_UMIN - //#define ENDSTOPPULLDOWN_VMIN - //#define ENDSTOPPULLDOWN_WMIN //#define ENDSTOPPULLDOWN_XMAX //#define ENDSTOPPULLDOWN_YMAX //#define ENDSTOPPULLDOWN_ZMAX - //#define ENDSTOPPULLDOWN_IMAX - //#define ENDSTOPPULLDOWN_JMAX - //#define ENDSTOPPULLDOWN_KMAX - //#define ENDSTOPPULLDOWN_UMAX - //#define ENDSTOPPULLDOWN_VMAX - //#define ENDSTOPPULLDOWN_WMAX + //#define ENDSTOPPULLDOWN_XMIN + //#define ENDSTOPPULLDOWN_YMIN + //#define ENDSTOPPULLDOWN_ZMIN //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif @@ -1107,23 +657,44 @@ #define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define U_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define V_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define W_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define U_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define V_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. -#define W_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe. +/** + * Stepper Drivers + * + * These settings allow Marlin to tune stepper driver timing and enable advanced options for + * stepper drivers that support them. You may also override timing options in Configuration_adv.h. + * + * A4988 is assumed for unspecified drivers. + * + * Options: A4988, A5984, DRV8825, LV8729, L6470, L6474, POWERSTEP01, + * TB6560, TB6600, TMC2100, + * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, + * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, + * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, + * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE + * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'L6474', 'POWERSTEP01', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] + */ +#define X_DRIVER_TYPE TMC2130 +#define Y_DRIVER_TYPE TMC2130 +#define Z_DRIVER_TYPE TMC2130 +//#define X2_DRIVER_TYPE A4988 +//#define Y2_DRIVER_TYPE A4988 +//#define Z2_DRIVER_TYPE A4988 +//#define Z3_DRIVER_TYPE A4988 +//#define Z4_DRIVER_TYPE A4988 +#define E0_DRIVER_TYPE TMC2130 +//#define E1_DRIVER_TYPE A4988 +//#define E2_DRIVER_TYPE A4988 +//#define E3_DRIVER_TYPE A4988 +//#define E4_DRIVER_TYPE A4988 +//#define E5_DRIVER_TYPE A4988 +//#define E6_DRIVER_TYPE A4988 +//#define E7_DRIVER_TYPE A4988 + // Enable this feature if all enabled endstop pins are interrupt-capable. // This will remove the need to poll the interrupt pins, saving many CPU cycles. //#define ENDSTOP_INTERRUPTS_FEATURE @@ -1166,16 +737,16 @@ //#define DISTINCT_E_FACTORS /** - * Default Axis Steps Per Unit (linear=steps/mm, rotational=steps/°) + * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] + * X, Y, Z, E0 [, E1[, E2...]] */ -#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 } +#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 } /** - * Default Max Feed Rate (linear=mm/s, rotational=°/s) + * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] + * X, Y, Z, E0 [, E1[, E2...]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -1185,10 +756,10 @@ #endif /** - * Default Max Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2)) + * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] + * X, Y, Z, E0 [, E1[, E2...]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } @@ -1198,7 +769,7 @@ #endif /** - * Default Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2)) + * Default Acceleration (change/s) change = mm/s * Override with M204 * * M204 P Acceleration @@ -1211,7 +782,7 @@ /** * Default Jerk limits (mm/s) - * Override with M205 X Y Z . . . E + * Override with M205 X Y Z E * * "Jerk" specifies the minimum speed change that requires acceleration. * When changing speed and direction, if the difference is less than the @@ -1222,12 +793,6 @@ #define DEFAULT_XJERK 10.0 #define DEFAULT_YJERK 10.0 #define DEFAULT_ZJERK 0.3 - //#define DEFAULT_IJERK 0.3 - //#define DEFAULT_JJERK 0.3 - //#define DEFAULT_KJERK 0.3 - //#define DEFAULT_UJERK 0.3 - //#define DEFAULT_VJERK 0.3 - //#define DEFAULT_WJERK 0.3 //#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves @@ -1295,6 +860,7 @@ * - For simple switches connect... * - normally-closed switches to GND and D32. * - normally-open switches to 5V and D32. + * */ //#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default @@ -1311,6 +877,7 @@ * or (with LCD_BED_LEVELING) the LCD controller. */ //#define PROBE_MANUALLY +//#define MANUAL_PROBE_START_Z 0.2 /** * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. @@ -1336,15 +903,9 @@ //#define BLTOUCH /** - * MagLev V4 probe by MDD - * - * This probe is deployed and activated by powering a built-in electromagnet. + * Pressure sensor with a BLTouch-like interface */ -//#define MAGLEV4 -#if ENABLED(MAGLEV4) - //#define MAGLEV_TRIGGER_PIN 11 // Set to the connected digital output - #define MAGLEV_TRIGGER_DELAY 15 // Changing this risks overheating the coil -#endif +//#define CREALITY_TOUCH /** * Touch-MI Probe by hotends.fr @@ -1377,29 +938,8 @@ #define Z_PROBE_RETRACT_X X_MAX_POS #endif -/** - * Magnetically Mounted Probe - * For probes such as Euclid, Klicky, Klackender, etc. - */ -//#define MAG_MOUNTED_PROBE -#if ENABLED(MAG_MOUNTED_PROBE) - #define PROBE_DEPLOY_FEEDRATE (133*60) // (mm/min) Probe deploy speed - #define PROBE_STOW_FEEDRATE (133*60) // (mm/min) Probe stow speed - - #define MAG_MOUNTED_DEPLOY_1 { PROBE_DEPLOY_FEEDRATE, { 245, 114, 30 } } // Move to side Dock & Attach probe - #define MAG_MOUNTED_DEPLOY_2 { PROBE_DEPLOY_FEEDRATE, { 210, 114, 30 } } // Move probe off dock - #define MAG_MOUNTED_DEPLOY_3 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed - #define MAG_MOUNTED_DEPLOY_4 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed - #define MAG_MOUNTED_DEPLOY_5 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed - #define MAG_MOUNTED_STOW_1 { PROBE_STOW_FEEDRATE, { 245, 114, 20 } } // Move to dock - #define MAG_MOUNTED_STOW_2 { PROBE_STOW_FEEDRATE, { 245, 114, 0 } } // Place probe beside remover - #define MAG_MOUNTED_STOW_3 { PROBE_STOW_FEEDRATE, { 230, 114, 0 } } // Side move to remove probe - #define MAG_MOUNTED_STOW_4 { PROBE_STOW_FEEDRATE, { 210, 114, 20 } } // Side move to remove probe - #define MAG_MOUNTED_STOW_5 { PROBE_STOW_FEEDRATE, { 0, 0, 0 } } // Extra move if needed -#endif - // Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J -// When the pin is defined you can use M672 to set/reset the probe sensitivity. +// When the pin is defined you can use M672 to set/reset the probe sensivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) #define SMART_EFFECTOR_MOD_PIN -1 // Connect a GPIO pin to the Smart Effector MOD pin @@ -1413,55 +953,17 @@ */ //#define SENSORLESS_PROBING -/** - * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe - * Deploys by touching z-axis belt. Retracts by pushing the probe down. - */ -//#define Z_PROBE_ALLEN_KEY -#if ENABLED(Z_PROBE_ALLEN_KEY) - // 2 or 3 sets of coordinates for deploying and retracting the spring loaded touch probe on G29, - // if servo actuated touch probe is not defined. Uncomment as appropriate for your printer/probe. - - #define Z_PROBE_ALLEN_KEY_DEPLOY_1 { 30.0, DELTA_PRINTABLE_RADIUS, 100.0 } - #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE XY_PROBE_FEEDRATE - - #define Z_PROBE_ALLEN_KEY_DEPLOY_2 { 0.0, DELTA_PRINTABLE_RADIUS, 100.0 } - #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 - - #define Z_PROBE_ALLEN_KEY_DEPLOY_3 { 0.0, (DELTA_PRINTABLE_RADIUS) * 0.75, 100.0 } - #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE XY_PROBE_FEEDRATE - - #define Z_PROBE_ALLEN_KEY_STOW_1 { -64.0, 56.0, 23.0 } // Move the probe into position - #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE XY_PROBE_FEEDRATE - - #define Z_PROBE_ALLEN_KEY_STOW_2 { -64.0, 56.0, 3.0 } // Push it down - #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 - - #define Z_PROBE_ALLEN_KEY_STOW_3 { -64.0, 56.0, 50.0 } // Move it up to clear - #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE XY_PROBE_FEEDRATE - - #define Z_PROBE_ALLEN_KEY_STOW_4 { 0.0, 0.0, 50.0 } - #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE XY_PROBE_FEEDRATE - -#endif // Z_PROBE_ALLEN_KEY +// +// For Z_PROBE_ALLEN_KEY see the Delta example configurations. +// /** * Nozzle-to-Probe offsets { X, Y, Z } * - * X and Y offset - * Use a caliper or ruler to measure the distance from the tip of + * - Use a caliper or ruler to measure the distance from the tip of * the Nozzle to the center-point of the Probe in the X and Y axes. - * - * Z offset * - For the Z offset use your best known value and adjust at runtime. - * - Common probes trigger below the nozzle and have negative values for Z offset. - * - Probes triggering above the nozzle height are uncommon but do exist. When using - * probes such as this, carefully set Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES - * to avoid collisions during probing. - * - * Tune and Adjust - * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. - * - PROBE_OFFSET_WIZARD (configuration_adv.h) can be used for setting the Z offset. + * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. * * Assuming the typical work area orientation: * - Probe to RIGHT of the Nozzle has a Positive X offset @@ -1495,47 +997,11 @@ #define XY_PROBE_FEEDRATE (133*60) // Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2) -#define Z_PROBE_FEEDRATE_FAST (4*60) +#define Z_PROBE_FEEDRATE_FAST HOMING_FEEDRATE_Z // Feedrate (mm/min) for the "accurate" probe of each point #define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) -/** - * Probe Activation Switch - * A switch indicating proper deployment, or an optical - * switch triggered when the carriage is near the bed. - */ -//#define PROBE_ACTIVATION_SWITCH -#if ENABLED(PROBE_ACTIVATION_SWITCH) - #define PROBE_ACTIVATION_SWITCH_STATE LOW // State indicating probe is active - //#define PROBE_ACTIVATION_SWITCH_PIN PC6 // Override default pin -#endif - -/** - * Tare Probe (determine zero-point) prior to each probe. - * Useful for a strain gauge or piezo sensor that needs to factor out - * elements such as cables pulling on the carriage. - */ -//#define PROBE_TARE -#if ENABLED(PROBE_TARE) - #define PROBE_TARE_TIME 200 // (ms) Time to hold tare pin - #define PROBE_TARE_DELAY 200 // (ms) Delay after tare before - #define PROBE_TARE_STATE HIGH // State to write pin for tare - //#define PROBE_TARE_PIN PA5 // Override default pin - #if ENABLED(PROBE_ACTIVATION_SWITCH) - //#define PROBE_TARE_ONLY_WHILE_INACTIVE // Fail to tare/probe if PROBE_ACTIVATION_SWITCH is active - #endif -#endif - -/** - * Probe Enable / Disable - * The probe only provides a triggered signal when enabled. - */ -//#define PROBE_ENABLE_DISABLE -#if ENABLED(PROBE_ENABLE_DISABLE) - //#define PROBE_ENABLE_PIN -1 // Override the default pin here -#endif - /** * Multiple Probing * @@ -1592,44 +1058,23 @@ //#define PROBING_HEATERS_OFF // Turn heaters off when probing #if ENABLED(PROBING_HEATERS_OFF) //#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy) - //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude) #endif //#define PROBING_FANS_OFF // Turn fans off when probing -//#define PROBING_ESTEPPERS_OFF // Turn all extruder steppers off when probing -//#define PROBING_STEPPERS_OFF // Turn all steppers off (unless needed to hold position) when probing (including extruders) +//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing //#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors -// Require minimum nozzle and/or bed temperature for probing -//#define PREHEAT_BEFORE_PROBING -#if ENABLED(PREHEAT_BEFORE_PROBING) - #define PROBING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time - #define PROBING_BED_TEMP 50 -#endif - // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 // :{ 0:'Low', 1:'High' } #define X_ENABLE_ON 0 #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders -//#define I_ENABLE_ON 0 -//#define J_ENABLE_ON 0 -//#define K_ENABLE_ON 0 -//#define U_ENABLE_ON 0 -//#define V_ENABLE_ON 0 -//#define W_ENABLE_ON 0 // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! #define DISABLE_X false #define DISABLE_Y false #define DISABLE_Z false -//#define DISABLE_I false -//#define DISABLE_J false -//#define DISABLE_K false -//#define DISABLE_U false -//#define DISABLE_V false -//#define DISABLE_W false // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING @@ -1639,18 +1084,12 @@ #define DISABLE_E false // Disable the extruder when not stepping #define DISABLE_INACTIVE_EXTRUDER // Keep only the active extruder enabled -// @section motion +// @section machine // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. #define INVERT_X_DIR false #define INVERT_Y_DIR true #define INVERT_Z_DIR false -//#define INVERT_I_DIR false -//#define INVERT_J_DIR false -//#define INVERT_K_DIR false -//#define INVERT_U_DIR false -//#define INVERT_V_DIR false -//#define INVERT_W_DIR false // @section extruder @@ -1666,15 +1105,9 @@ // @section homing -//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed. Also enable HOME_AFTER_DEACTIVATE for extra safety. -//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated. Also enable NO_MOTION_BEFORE_HOMING for extra safety. +//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed -/** - * Set Z_IDLE_HEIGHT if the Z-Axis moves on its own when steppers are disabled. - * - Use a low value (i.e., Z_MIN_POS) if the nozzle falls down to the bed. - * - Use a large value (i.e., Z_MAX_POS) if the bed falls down, away from the nozzle. - */ -//#define Z_IDLE_HEIGHT Z_HOME_POS +//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off. //#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... // Be sure to have this much clearance over your Z_MAX_POS to prevent grinding. @@ -1686,38 +1119,20 @@ #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 -//#define I_HOME_DIR -1 -//#define J_HOME_DIR -1 -//#define K_HOME_DIR -1 -//#define U_HOME_DIR -1 -//#define V_HOME_DIR -1 -//#define W_HOME_DIR -1 -// @section geometry +// @section machine -// The size of the printable area +// The size of the print bed #define X_BED_SIZE 200 #define Y_BED_SIZE 200 -// Travel limits (linear=mm, rotational=°) after homing, corresponding to endstop positions. +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 #define X_MAX_POS X_BED_SIZE #define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 -//#define I_MIN_POS 0 -//#define I_MAX_POS 50 -//#define J_MIN_POS 0 -//#define J_MAX_POS 50 -//#define K_MIN_POS 0 -//#define K_MAX_POS 50 -//#define U_MIN_POS 0 -//#define U_MAX_POS 50 -//#define V_MIN_POS 0 -//#define V_MAX_POS 50 -//#define W_MIN_POS 0 -//#define W_MAX_POS 50 /** * Software Endstops @@ -1734,12 +1149,6 @@ #define MIN_SOFTWARE_ENDSTOP_X #define MIN_SOFTWARE_ENDSTOP_Y #define MIN_SOFTWARE_ENDSTOP_Z - #define MIN_SOFTWARE_ENDSTOP_I - #define MIN_SOFTWARE_ENDSTOP_J - #define MIN_SOFTWARE_ENDSTOP_K - #define MIN_SOFTWARE_ENDSTOP_U - #define MIN_SOFTWARE_ENDSTOP_V - #define MIN_SOFTWARE_ENDSTOP_W #endif // Max software endstops constrain movement within maximum coordinate bounds @@ -1748,12 +1157,6 @@ #define MAX_SOFTWARE_ENDSTOP_X #define MAX_SOFTWARE_ENDSTOP_Y #define MAX_SOFTWARE_ENDSTOP_Z - #define MAX_SOFTWARE_ENDSTOP_I - #define MAX_SOFTWARE_ENDSTOP_J - #define MAX_SOFTWARE_ENDSTOP_K - #define MAX_SOFTWARE_ENDSTOP_U - #define MAX_SOFTWARE_ENDSTOP_V - #define MAX_SOFTWARE_ENDSTOP_W #endif #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) @@ -1764,12 +1167,6 @@ * Filament Runout Sensors * Mechanical or opto endstops are used to check for the presence of filament. * - * IMPORTANT: Runout will only trigger if Marlin is aware that a print job is running. - * Marlin knows a print job is running when: - * 1. Running a print job from media started with M24. - * 2. The Print Job Timer has been started with M75. - * 3. The heaters were turned on and PRINTJOB_TIMER_AUTOSTART is enabled. - * * RAMPS-based boards use SERVO3_PIN for the first runout sensor. * For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc. */ @@ -1777,49 +1174,12 @@ #if ENABLED(FILAMENT_RUNOUT_SENSOR) #define FIL_RUNOUT_ENABLED_DEFAULT true // Enable the sensor on startup. Override with M412 followed by M500. #define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each. - #define FIL_RUNOUT_STATE LOW // Pin state indicating that filament is NOT present. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins. //#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins. - //#define WATCH_ALL_RUNOUT_SENSORS // Execute runout script on any triggering sensor, not only for the active extruder. - // This is automatically enabled for MIXING_EXTRUDERs. - - // Override individually if the runout sensors vary - //#define FIL_RUNOUT1_STATE LOW - //#define FIL_RUNOUT1_PULLUP - //#define FIL_RUNOUT1_PULLDOWN - //#define FIL_RUNOUT2_STATE LOW - //#define FIL_RUNOUT2_PULLUP - //#define FIL_RUNOUT2_PULLDOWN - - //#define FIL_RUNOUT3_STATE LOW - //#define FIL_RUNOUT3_PULLUP - //#define FIL_RUNOUT3_PULLDOWN - - //#define FIL_RUNOUT4_STATE LOW - //#define FIL_RUNOUT4_PULLUP - //#define FIL_RUNOUT4_PULLDOWN - - //#define FIL_RUNOUT5_STATE LOW - //#define FIL_RUNOUT5_PULLUP - //#define FIL_RUNOUT5_PULLDOWN - - //#define FIL_RUNOUT6_STATE LOW - //#define FIL_RUNOUT6_PULLUP - //#define FIL_RUNOUT6_PULLDOWN - - //#define FIL_RUNOUT7_STATE LOW - //#define FIL_RUNOUT7_PULLUP - //#define FIL_RUNOUT7_PULLDOWN - - //#define FIL_RUNOUT8_STATE LOW - //#define FIL_RUNOUT8_PULLUP - //#define FIL_RUNOUT8_PULLDOWN - - // Commands to execute on filament runout. - // With multiple runout sensors use the %c placeholder for the current tool in commands (e.g., "M600 T%c") - // NOTE: After 'M412 H1' the host handles filament runout and this script does not apply. + // Set one or more commands to execute on filament runout. + // (After 'M412 H' Marlin will ask the host to handle the process.) #define FILAMENT_RUNOUT_SCRIPT "M600" // After a runout is detected, continue printing this length of filament @@ -1880,30 +1240,10 @@ //#define MESH_BED_LEVELING /** - * Normally G28 leaves leveling disabled on completion. Enable one of - * these options to restore the prior leveling state or to always enable - * leveling immediately after G28. + * Normally G28 leaves leveling disabled on completion. Enable + * this option to have G28 restore the prior leveling state. */ //#define RESTORE_LEVELING_AFTER_G28 -//#define ENABLE_LEVELING_AFTER_G28 - -/** - * Auto-leveling needs preheating - */ -//#define PREHEAT_BEFORE_LEVELING -#if ENABLED(PREHEAT_BEFORE_LEVELING) - #define LEVELING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time - #define LEVELING_BED_TEMP 50 -#endif - -/** - * Bed Distance Sensor - * - * Measures the distance from bed to nozzle with accuracy of 0.01mm. - * For information about this sensor https://github.com/markniu/Bed_Distance_sensor - * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. - */ -//#define BD_SENSOR /** * Enable detailed logging of G28, G29, M48, etc. @@ -1912,19 +1252,11 @@ */ //#define DEBUG_LEVELING_FEATURE -#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL, PROBE_MANUALLY) - // Set a height for the start of manual adjustment - #define MANUAL_PROBE_START_Z 0.2 // (mm) Comment out to use the last-measured height -#endif - #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL) // Gradually reduce leveling correction until a set height is reached, // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z #define ENABLE_LEVELING_FADE_HEIGHT - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - #define DEFAULT_LEVELING_FADE_HEIGHT 10.0 // (mm) Default fade height. - #endif // For Cartesian machines, instead of dividing moves on mesh boundaries, // split up moves into short segments like a Delta. This follows the @@ -1938,11 +1270,10 @@ //#define G26_MESH_VALIDATION #if ENABLED(G26_MESH_VALIDATION) #define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle. - #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for G26. - #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for G26. - #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for G26. - #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for G26 XY moves. - #define G26_XY_FEEDRATE_TRAVEL 100 // (mm/s) Feedrate for G26 XY travel moves. + #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool. + #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool. + #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for the G26 Mesh Validation Tool. + #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for XY Moves for the G26 Mesh Validation Tool. #define G26_RETRACT_MULTIPLIER 1.0 // G26 Q (retraction) used by default between mesh test elements. #endif @@ -1987,16 +1318,12 @@ #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - //#define UBL_HILBERT_CURVE // Use Hilbert distribution for less travel when probing multiple points - #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500 //#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used // as the Z-Height correction value. - //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh - #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== @@ -2024,38 +1351,13 @@ #endif // Add a menu item to move between bed corners for manual bed adjustment -//#define LCD_BED_TRAMMING - -#if ENABLED(LCD_BED_TRAMMING) - #define BED_TRAMMING_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets - #define BED_TRAMMING_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points - #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points - //#define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner - //#define BED_TRAMMING_USE_PROBE - #if ENABLED(BED_TRAMMING_USE_PROBE) - #define BED_TRAMMING_PROBE_TOLERANCE 0.1 // (mm) - #define BED_TRAMMING_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify - //#define BED_TRAMMING_AUDIO_FEEDBACK - #endif +//#define LEVEL_BED_CORNERS - /** - * Corner Leveling Order - * - * Set 2 or 4 points. When 2 points are given, the 3rd is the center of the opposite edge. - * - * LF Left-Front RF Right-Front - * LB Left-Back RB Right-Back - * - * Examples: - * - * Default {LF,RB,LB,RF} {LF,RF} {LB,LF} - * LB --------- RB LB --------- RB LB --------- RB LB --------- RB - * | 4 3 | | 3 2 | | <3> | | 1 | - * | | | | | | | <3>| - * | 1 2 | | 1 4 | | 1 2 | | 2 | - * LF --------- RF LF --------- RF LF --------- RF LF --------- RF - */ - #define BED_TRAMMING_LEVELING_ORDER { LF, RF, RB, LB } +#if ENABLED(LEVEL_BED_CORNERS) + #define LEVEL_CORNERS_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets + #define LEVEL_CORNERS_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points + #define LEVEL_CORNERS_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points + //#define LEVEL_CENTER_TOO // Move to the center after the last corner #endif /** @@ -2074,20 +1376,16 @@ //#define MANUAL_X_HOME_POS 0 //#define MANUAL_Y_HOME_POS 0 //#define MANUAL_Z_HOME_POS 0 -//#define MANUAL_I_HOME_POS 0 -//#define MANUAL_J_HOME_POS 0 -//#define MANUAL_K_HOME_POS 0 -//#define MANUAL_U_HOME_POS 0 -//#define MANUAL_V_HOME_POS 0 -//#define MANUAL_W_HOME_POS 0 -/** - * Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. - * - * - Moves the Z probe (or nozzle) to a defined XY point before Z homing. - * - Allows Z homing only when XY positions are known and trusted. - * - If stepper drivers sleep, XY homing may be required again before Z homing. - */ +// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. +// +// With this feature enabled: +// +// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. +// - If stepper drivers time out, it will need X and Y homing again before Z homing. +// - Move the Z probe (or nozzle) to a defined XY point before Z Homing. +// - Prevent Z homing when the Z probe is outside bed area. +// //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) @@ -2095,7 +1393,7 @@ #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing #endif -// Homing speeds (linear=mm/min, rotational=°/min) +// Homing speeds (mm/min) #define HOMING_FEEDRATE_MM_M { (50*60), (50*60), (4*60) } // Validate that endstops are triggered on homing moves @@ -2139,8 +1437,9 @@ #define XY_DIAG_BD 282.8427124746 #define XY_SIDE_AD 200 - // Or, set the XY skew factor directly: - //#define XY_SKEW_FACTOR 0.0 + // Or, set the default skew factors directly here + // to override the above measurements: + #define XY_SKEW_FACTOR 0.0 //#define SKEW_CORRECTION_FOR_Z #if ENABLED(SKEW_CORRECTION_FOR_Z) @@ -2149,10 +1448,8 @@ #define YZ_DIAG_AC 282.8427124746 #define YZ_DIAG_BD 282.8427124746 #define YZ_SIDE_AD 200 - - // Or, set the Z skew factors directly: - //#define XZ_SKEW_FACTOR 0.0 - //#define YZ_SKEW_FACTOR 0.0 + #define XZ_SKEW_FACTOR 0.0 + #define YZ_SKEW_FACTOR 0.0 #endif // Enable this option for M852 to set skew at runtime @@ -2163,7 +1460,7 @@ //============================= Additional Features =========================== //============================================================================= -// @section eeprom +// @section extras /** * EEPROM @@ -2175,16 +1472,13 @@ * M502 - Revert settings to "factory" defaults. (Follow with M500 to init the EEPROM.) */ //#define EEPROM_SETTINGS // Persistent storage with M500 and M501 -//#define DISABLE_M503 // Saves ~2700 bytes of flash. Disable for release! +//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! #define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. #define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load #if ENABLED(EEPROM_SETTINGS) //#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors. - //#define EEPROM_INIT_NOW // Init EEPROM on first boot after a new build. #endif -// @section host - // // Host Keepalive // @@ -2195,8 +1489,6 @@ #define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113. #define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating -// @section units - // // G20/G21 Inch mode support // @@ -2209,23 +1501,17 @@ // @section temperature -// -// Preheat Constants - Up to 10 are supported without changes -// +// Preheat Constants #define PREHEAT_1_LABEL "PLA" #define PREHEAT_1_TEMP_HOTEND 180 #define PREHEAT_1_TEMP_BED 70 -#define PREHEAT_1_TEMP_CHAMBER 35 #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 #define PREHEAT_2_LABEL "ABS" #define PREHEAT_2_TEMP_HOTEND 240 #define PREHEAT_2_TEMP_BED 110 -#define PREHEAT_2_TEMP_CHAMBER 35 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// @section motion - /** * Nozzle Park * @@ -2242,7 +1528,8 @@ #if ENABLED(NOZZLE_PARK_FEATURE) // Specify a park position as { X, Y, Z_raise } #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } - #define NOZZLE_PARK_MOVE 0 // Park motion: 0 = XY Move, 1 = X Only, 2 = Y Only, 3 = X before Y, 4 = Y before X + //#define NOZZLE_PARK_X_ONLY // X move only is required to park + //#define NOZZLE_PARK_Y_ONLY // Y move only is required to park #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance #define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis) #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) @@ -2284,6 +1571,7 @@ * * Caveats: The ending Z should be the same as starting Z. * Attention: EXPERIMENTAL. G-code arguments may change. + * */ //#define NOZZLE_CLEAN_FEATURE @@ -2315,34 +1603,19 @@ // For a purge/clean station mounted on the X axis //#define NOZZLE_CLEAN_NO_Y - // Require a minimum hotend temperature for cleaning - #define NOZZLE_CLEAN_MIN_TEMP 170 - //#define NOZZLE_CLEAN_HEATUP // Heat up the nozzle instead of skipping wipe - // Explicit wipe G-code script applies to a G12 with no arguments. //#define WIPE_SEQUENCE_COMMANDS "G1 X-17 Y25 Z10 F4000\nG1 Z1\nM114\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 Z15\nM400\nG0 X-10.0 Y-9.0" #endif -// @section host - /** * Print Job Timer * - * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191. - * The print job timer will only be stopped if the bed/chamber target temp is - * below BED_MINTEMP/CHAMBER_MINTEMP. - * - * M104 (hotend, no wait) - high temp = none, low temp = stop timer - * M109 (hotend, wait) - high temp = start timer, low temp = stop timer - * M140 (bed, no wait) - high temp = none, low temp = stop timer - * M190 (bed, wait) - high temp = start timer, low temp = none - * M141 (chamber, no wait) - high temp = none, low temp = stop timer - * M191 (chamber, wait) - high temp = start timer, low temp = none + * Automatically start and stop the print job timer on M104/M109/M190. * - * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2. - * For M140/M190, high temp is anything over BED_MINTEMP. - * For M141/M191, high temp is anything over CHAMBER_MINTEMP. + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none * * The timer can also be controlled with the following commands: * @@ -2352,8 +1625,6 @@ */ #define PRINTJOB_TIMER_AUTOSTART -// @section stats - /** * Print Counter * @@ -2367,11 +1638,6 @@ * View the current statistics with M78. */ //#define PRINTCOUNTER -#if ENABLED(PRINTCOUNTER) - #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print. A value of 0 will save stats at end of print. -#endif - -// @section security /** * Password @@ -2408,17 +1674,17 @@ //============================= LCD and SD support ============================ //============================================================================= -// @section interface +// @section lcd /** * LCD LANGUAGE * * Select the language to display on the LCD. These languages are available: * - * en, an, bg, ca, cz, da, de, el, el_CY, es, eu, fi, fr, gl, hr, hu, it, - * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW + * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it, + * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, tr, uk, vi, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek (Greece)', 'el_CY':'Greek (Cyprus)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' } */ #define LCD_LANGUAGE en @@ -2447,9 +1713,9 @@ #define DISPLAY_CHARSET_HD44780 JAPANESE /** - * Info Screen Style (0:Classic, 1:Průša) + * Info Screen Style (0:Classic, 1:Pruša) * - * :[0:'Classic', 1:'Průša'] + * :[0:'Classic', 1:'Pruša'] */ #define LCD_INFO_SCREEN_STYLE 0 @@ -2458,9 +1724,20 @@ * * SD Card support is disabled by default. If your controller has an SD slot, * you must uncomment the following option or it won't work. + * */ //#define SDSUPPORT +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ +//#define SPI_SPEED SPI_HALF_SPEED +//#define SPI_SPEED SPI_QUARTER_SPEED +//#define SPI_SPEED SPI_EIGHTH_SPEED + /** * SD CARD: ENABLE CRC * @@ -2524,23 +1801,12 @@ // //#define REVERSE_SELECT_DIRECTION -// -// Encoder EMI Noise Filter -// -// This option increases encoder samples to filter out phantom encoder clicks caused by EMI noise. -// -//#define ENCODER_NOISE_FILTER -#if ENABLED(ENCODER_NOISE_FILTER) - #define ENCODER_SAMPLES 10 -#endif - // // Individual Axis Homing // // Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. // //#define INDIVIDUAL_AXIS_HOMING_MENU -//#define INDIVIDUAL_AXIS_HOMING_SUBMENU // // SPEAKER/BUZZER @@ -2564,7 +1830,6 @@ //======================== LCD / Controller Selection ========================= //======================== (Character-based LCDs) ========================= //============================================================================= -// @section lcd // // RepRapDiscount Smart Controller. @@ -2574,14 +1839,6 @@ // //#define REPRAP_DISCOUNT_SMART_CONTROLLER -// -// GT2560 (YHCB2004) LCD Display -// -// Requires Testato, Koepel softwarewire library and -// Andriy Golovnya's LiquidCrystal_AIP31068 library. -// -//#define YHCB2004 - // // Original RADDS LCD Display+Encoder+SDCardReader // http://doku.radds.org/dokumentation/lcd-display/ @@ -2704,14 +1961,6 @@ // //#define FF_INTERFACEBOARD -// -// TFT GLCD Panel with Marlin UI -// Panel connected to main board by SPI or I2C interface. -// See https://github.com/Serhiy-K/TFTGLCDAdapter -// -//#define TFTGLCD_PANEL_SPI -//#define TFTGLCD_PANEL_I2C - //============================================================================= //======================= LCD / Controller Selection ======================= //========================= (Graphical LCDs) ======================== @@ -2732,11 +1981,6 @@ // //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER -// -// K.3D Full Graphic Smart Controller -// -//#define K3D_FULL_GRAPHIC_SMART_CONTROLLER - // // ReprapWorld Graphical LCD // https://reprapworld.com/?products_details&products_id/1218 @@ -2751,11 +1995,6 @@ //#define VIKI2 //#define miniVIKI -// -// Alfawise Ex8 printer LCD marked as WYH L12864 COG -// -//#define WYH_L12864 - // // MakerLab Mini Panel with graphic // controller and SD support - https://reprap.org/wiki/Mini_panel @@ -2803,17 +2042,11 @@ // //#define MKS_MINI_12864 -// -// MKS MINI12864 V3 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. -// -//#define MKS_MINI_12864_V3 - // // MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout. // https://www.aliexpress.com/item/33018110072.html // -//#define MKS_LCD12864A -//#define MKS_LCD12864B +//#define MKS_LCD12864 // // FYSETC variant of the MINI12864 graphic controller with SD support @@ -2825,11 +2058,6 @@ //#define FYSETC_MINI_12864_2_1 // Type A/B. NeoPixel RGB Backlight //#define FYSETC_GENERIC_12864_1_1 // Larger display with basic ON/OFF backlight. -// -// BigTreeTech Mini 12864 V1.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. -// -//#define BTT_MINI_12864_V1 - // // Factory display for Creality CR-10 // https://www.aliexpress.com/item/32833148327.html @@ -2849,10 +2077,9 @@ // // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 // A clone of the RepRapDiscount full graphics display but with -// different pins/wiring (see pins_ANET_10.h). Enable one of these. +// different pins/wiring (see pins_ANET_10.h). // //#define ANET_FULL_GRAPHICS_LCD -//#define ANET_FULL_GRAPHICS_LCD_ALT_WIRING // // AZSMZ 12864 LCD with SD @@ -2866,12 +2093,6 @@ // //#define SILVER_GATE_GLCD_CONTROLLER -// -// eMotion Tech LCD with SD -// https://www.reprap-france.com/produit/1234568748-ecran-graphique-128-x-64-points-2-1 -// -//#define EMOTION_TECH_LCD - //============================================================================= //============================== OLED Displays ============================== //============================================================================= @@ -2896,7 +2117,7 @@ //#define OLED_PANEL_TINYBOY2 // -// MKS OLED 1.3" 128×64 Full Graphics Controller +// MKS OLED 1.3" 128×64 FULL GRAPHICS CONTROLLER // https://reprap.org/wiki/MKS_12864OLED // // Tiny, but very sharp OLED display @@ -2905,7 +2126,7 @@ //#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller // -// Zonestar OLED 128×64 Full Graphics Controller +// Zonestar OLED 128×64 FULL GRAPHICS CONTROLLER // //#define ZONESTAR_12864LCD // Graphical (DOGM) with ST7920 controller //#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller (default) @@ -2922,59 +2143,22 @@ //#define OVERLORD_OLED // -// FYSETC OLED 2.42" 128×64 Full Graphics Controller with WS2812 RGB +// FYSETC OLED 2.42" 128×64 FULL GRAPHICS CONTROLLER with WS2812 RGB // Where to find : https://www.aliexpress.com/item/4000345255731.html //#define FYSETC_242_OLED_12864 // Uses the SSD1309 controller -// -// K.3D SSD1309 OLED 2.42" 128×64 Full Graphics Controller -// -//#define K3D_242_OLED_CONTROLLER // Software SPI - //============================================================================= //========================== Extensible UI Displays =========================== //============================================================================= -/** - * DGUS Touch Display with DWIN OS. (Choose one.) - * ORIGIN : https://www.aliexpress.com/item/32993409517.html - * FYSETC : https://www.aliexpress.com/item/32961471929.html - * MKS : https://www.aliexpress.com/item/1005002008179262.html - * - * Flash display with DGUS Displays for Marlin: - * - Format the SD card to FAT32 with an allocation size of 4kb. - * - Download files as specified for your type of display. - * - Plug the microSD card into the back of the display. - * - Boot the display and wait for the update to complete. - * - * ORIGIN (Marlin DWIN_SET) - * - Download https://github.com/coldtobi/Marlin_DGUS_Resources - * - Copy the downloaded DWIN_SET folder to the SD card. - * - * FYSETC (Supplier default) - * - Download https://github.com/FYSETC/FYSTLCD-2.0 - * - Copy the downloaded SCREEN folder to the SD card. - * - * HIPRECY (Supplier default) - * - Download https://github.com/HiPrecy/Touch-Lcd-LEO - * - Copy the downloaded DWIN_SET folder to the SD card. - * - * MKS (MKS-H43) (Supplier default) - * - Download https://github.com/makerbase-mks/MKS-H43 - * - Copy the downloaded DWIN_SET folder to the SD card. - * - * RELOADED (T5UID1) - * - Download https://github.com/Desuuuu/DGUS-reloaded/releases - * - Copy the downloaded DWIN_SET folder to the SD card. - */ +// +// DGUS Touch Display with DWIN OS. (Choose one.) +// ORIGIN : https://www.aliexpress.com/item/32993409517.html +// FYSETC : https://www.aliexpress.com/item/32961471929.html +// //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC //#define DGUS_LCD_UI_HIPRECY -//#define DGUS_LCD_UI_MKS -//#define DGUS_LCD_UI_RELOADED -#if ENABLED(DGUS_LCD_UI_MKS) - #define USE_MKS_GREEN_UI -#endif // // Touch-screen LCD for Malyan M200/M300 printers @@ -2993,18 +2177,13 @@ //#define ANYCUBIC_LCD_I3MEGA //#define ANYCUBIC_LCD_CHIRON #if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) + #define ANYCUBIC_LCD_SERIAL_PORT 3 //#define ANYCUBIC_LCD_DEBUG - //#define ANYCUBIC_LCD_GCODE_EXT // Add ".gcode" to menu entries for DGUS clone compatibility #endif -// -// 320x240 Nextion 2.8" serial TFT Resistive Touch Screen NX3224T028 -// -//#define NEXTION_TFT - // // Third-party or vendor-customized controller interfaces. -// Sources should be installed in 'src/lcd/extui'. +// Sources should be installed in 'src/lcd/extensible_ui'. // //#define EXTENSIBLE_UI @@ -3016,133 +2195,43 @@ //=============================== Graphical TFTs ============================== //============================================================================= -/** - * Specific TFT Model Presets. Enable one of the following options - * or enable TFT_GENERIC and set sub-options. - */ - -// -// 480x320, 3.5", SPI Display with Rotary Encoder from MKS -// Usually paired with MKS Robin Nano V2 & V3 -// -//#define MKS_TS35_V2_0 - -// -// 320x240, 2.4", FSMC Display From MKS -// Usually paired with MKS Robin Nano V1.2 -// -//#define MKS_ROBIN_TFT24 - -// -// 320x240, 2.8", FSMC Display From MKS -// Usually paired with MKS Robin Nano V1.2 -// -//#define MKS_ROBIN_TFT28 - -// -// 320x240, 3.2", FSMC Display From MKS -// Usually paired with MKS Robin Nano V1.2 -// -//#define MKS_ROBIN_TFT32 - -// -// 480x320, 3.5", FSMC Display From MKS -// Usually paired with MKS Robin Nano V1.2 -// -//#define MKS_ROBIN_TFT35 - -// -// 480x272, 4.3", FSMC Display From MKS -// -//#define MKS_ROBIN_TFT43 - -// -// 320x240, 3.2", FSMC Display From MKS -// Usually paired with MKS Robin -// -//#define MKS_ROBIN_TFT_V1_1R - // -// 480x320, 3.5", FSMC Stock Display from Tronxy +// TFT display with optional touch screen +// Color Marlin UI with standard menu system // -//#define TFT_TRONXY_X5SA +//#define TFT_320x240 +//#define TFT_320x240_SPI +//#define TFT_480x320 +//#define TFT_480x320_SPI // -// 480x320, 3.5", FSMC Stock Display from AnyCubic +// Skip autodetect and force specific TFT driver +// Mandatory for SPI screens with no MISO line +// Available drivers are: ST7735, ST7789, ST7796, R61505, ILI9328, ILI9341, ILI9488 // -//#define ANYCUBIC_TFT35 +//#define TFT_DRIVER AUTO // -// 320x240, 2.8", FSMC Stock Display from Longer/Alfawise +// SPI display (MKS Robin Nano V2.0, MKS Gen L V2.0) +// Upscaled 128x64 Marlin UI // -//#define LONGER_LK_TFT28 +//#define SPI_GRAPHICAL_TFT // -// 320x240, 2.8", FSMC Stock Display from ET4 +// FSMC display (MKS Robin, Alfawise U20, JGAurora A5S, REXYZ A1, etc.) +// Upscaled 128x64 Marlin UI // -//#define ANET_ET4_TFT28 +//#define FSMC_GRAPHICAL_TFT // -// 480x320, 3.5", FSMC Stock Display from ET5 -// -//#define ANET_ET5_TFT35 - -// -// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU-BX -// -//#define BIQU_BX_TFT70 - -// -// 480x320, 3.5", SPI Stock Display with Rotary Encoder from BIQU B1 SE Series -// -//#define BTT_TFT35_SPI_V1_0 - +// TFT LVGL UI // -// Generic TFT with detailed options +// Using default MKS icons and fonts from: https://git.io/JJvzK +// Just copy the 'assets' folder from the build directory to the +// root of your SD card, together with the compiled firmware. // -//#define TFT_GENERIC -#if ENABLED(TFT_GENERIC) - // :[ 'AUTO', 'ST7735', 'ST7789', 'ST7796', 'R61505', 'ILI9328', 'ILI9341', 'ILI9488' ] - #define TFT_DRIVER AUTO - - // Interface. Enable one of the following options: - //#define TFT_INTERFACE_FSMC - //#define TFT_INTERFACE_SPI - - // TFT Resolution. Enable one of the following options: - //#define TFT_RES_320x240 - //#define TFT_RES_480x272 - //#define TFT_RES_480x320 - //#define TFT_RES_1024x600 -#endif - -/** - * TFT UI - User Interface Selection. Enable one of the following options: - * - * TFT_CLASSIC_UI - Emulated DOGM - 128x64 Upscaled - * TFT_COLOR_UI - Marlin Default Menus, Touch Friendly, using full TFT capabilities - * TFT_LVGL_UI - A Modern UI using LVGL - * - * For LVGL_UI also copy the 'assets' folder from the build directory to the - * root of your SD card, together with the compiled firmware. - */ -//#define TFT_CLASSIC_UI -//#define TFT_COLOR_UI -//#define TFT_LVGL_UI - -#if ENABLED(TFT_LVGL_UI) - //#define MKS_WIFI_MODULE // MKS WiFi module -#endif - -/** - * TFT Rotation. Set to one of the following values: - * - * TFT_ROTATE_90, TFT_ROTATE_90_MIRROR_X, TFT_ROTATE_90_MIRROR_Y, - * TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y, - * TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y, - * TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION - */ -//#define TFT_ROTATION TFT_NO_ROTATION +//#define TFT_LVGL_UI_FSMC // Robin nano v1.2 uses FSMC +//#define TFT_LVGL_UI_SPI // Robin nano v2.0 uses SPI //============================================================================= //============================ Other Controllers ============================ @@ -3151,38 +2240,22 @@ // // Ender-3 v2 OEM display. A DWIN display with Rotary Encoder. // -//#define DWIN_CREALITY_LCD // Creality UI -//#define DWIN_LCD_PROUI // Pro UI by MRiscoC -//#define DWIN_CREALITY_LCD_JYERSUI // Jyers UI by Jacob Myers -//#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) -//#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) +//#define DWIN_CREALITY_LCD // -// Touch Screen Settings +// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 // //#define TOUCH_SCREEN #if ENABLED(TOUCH_SCREEN) - #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens - #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus - - //#define DISABLE_ENCODER // Disable the click encoder, if any - //#define TOUCH_IDLE_SLEEP_MINS 5 // (minutes) Display Sleep after a period of inactivity. Set with M255 S. + #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens + #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus #define TOUCH_SCREEN_CALIBRATION - //#define TOUCH_CALIBRATION_X 12316 - //#define TOUCH_CALIBRATION_Y -8981 - //#define TOUCH_OFFSET_X -43 - //#define TOUCH_OFFSET_Y 257 - //#define TOUCH_ORIENTATION TOUCH_LANDSCAPE - - #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) - #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM - #endif - - #if ENABLED(TFT_COLOR_UI) - //#define SINGLE_TOUCH_NAVIGATION - #endif + //#define XPT2046_X_CALIBRATION 12316 + //#define XPT2046_Y_CALIBRATION -8981 + //#define XPT2046_X_OFFSET -43 + //#define XPT2046_Y_OFFSET 257 #endif // @@ -3192,21 +2265,19 @@ //#define REPRAPWORLD_KEYPAD //#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press -// -// EasyThreeD ET-4000+ with button input and status LED -// -//#define EASYTHREED_UI - //============================================================================= //=============================== Extra Features ============================== //============================================================================= -// @section fans +// @section extras // Set number of user-controlled fans. Disable to use all board-defined fans. // :[1,2,3,4,5,6,7,8] //#define NUM_M106_FANS 1 +// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino +//#define FAST_PWM_FAN + // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency // which is not as annoying as with the hardware PWM. On the other hand, if this frequency // is too low, you should also increment SOFT_PWM_SCALE. @@ -3225,18 +2296,17 @@ // duty cycle is attained. //#define SOFT_PWM_DITHER -// @section extras - -// Support for the BariCUDA Paste Extruder -//#define BARICUDA - -// @section lights - // Temperature status LEDs that display the hotend and bed temperature. // If all hotends, bed temperature, and target temperature are under 54C // then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) //#define TEMP_STAT_LEDS +// SkeinForge sends the wrong arc G-codes when using Arc Point as fillet procedure +//#define SF_ARC_FIX + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + // Support for BlinkM/CyzRgb //#define BLINKM @@ -3257,19 +2327,17 @@ * luminance values can be set from 0 to 255. * For NeoPixel LED an overall brightness parameter is also available. * - * === CAUTION === + * *** CAUTION *** * LED Strips require a MOSFET Chip between PWM lines and LEDs, * as the Arduino cannot handle the current the LEDs will require. * Failure to follow this precaution can destroy your Arduino! - * * NOTE: A separate 5V power supply is required! The NeoPixel LED needs * more current than the Arduino 5V linear regulator can produce. + * *** CAUTION *** + * + * LED Type. Enable only one of the following two options. * - * Requires PWM frequency between 50 <> 100Hz (Check HAL or variant) - * Use FAST_PWM_FAN, if possible, to reduce fan noise. */ - -// LED Type. Enable only one of the following two options: //#define RGB_LED //#define RGBW_LED @@ -3278,40 +2346,33 @@ //#define RGB_LED_G_PIN 43 //#define RGB_LED_B_PIN 35 //#define RGB_LED_W_PIN -1 - //#define RGB_STARTUP_TEST // For PWM pins, fade between all colors - #if ENABLED(RGB_STARTUP_TEST) - #define RGB_STARTUP_TEST_INNER_MS 10 // (ms) Reduce or increase fading speed - #endif #endif // Support for Adafruit NeoPixel LED driver //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) - #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW, NEO_RGBW, NEO_GRB, NEO_RBG, etc. - // See https://github.com/adafruit/Adafruit_NeoPixel/blob/master/Adafruit_NeoPixel.h - //#define NEOPIXEL_PIN 4 // LED driving pin - //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE - //#define NEOPIXEL2_PIN 5 - #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) - #define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once. - #define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255) - //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup + #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) + #define NEOPIXEL_PIN 4 // LED driving pin + //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE + //#define NEOPIXEL2_PIN 5 + #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) + #define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once. + #define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255) + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup // Support for second Adafruit NeoPixel LED driver controlled with M150 S1 ... //#define NEOPIXEL2_SEPARATE #if ENABLED(NEOPIXEL2_SEPARATE) - #define NEOPIXEL2_PIXELS 15 // Number of LEDs in the second strip - #define NEOPIXEL2_BRIGHTNESS 127 // Initial brightness (0-255) - #define NEOPIXEL2_STARTUP_TEST // Cycle through colors at startup + #define NEOPIXEL2_PIXELS 15 // Number of LEDs in the second strip + #define NEOPIXEL2_BRIGHTNESS 127 // Initial brightness (0-255) + #define NEOPIXEL2_STARTUP_TEST // Cycle through colors at startup #else - //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel + //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif - // Use some of the NeoPixel LEDs for static (background) lighting - //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED - //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W - //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off + // Use a single NeoPixel LED for static (background) lighting + //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W #endif /** @@ -3329,18 +2390,21 @@ #define PRINTER_EVENT_LEDS #endif -// @section servos +/** + * R/C SERVO support + * Sponsored by TrinityLabs, Reworked by codexmas + */ /** * Number of servos * * For some servo-related options NUM_SERVOS will be set automatically. * Set this manually if there are extra servos needing manual control. - * Set to 0 to turn off servo support. + * Leave undefined or set to 0 to entirely disable the servo subsystem. */ -//#define NUM_SERVOS 3 // Note: Servo index starts with 0 for M280-M282 commands +//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command -// (ms) Delay before the next move will start, to give the servo time to reach its target angle. +// (ms) Delay before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. #define SERVO_DELAY { 300 } @@ -3348,8 +2412,5 @@ // Only power servos during movement, otherwise leave off to prevent jitter //#define DEACTIVATE_SERVOS_AFTER_MOVE -// Edit servo angles with M281 and save to EEPROM with M500 -//#define EDITABLE_SERVO_ANGLES - -// Disable servo with M282 to reduce power consumption, noise, and heat when not in use -//#define SERVO_DETACH_GCODE +// Allow servo angle to be edited and saved to EEPROM +//#define EDITABLE_SERVO_ANGLES \ No newline at end of file diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 9a54b10b82b1..06dca33a8579 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -29,31 +29,15 @@ * Some of these settings can damage your printer if improperly set! * * Basic settings can be found in Configuration.h + * */ #define CONFIGURATION_ADV_H_VERSION 02010200 -// @section develop - -/** - * Configuration Export - * - * Export the configuration as part of the build. (See signature.py) - * Output files are saved with the build (e.g., .pio/build/mega2560). - * - * See `build_all_examples --ini` as an example of config.ini archiving. - * - * 1 = marlin_config.json - Dictionary containing the configuration. - * This file is also generated for CONFIGURATION_EMBEDDING. - * 2 = config.ini - File format for PlatformIO preprocessing. - * 3 = schema.json - The entire configuration schema. (13 = pattern groups) - * 4 = schema.yml - The entire configuration schema. - */ -//#define CONFIG_EXPORT 2 // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] +// @section temperature //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== -// @section temperature /** * Thermocouple sensors are quite sensitive to noise. Any noise induced in @@ -72,126 +56,69 @@ // Custom Thermistor 1000 parameters // #if TEMP_SENSOR_0 == 1000 - #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND0_BETA 3950 // Beta value - #define HOTEND0_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND0_BETA 3950 // Beta value #endif #if TEMP_SENSOR_1 == 1000 - #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND1_BETA 3950 // Beta value - #define HOTEND1_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND1_BETA 3950 // Beta value #endif #if TEMP_SENSOR_2 == 1000 - #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND2_BETA 3950 // Beta value - #define HOTEND2_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND2_BETA 3950 // Beta value #endif #if TEMP_SENSOR_3 == 1000 - #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND3_BETA 3950 // Beta value - #define HOTEND3_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND3_BETA 3950 // Beta value #endif #if TEMP_SENSOR_4 == 1000 - #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND4_BETA 3950 // Beta value - #define HOTEND4_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND4_BETA 3950 // Beta value #endif #if TEMP_SENSOR_5 == 1000 - #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND5_BETA 3950 // Beta value - #define HOTEND5_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND5_BETA 3950 // Beta value #endif #if TEMP_SENSOR_6 == 1000 - #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND6_BETA 3950 // Beta value - #define HOTEND6_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND6_BETA 3950 // Beta value #endif #if TEMP_SENSOR_7 == 1000 - #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND7_BETA 3950 // Beta value - #define HOTEND7_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND7_BETA 3950 // Beta value #endif #if TEMP_SENSOR_BED == 1000 - #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define BED_BETA 3950 // Beta value - #define BED_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BED_BETA 3950 // Beta value #endif #if TEMP_SENSOR_CHAMBER == 1000 - #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define CHAMBER_BETA 3950 // Beta value - #define CHAMBER_SH_C_COEFF 0 // Steinhart-Hart C coefficient -#endif - -#if TEMP_SENSOR_COOLER == 1000 - #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define COOLER_BETA 3950 // Beta value - #define COOLER_SH_C_COEFF 0 // Steinhart-Hart C coefficient -#endif - -#if TEMP_SENSOR_PROBE == 1000 - #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define PROBE_BETA 3950 // Beta value - #define PROBE_SH_C_COEFF 0 // Steinhart-Hart C coefficient -#endif - -#if TEMP_SENSOR_BOARD == 1000 - #define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define BOARD_BETA 3950 // Beta value - #define BOARD_SH_C_COEFF 0 // Steinhart-Hart C coefficient -#endif - -#if TEMP_SENSOR_REDUNDANT == 1000 - #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define REDUNDANT_BETA 3950 // Beta value - #define REDUNDANT_SH_C_COEFF 0 // Steinhart-Hart C coefficient + #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define CHAMBER_BETA 3950 // Beta value #endif -/** - * Thermocouple Options — for MAX6675 (-2), MAX31855 (-3), and MAX31865 (-5). - */ -//#define TEMP_SENSOR_FORCE_HW_SPI // Ignore SCK/MOSI/MISO pins; use CS and the default SPI bus. -//#define MAX31865_SENSOR_WIRES_0 2 // (2-4) Number of wires for the probe connected to a MAX31865 board. -//#define MAX31865_SENSOR_WIRES_1 2 -//#define MAX31865_SENSOR_WIRES_2 2 - -//#define MAX31865_50HZ_FILTER // Use a 50Hz filter instead of the default 60Hz. -//#define MAX31865_USE_READ_ERROR_DETECTION // Treat value spikes (20°C delta in under 1s) as read errors. - -//#define MAX31865_USE_AUTO_MODE // Read faster and more often than 1-shot; bias voltage always on; slight effect on RTD temperature. -//#define MAX31865_MIN_SAMPLING_TIME_MSEC 100 // (ms) 1-shot: minimum read interval. Reduces bias voltage effects by leaving sensor unpowered for longer intervals. -//#define MAX31865_IGNORE_INITIAL_FAULTY_READS 10 // Ignore some read faults (keeping the temperature reading) to work around a possible issue (#23439). - -//#define MAX31865_WIRE_OHMS_0 0.95f // For 2-wire, set the wire resistances for more accurate readings. -//#define MAX31865_WIRE_OHMS_1 0.0f -//#define MAX31865_WIRE_OHMS_2 0.0f - -/** - * Hephestos 2 24V heated bed upgrade kit. - * https://store.bq.com/en/heated-bed-kit-hephestos2 - */ +// +// Hephestos 2 24V heated bed upgrade kit. +// https://store.bq.com/en/heated-bed-kit-hephestos2 +// //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef TEMP_SENSOR_BED @@ -199,87 +126,22 @@ #define HEATER_BED_INVERTING true #endif -// -// Heated Bed Bang-Bang options -// -#if DISABLED(PIDTEMPBED) - #define BED_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control - #if ENABLED(BED_LIMIT_SWITCHING) - #define BED_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > BED_HYSTERESIS - #endif -#endif - -// -// Heated Chamber options -// -#if DISABLED(PIDTEMPCHAMBER) - #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control - #if ENABLED(CHAMBER_LIMIT_SWITCHING) - #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS - #endif -#endif - +/** + * Heated Chamber settings + */ #if TEMP_SENSOR_CHAMBER - //#define HEATER_CHAMBER_PIN P2_04 // Required heater on/off pin (example: SKR 1.4 Turbo HE1 plug) + #define CHAMBER_MINTEMP 5 + #define CHAMBER_MAXTEMP 60 + #define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target + //#define CHAMBER_LIMIT_SWITCHING + //#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin //#define HEATER_CHAMBER_INVERTING false - //#define FAN1_PIN -1 // Remove the fan signal on pin P2_04 (example: SKR 1.4 Turbo HE1 plug) - - //#define CHAMBER_FAN // Enable a fan on the chamber - #if ENABLED(CHAMBER_FAN) - //#define CHAMBER_FAN_INDEX 2 // Index of a fan to repurpose as the chamber fan. (Default: first unused fan) - #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on. - #if CHAMBER_FAN_MODE == 0 - #define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255) - #elif CHAMBER_FAN_MODE == 1 - #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255); turns on when chamber temperature is above the target - #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target - #elif CHAMBER_FAN_MODE == 2 - #define CHAMBER_FAN_BASE 128 // Minimum chamber fan PWM (0-255) - #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C difference from target - #elif CHAMBER_FAN_MODE == 3 - #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255) - #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target - #endif - #endif - - //#define CHAMBER_VENT // Enable a servo-controlled vent on the chamber - #if ENABLED(CHAMBER_VENT) - #define CHAMBER_VENT_SERVO_NR 1 // Index of the vent servo - #define HIGH_EXCESS_HEAT_LIMIT 5 // How much above target temp to consider there is excess heat in the chamber - #define LOW_EXCESS_HEAT_LIMIT 3 - #define MIN_COOLING_SLOPE_TIME_CHAMBER_VENT 20 - #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5 - #endif #endif -// -// Laser Cooler options -// -#if TEMP_SENSOR_COOLER - #define COOLER_MINTEMP 8 // (°C) - #define COOLER_MAXTEMP 26 // (°C) - #define COOLER_DEFAULT_TEMP 16 // (°C) - #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target - #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay) - #define COOLER_INVERTING false - #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required. - #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc. - #define COOLER_FAN_INDEX 0 // FAN number 0, 1, 2 etc. e.g. - #if ENABLED(COOLER_FAN) - #define COOLER_FAN_BASE 100 // Base Cooler fan PWM (0-255); turns on when Cooler temperature is above the target - #define COOLER_FAN_FACTOR 25 // PWM increase per °C above target - #endif -#endif - -// -// Motherboard Sensor options -// -#if TEMP_SENSOR_BOARD - #define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below. - #define BOARD_MINTEMP 8 // (°C) - #define BOARD_MAXTEMP 70 // (°C) - #ifndef TEMP_BOARD_PIN - //#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file. +#if DISABLED(PIDTEMPBED) + #define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control + #if ENABLED(BED_LIMIT_SWITCHING) + #define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS #endif #endif @@ -320,7 +182,7 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 40 // Seconds + #define WATCH_TEMP_PERIOD 20 // Seconds #define WATCH_TEMP_INCREASE 2 // Degrees Celsius #endif @@ -352,28 +214,6 @@ #define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius #endif -/** - * Thermal Protection parameters for the laser cooler. - */ -#if ENABLED(THERMAL_PROTECTION_COOLER) - #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds - #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius - - /** - * Laser cooling watch settings (M143/M193). - */ - #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds - #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius -#endif - -#if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) - /** - * Thermal Protection Variance Monitor - EXPERIMENTAL. - * Kill the machine on a stuck temperature sensor. Disable if you get false positives. - */ - //#define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates -#endif - #if ENABLED(PIDTEMP) // Add an experimental additional term to the heater power, proportional to the extrusion speed. // A well-chosen Kc value should add just enough power to melt the increased material volume. @@ -420,8 +260,8 @@ // DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf - #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf - #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING + #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf + #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING #define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0 @@ -449,7 +289,7 @@ */ #define AUTOTEMP #if ENABLED(AUTOTEMP) - #define AUTOTEMP_OLDWEIGHT 0.98 // Factor used to weight previous readings (0.0 < value < 1.0) + #define AUTOTEMP_OLDWEIGHT 0.98 // Turn on AUTOTEMP on M104/M109 by default using proportions set here //#define AUTOTEMP_PROPORTIONAL #if ENABLED(AUTOTEMP_PROPORTIONAL) @@ -467,7 +307,7 @@ * High Temperature Thermistor Support * * Thermistors able to support high temperature tend to have a hard time getting - * good readings at room and lower temperatures. This means TEMP_SENSOR_X_RAW_LO_TEMP + * good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP * will probably be caught when the heating element first turns on during the * preheating process, which will trigger a min_temp_error as a safety measure * and force stop everything. @@ -483,22 +323,18 @@ // before a min_temp_error is triggered. (Shouldn't be more than 10.) //#define MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED 0 -/** - * The number of milliseconds a hotend will preheat before starting to check - * the temperature. This value should NOT be set to the time it takes the - * hot end to reach the target temperature, but the time it takes to reach - * the minimum temperature your thermistor can read. The lower the better/safer. - * This shouldn't need to be more than 30 seconds (30000) - */ +// The number of milliseconds a hotend will preheat before starting to check +// the temperature. This value should NOT be set to the time it takes the +// hot end to reach the target temperature, but the time it takes to reach +// the minimum temperature your thermistor can read. The lower the better/safer. +// This shouldn't need to be more than 30 seconds (30000) //#define MILLISECONDS_PREHEAT_TIME 0 // @section extruder -/** - * Extruder runout prevention. - * If the machine is idle and the temperature over MINTEMP - * then extrude some filament every couple of SECONDS. - */ +// Extruder runout prevention. +// If the machine is idle and the temperature over MINTEMP +// then extrude some filament every couple of SECONDS. //#define EXTRUDER_RUNOUT_PREVENT #if ENABLED(EXTRUDER_RUNOUT_PREVENT) #define EXTRUDER_RUNOUT_MINTEMP 190 @@ -537,31 +373,23 @@ */ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) - //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan - //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered - //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. - #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) - #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled - #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled - #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors - - // Use TEMP_SENSOR_BOARD as a trigger for enabling the controller fan - //#define CONTROLLER_FAN_MIN_BOARD_TEMP 40 // (°C) Turn on the fan if the board reaches this temperature - - //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings + //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan + //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered + //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. + #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) + #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled + #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled + #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors + //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings #if ENABLED(CONTROLLER_FAN_EDITABLE) - #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu + #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu #endif #endif -/** - * Fan Kickstart - * When part cooling or controller fans first start, run at a speed that - * gets it spinning reliably for a short time before setting the requested speed. - * (Does not work on Sanguinololu with FAN_SOFT_PWM.) - */ -//#define FAN_KICKSTART_TIME 100 // (ms) -//#define FAN_KICKSTART_POWER 180 // 64-255 +// When first starting the main fan, run it at full speed for the +// given number of milliseconds. This gets the fan spinning reliably +// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu) +//#define FAN_KICKSTART_TIME 100 // Some coolers may require a non-zero "off" state. //#define FAN_OFF_PWM 1 @@ -582,48 +410,32 @@ //#define FAN_MAX_PWM 128 /** - * Fan Fast PWM + * FAST PWM FAN Settings * - * Combinations of PWM Modes, prescale values and TOP resolutions are used internally - * to produce a frequency as close as possible to the desired frequency. + * Use to change the FAST FAN PWM frequency (if enabled in Configuration.h) + * Combinations of PWM Modes, prescale values and TOP resolutions are used internally to produce a + * frequency as close as possible to the desired frequency. * - * FAST_PWM_FAN_FREQUENCY + * FAST_PWM_FAN_FREQUENCY [undefined by default] * Set this to your desired frequency. - * For AVR, if left undefined this defaults to F = F_CPU/(2*255*1) - * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. - * For non AVR, if left undefined this defaults to F = 1Khz. - * This F value is only to protect the hardware from an absence of configuration - * and not to complete it when users are not aware that the frequency must be specifically set to support the target board. - * + * If left undefined this defaults to F = F_CPU/(2*255*1) + * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. + * These defaults are the same as with the old FAST_PWM_FAN implementation - no migration is required * NOTE: Setting very low frequencies (< 10 Hz) may result in unexpected timer behavior. - * Setting very high frequencies can damage your hardware. * * USE_OCR2A_AS_TOP [undefined by default] * Boards that use TIMER2 for PWM have limitations resulting in only a few possible frequencies on TIMER2: - * 16MHz MCUs: [62.5kHz, 31.4kHz (default), 7.8kHz, 3.92kHz, 1.95kHz, 977Hz, 488Hz, 244Hz, 60Hz, 122Hz, 30Hz] - * 20MHz MCUs: [78.1kHz, 39.2kHz (default), 9.77kHz, 4.9kHz, 2.44kHz, 1.22kHz, 610Hz, 305Hz, 153Hz, 76Hz, 38Hz] + * 16MHz MCUs: [62.5KHz, 31.4KHz (default), 7.8KHz, 3.92KHz, 1.95KHz, 977Hz, 488Hz, 244Hz, 60Hz, 122Hz, 30Hz] + * 20MHz MCUs: [78.1KHz, 39.2KHz (default), 9.77KHz, 4.9KHz, 2.44KHz, 1.22KHz, 610Hz, 305Hz, 153Hz, 76Hz, 38Hz] * A greater range can be achieved by enabling USE_OCR2A_AS_TOP. But note that this option blocks the use of * PWM on pin OC2A. Only use this option if you don't need PWM on 0C2A. (Check your schematic.) * USE_OCR2A_AS_TOP sacrifices duty cycle control resolution to achieve this broader range of frequencies. */ -//#define FAST_PWM_FAN // Increase the fan PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino #if ENABLED(FAST_PWM_FAN) - //#define FAST_PWM_FAN_FREQUENCY 31400 // Define here to override the defaults below + //#define FAST_PWM_FAN_FREQUENCY 31400 //#define USE_OCR2A_AS_TOP - #ifndef FAST_PWM_FAN_FREQUENCY - #ifdef __AVR__ - #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) - #else - #define FAST_PWM_FAN_FREQUENCY 1000U - #endif - #endif #endif -/** - * Use one of the PWM fans as a redundant part-cooling fan - */ -//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. - // @section extruder /** @@ -647,48 +459,11 @@ #define E6_AUTO_FAN_PIN -1 #define E7_AUTO_FAN_PIN -1 #define CHAMBER_AUTO_FAN_PIN -1 -#define COOLER_AUTO_FAN_PIN -1 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // 255 == full speed #define CHAMBER_AUTO_FAN_TEMPERATURE 30 #define CHAMBER_AUTO_FAN_SPEED 255 -#define COOLER_AUTO_FAN_TEMPERATURE 18 -#define COOLER_AUTO_FAN_SPEED 255 - -/** - * Hotend Cooling Fans tachometers - * - * Define one or more tachometer pins to enable fan speed - * monitoring, and reporting of fan speeds with M123. - * - * NOTE: Only works with fans up to 7000 RPM. - */ -//#define FOURWIRES_FANS // Needed with AUTO_FAN when 4-wire PWM fans are installed -//#define E0_FAN_TACHO_PIN -1 -//#define E0_FAN_TACHO_PULLUP -//#define E0_FAN_TACHO_PULLDOWN -//#define E1_FAN_TACHO_PIN -1 -//#define E1_FAN_TACHO_PULLUP -//#define E1_FAN_TACHO_PULLDOWN -//#define E2_FAN_TACHO_PIN -1 -//#define E2_FAN_TACHO_PULLUP -//#define E2_FAN_TACHO_PULLDOWN -//#define E3_FAN_TACHO_PIN -1 -//#define E3_FAN_TACHO_PULLUP -//#define E3_FAN_TACHO_PULLDOWN -//#define E4_FAN_TACHO_PIN -1 -//#define E4_FAN_TACHO_PULLUP -//#define E4_FAN_TACHO_PULLDOWN -//#define E5_FAN_TACHO_PIN -1 -//#define E5_FAN_TACHO_PULLUP -//#define E5_FAN_TACHO_PULLDOWN -//#define E6_FAN_TACHO_PIN -1 -//#define E6_FAN_TACHO_PULLUP -//#define E6_FAN_TACHO_PULLDOWN -//#define E7_FAN_TACHO_PIN -1 -//#define E7_FAN_TACHO_PULLUP -//#define E7_FAN_TACHO_PULLDOWN /** * Part-Cooling Fan Multiplexer @@ -710,17 +485,12 @@ #define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW #define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin) - //#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting. - //#define CASE_LIGHT_MAX_PWM 128 // Limit PWM duty cycle (0-255) + //#define CASE_LIGHT_MAX_PWM 128 // Limit pwm //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu - #if ENABLED(NEOPIXEL_LED) - //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light - #endif - #if EITHER(RGB_LED, RGBW_LED) - //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light - #endif - #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) - #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } + //#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting. + //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light, requires NEOPIXEL_LED. + #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) + #define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } #endif #endif @@ -741,6 +511,58 @@ //#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1 #endif +/** + * Dual Steppers / Dual Endstops + * + * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes. + * + * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to + * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop + * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug + * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'. + * + * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors + * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error + * in X2. Dual endstop offsets can be set at runtime with 'M666 X Y Z'. + */ + +//#define X_DUAL_STEPPER_DRIVERS +#if ENABLED(X_DUAL_STEPPER_DRIVERS) + #define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions + //#define X_DUAL_ENDSTOPS + #if ENABLED(X_DUAL_ENDSTOPS) + #define X2_USE_ENDSTOP _XMAX_ + #define X2_ENDSTOP_ADJUSTMENT 0 + #endif +#endif + +//#define Y_DUAL_STEPPER_DRIVERS +#if ENABLED(Y_DUAL_STEPPER_DRIVERS) + #define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions + //#define Y_DUAL_ENDSTOPS + #if ENABLED(Y_DUAL_ENDSTOPS) + #define Y2_USE_ENDSTOP _YMAX_ + #define Y2_ENDSTOP_ADJUSTMENT 0 + #endif +#endif + +// +// For Z set the number of stepper drivers +// +//#define Z_MULTI_ENDSTOPS +#if ENABLED(Z_MULTI_ENDSTOPS) + #define Z2_USE_ENDSTOP _XMAX_ + #define Z2_ENDSTOP_ADJUSTMENT 0 + #if NUM_Z_STEPPER_DRIVERS >= 3 + #define Z3_USE_ENDSTOP _YMAX_ + #define Z3_ENDSTOP_ADJUSTMENT 0 + #endif + #if NUM_Z_STEPPER_DRIVERS >= 4 + #define Z4_USE_ENDSTOP _ZMAX_ + #define Z4_ENDSTOP_ADJUSTMENT 0 + #endif +#endif + /** * Dual X Carriage * @@ -771,95 +593,22 @@ */ //#define DUAL_X_CARRIAGE #if ENABLED(DUAL_X_CARRIAGE) - #define X1_MIN_POS X_MIN_POS // Set to X_MIN_POS - #define X1_MAX_POS X_BED_SIZE // A max coordinate so the X1 carriage can't hit the parked X2 carriage - #define X2_MIN_POS 80 // A min coordinate so the X2 carriage can't hit the parked X1 carriage - #define X2_MAX_POS 353 // The max position of the X2 carriage, typically also the home position - #define X2_HOME_DIR 1 // Set to 1. The X2 carriage always homes to the max endstop position - #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. - // NOTE: For Dual X Carriage use M218 T1 Xn to override the X2_HOME_POS. - // This allows recalibration of endstops distance without a rebuild. - // Remember to set the second extruder's X-offset to 0 in your slicer. - - // This is the default power-up mode which can be changed later using M605 S. + #define X1_MIN_POS X_MIN_POS // Set to X_MIN_POS + #define X1_MAX_POS X_BED_SIZE // Set a maximum so the first X-carriage can't hit the parked second X-carriage + #define X2_MIN_POS 80 // Set a minimum to ensure the second X-carriage can't hit the parked first X-carriage + #define X2_MAX_POS 353 // Set this to the distance between toolheads when both heads are homed + #define X2_HOME_DIR 1 // Set to 1. The second X-carriage always homes to the maximum endstop position + #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. + // However: In this mode the HOTEND_OFFSET_X value for the second extruder provides a software + // override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops + // without modifying the firmware (through the "M218 T1 X???" command). + // Remember: you should set the second extruder x-offset to 0 in your slicer. + + // This is the default power-up mode which can be later using M605. #define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_AUTO_PARK_MODE // Default x offset in duplication mode (typically set to half print bed width) #define DEFAULT_DUPLICATION_X_OFFSET 100 - - // Default action to execute following M605 mode change commands. Typically G28X to apply new mode. - //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" -#endif - -/** - * Multi-Stepper / Multi-Endstop - * - * When X2_DRIVER_TYPE is defined, this indicates that the X and X2 motors work in tandem. - * The following explanations for X also apply to Y and Z multi-stepper setups. - * Endstop offsets may be changed by 'M666 X Y Z' and stored to EEPROM. - * - * - Enable INVERT_X2_VS_X_DIR if the X2 motor requires an opposite DIR signal from X. - * - * - Enable X_DUAL_ENDSTOPS if the second motor has its own endstop, with adjustable offset. - * - * - Extra endstops are included in the output of 'M119'. - * - * - Set X_DUAL_ENDSTOP_ADJUSTMENT to the known error in the X2 endstop. - * Applied to the X2 motor on 'G28' / 'G28 X'. - * Get the offset by homing X and measuring the error. - * Also set with 'M666 X' and stored to EEPROM with 'M500'. - * - * - Use X2_USE_ENDSTOP to set the endstop plug by name. (_XMIN_, _XMAX_, _YMIN_, _YMAX_, _ZMIN_, _ZMAX_) - */ -#if HAS_X2_STEPPER && DISABLED(DUAL_X_CARRIAGE) - //#define INVERT_X2_VS_X_DIR // X2 direction signal is the opposite of X - //#define X_DUAL_ENDSTOPS // X2 has its own endstop - #if ENABLED(X_DUAL_ENDSTOPS) - #define X2_USE_ENDSTOP _XMAX_ // X2 endstop board plug. Don't forget to enable USE_*_PLUG. - #define X2_ENDSTOP_ADJUSTMENT 0 // X2 offset relative to X endstop - #endif -#endif - -#if HAS_DUAL_Y_STEPPERS - //#define INVERT_Y2_VS_Y_DIR // Y2 direction signal is the opposite of Y - //#define Y_DUAL_ENDSTOPS // Y2 has its own endstop - #if ENABLED(Y_DUAL_ENDSTOPS) - #define Y2_USE_ENDSTOP _YMAX_ // Y2 endstop board plug. Don't forget to enable USE_*_PLUG. - #define Y2_ENDSTOP_ADJUSTMENT 0 // Y2 offset relative to Y endstop - #endif -#endif - -// -// Multi-Z steppers -// -#ifdef Z2_DRIVER_TYPE - //#define INVERT_Z2_VS_Z_DIR // Z2 direction signal is the opposite of Z - - //#define Z_MULTI_ENDSTOPS // Other Z axes have their own endstops - #if ENABLED(Z_MULTI_ENDSTOPS) - #define Z2_USE_ENDSTOP _XMAX_ // Z2 endstop board plug. Don't forget to enable USE_*_PLUG. - #define Z2_ENDSTOP_ADJUSTMENT 0 // Z2 offset relative to Y endstop - #endif - #ifdef Z3_DRIVER_TYPE - //#define INVERT_Z3_VS_Z_DIR // Z3 direction signal is the opposite of Z - #if ENABLED(Z_MULTI_ENDSTOPS) - #define Z3_USE_ENDSTOP _YMAX_ // Z3 endstop board plug. Don't forget to enable USE_*_PLUG. - #define Z3_ENDSTOP_ADJUSTMENT 0 // Z3 offset relative to Y endstop - #endif - #endif - #ifdef Z4_DRIVER_TYPE - //#define INVERT_Z4_VS_Z_DIR // Z4 direction signal is the opposite of Z - #if ENABLED(Z_MULTI_ENDSTOPS) - #define Z4_USE_ENDSTOP _ZMAX_ // Z4 endstop board plug. Don't forget to enable USE_*_PLUG. - #define Z4_ENDSTOP_ADJUSTMENT 0 // Z4 offset relative to Y endstop - #endif - #endif -#endif - -// Drive the E axis with two synchronized steppers -//#define E_DUAL_STEPPER_DRIVERS -#if ENABLED(E_DUAL_STEPPER_DRIVERS) - //#define INVERT_E1_VS_E0_DIR // E direction signals are opposites #endif // Activate a solenoid on the active extruder with M380. Disable all with M381. @@ -874,17 +623,15 @@ * the position of the toolhead relative to the workspace. */ -//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (linear=mm, rotational=°) Backoff from endstops before sensorless homing +//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing -#define HOMING_BUMP_MM { 5, 5, 2 } // (linear=mm, rotational=°) Backoff from endstops after first bump +#define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) -//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (linear=mm, rotational=°) Backoff from endstops after homing -//#define XY_COUNTERPART_BACKOFF_MM 0 // (mm) Backoff X after homing Y, and vice-versa +//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (mm) Backoff from endstops after homing //#define QUICK_HOME // If G28 contains XY do a diagonal move first //#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X -//#define HOME_Z_FIRST // Home Z first. Requires a Z-MIN endstop (not a probe). //#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first // @section bltouch @@ -944,14 +691,12 @@ //#define BLTOUCH_FORCE_MODE_SET /** - * Enable "HIGH SPEED" option for probing. + * Use "HIGH SPEED" mode for probing. * Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems. - * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians - * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM. - * - * Set the default state here, change with 'M401 S' or UI, use M500 to save, M502 to reset. + * This feature was designed for Delta's with very fast Z moves however higher speed cartesians may function + * If the machine cannot raise the probe fast enough after a trigger, it may enter a fault state. */ - //#define BLTOUCH_HS_MODE true + //#define BLTOUCH_HS_MODE // Safety: Enable voltage mode settings in the LCD menu. //#define BLTOUCH_LCD_VOLTAGE_MENU @@ -966,12 +711,9 @@ */ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) - /** - * Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] - * These positions are machine-relative and do not shift with the M206 home offset! - * If not defined, probe limits will be used. - * Override with 'M422 S X Y'. - */ + // Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] + // If not defined, probe limits will be used. + // Override with 'M422 S X Y' //#define Z_STEPPER_ALIGN_XY { { 10, 190 }, { 100, 10 }, { 190, 190 } } /** @@ -992,22 +734,21 @@ * | 4 3 | 1 4 | 2 1 | 3 2 | * | | | | | * | 1 2 | 2 3 | 3 4 | 4 1 | + * */ #ifndef Z_STEPPER_ALIGN_XY //#define Z_STEPPERS_ORIENTATION 0 #endif - /** - * Z Stepper positions for more rapid convergence in bed alignment. - * Requires 3 or 4 Z steppers. - * - * Define Stepper XY positions for Z1, Z2, Z3... corresponding to the screw - * positions in the bed carriage, with one position per Z stepper in stepper - * driver order. - */ - //#define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } - - #ifndef Z_STEPPER_ALIGN_STEPPER_XY + // Provide Z stepper positions for more rapid convergence in bed alignment. + // Requires triple stepper drivers (i.e., set NUM_Z_STEPPER_DRIVERS to 3) + //#define Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS + #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) + // Define Stepper XY positions for Z1, Z2, Z3 corresponding to + // the Z screw positions in the bed carriage. + // Define one position per Z stepper in stepper driver order. + #define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } + #else // Amplification factor. Used to scale the correction step up or down in case // the stepper (spindle) position is farther out than the test point. #define Z_STEPPER_ALIGN_AMP 1.0 // Use a value > 1.0 NOTE: This may cause instability! @@ -1028,22 +769,20 @@ // //#define ASSISTED_TRAMMING #if ENABLED(ASSISTED_TRAMMING) + // Define positions for probing points, use the hotend as reference not the sensor. + #define TRAMMING_POINT_XY { { 20, 20 }, { 200, 20 }, { 200, 200 }, { 20, 200 } } - // Define positions for probe points. - #define TRAMMING_POINT_XY { { 20, 20 }, { 180, 20 }, { 180, 180 }, { 20, 180 } } - - // Define position names for probe points. + // Define positions names for probing points. #define TRAMMING_POINT_NAME_1 "Front-Left" #define TRAMMING_POINT_NAME_2 "Front-Right" #define TRAMMING_POINT_NAME_3 "Back-Right" #define TRAMMING_POINT_NAME_4 "Back-Left" - #define RESTORE_LEVELING_AFTER_G35 // Enable to restore leveling setup after operation - //#define REPORT_TRAMMING_MM // Report Z deviation (mm) for each point relative to the first - - //#define ASSISTED_TRAMMING_WIZARD // Add a Tramming Wizard to the LCD menu + // Enable to restore leveling setup after operation + #define RESTORE_LEVELING_AFTER_G35 - //#define ASSISTED_TRAMMING_WAIT_POSITION { X_CENTER, Y_CENTER, 30 } // Move the nozzle out of the way for adjustment + // Add a menu item for Assisted Tramming + //#define ASSISTED_TRAMMING_MENU_ITEM /** * Screw thread: @@ -1052,40 +791,10 @@ * M5: 50 = Clockwise, 51 = Counter-Clockwise */ #define TRAMMING_SCREW_THREAD 30 - #endif // @section motion -/** - * Input Shaping -- EXPERIMENTAL - * - * Zero Vibration (ZV) Input Shaping for X and/or Y movements. - * - * This option uses a lot of SRAM for the step buffer, which is proportional - * to the largest step rate possible for any axis. If the build fails due to - * low SRAM the buffer size may be reduced by setting smaller values for - * DEFAULT_AXIS_STEPS_PER_UNIT and/or DEFAULT_MAX_FEEDRATE. Runtime editing - * of max feedrate (M203) or resonant frequency (M593) may result feedrate - * being capped to prevent buffer overruns. - * - * Tune with M593 D F: - * - * D Set the zeta/damping factor. If axes (X, Y, etc.) are not specified, set for all axes. - * F Set the frequency. If axes (X, Y, etc.) are not specified, set for all axes. - * T[map] Input Shaping type, 0:ZV, 1:EI, 2:2H EI (not implemented yet) - * X<1> Set the given parameters only for the X axis. - * Y<1> Set the given parameters only for the Y axis. - */ -//#define INPUT_SHAPING -#if ENABLED(INPUT_SHAPING) - #define SHAPING_FREQ_X 40 // (Hz) The dominant resonant frequency of the X axis. - #define SHAPING_FREQ_Y 40 // (Hz) The dominant resonant frequency of the Y axis. - #define SHAPING_ZETA_X 0.3f // Damping ratio of the X axis (range: 0.0 = no damping to 1.0 = critical damping). - #define SHAPING_ZETA_Y 0.3f // Damping ratio of the Y axis (range: 0.0 = no damping to 1.0 = critical damping). - //#define SHAPING_MENU // Add a menu to the LCD to set shaping parameters. -#endif - #define AXIS_RELATIVE_MODES { false, false, false, false } // Add a Duplicate option for well-separated conjoined nozzles @@ -1095,12 +804,6 @@ #define INVERT_X_STEP_PIN false #define INVERT_Y_STEP_PIN false #define INVERT_Z_STEP_PIN false -#define INVERT_I_STEP_PIN false -#define INVERT_J_STEP_PIN false -#define INVERT_K_STEP_PIN false -#define INVERT_U_STEP_PIN false -#define INVERT_V_STEP_PIN false -#define INVERT_W_STEP_PIN false #define INVERT_E_STEP_PIN false /** @@ -1112,17 +815,16 @@ #define DISABLE_INACTIVE_X true #define DISABLE_INACTIVE_Y true #define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! -#define DISABLE_INACTIVE_I true -#define DISABLE_INACTIVE_J true -#define DISABLE_INACTIVE_K true -#define DISABLE_INACTIVE_U true -#define DISABLE_INACTIVE_V true -#define DISABLE_INACTIVE_W true #define DISABLE_INACTIVE_E true +// If the Nozzle or Bed falls when the Z stepper is disabled, set its resting position here. +//#define Z_AFTER_DEACTIVATE Z_HOME_POS + +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // Default Minimum Feedrates for printing and travel moves -#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S. -#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T. +#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S. +#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T. // Minimum time that a segment needs to take as the buffer gets emptied #define DEFAULT_MINSEGMENTTIME 20000 // (µs) Set with M205 B. @@ -1158,12 +860,9 @@ #if ENABLED(BACKLASH_COMPENSATION) // Define values for backlash distance and correction. // If BACKLASH_GCODE is enabled these values are the defaults. - #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (linear=mm, rotational=°) One value for each linear axis + #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) #define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction - // Add steps for motor direction changes on CORE kinematics - //#define CORE_BACKLASH - // Set BACKLASH_SMOOTHING_MM to spread backlash correction over multiple segments // to reduce print artifacts. (Enabling this is costly in memory and computation!) //#define BACKLASH_SMOOTHING_MM 3 // (mm) @@ -1181,13 +880,13 @@ // increments while checking for the contact to be broken. #define BACKLASH_MEASUREMENT_LIMIT 0.5 // (mm) #define BACKLASH_MEASUREMENT_RESOLUTION 0.005 // (mm) - #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_FEEDRATE_SLOW // (mm/min) + #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_SPEED_SLOW // (mm/min) #endif #endif #endif /** - * Automatic backlash, position, and hotend offset calibration + * Automatic backlash, position and hotend offset calibration * * Enable G425 to run automatic calibration using an electrically- * conductive cube, bolt, or washer mounted on the bed. @@ -1229,19 +928,6 @@ #define CALIBRATION_MEASURE_LEFT #define CALIBRATION_MEASURE_BACK - //#define CALIBRATION_MEASURE_IMIN - //#define CALIBRATION_MEASURE_IMAX - //#define CALIBRATION_MEASURE_JMIN - //#define CALIBRATION_MEASURE_JMAX - //#define CALIBRATION_MEASURE_KMIN - //#define CALIBRATION_MEASURE_KMAX - //#define CALIBRATION_MEASURE_UMIN - //#define CALIBRATION_MEASURE_UMAX - //#define CALIBRATION_MEASURE_VMIN - //#define CALIBRATION_MEASURE_VMAX - //#define CALIBRATION_MEASURE_WMIN - //#define CALIBRATION_MEASURE_WMAX - // Probing at the exact top center only works if the center is flat. If // probing on a screwhead or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES @@ -1304,7 +990,7 @@ /** * I2C-based DIGIPOTs (e.g., Azteeg X3 Pro) */ -//#define DIGIPOT_MCP4018 // Requires https://github.com/felias-fogg/SlowSoftI2CMaster +//#define DIGIPOT_MCP4018 // Requires https://github.com/stawel/SlowSoftI2CMaster //#define DIGIPOT_MCP4451 #if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 @@ -1335,10 +1021,10 @@ // @section lcd -#if HAS_MANUAL_MOVE_MENU +#if EITHER(ULTIPANEL, EXTENSIBLE_UI) #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel - #define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines - #if IS_ULTIPANEL + #define SHORT_MANUAL_Z_MOVE 0.025 // (mm) Smallest manual Z move (< 0.1mm) + #if ENABLED(ULTIPANEL) #define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position" #define ULTIPANEL_FEEDMULTIPLY // Encoder sets the feedrate multiplier on the Status Screen #endif @@ -1358,46 +1044,7 @@ #define FEEDRATE_CHANGE_BEEP_FREQUENCY 440 #endif -// -// LCD Backlight Timeout -// -//#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight - -#if HAS_BED_PROBE && EITHER(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) - //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu - #if ENABLED(PROBE_OFFSET_WIZARD) - /** - * Enable to init the Probe Z-Offset when starting the Wizard. - * Use a height slightly above the estimated nozzle-to-probe Z offset. - * For example, with an offset of -5, consider a starting height of -4. - */ - //#define PROBE_OFFSET_WIZARD_START_Z -4.0 - - // Set a convenient position to do the calibration (probing point and nozzle/bed-distance) - //#define PROBE_OFFSET_WIZARD_XY_POS { X_CENTER, Y_CENTER } - #endif -#endif - -#if HAS_MARLINUI_MENU - - #if HAS_BED_PROBE - // Add calibration in the Probe Offsets menu to compensate for X-axis twist. - //#define X_AXIS_TWIST_COMPENSATION - #if ENABLED(X_AXIS_TWIST_COMPENSATION) - /** - * Enable to init the Probe Z-Offset when starting the Wizard. - * Use a height slightly above the estimated nozzle-to-probe Z offset. - * For example, with an offset of -5, consider a starting height of -4. - */ - #define XATC_START_Z 0.0 - #define XATC_MAX_POINTS 3 // Number of points to probe in the wizard - #define XATC_Y_POSITION Y_CENTER // (mm) Y position to probe - #define XATC_Z_OFFSETS { 0, 0, 0 } // Z offsets for X axis sample points - #endif - - // Show Deploy / Stow Probe options in the Motion menu. - #define PROBE_DEPLOY_STOW_MENU - #endif +#if HAS_LCD_MENU // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU @@ -1408,39 +1055,6 @@ // BACK menu items keep the highlight at the top //#define TURBO_BACK_MENU_ITEM - // Insert a menu for preheating at the top level to allow for quick access - //#define PREHEAT_SHORTCUT_MENU_ITEM - -#endif // HAS_MARLINUI_MENU - -#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) - //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu - #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state -#endif - -#if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) - // The timeout to return to the status screen from sub-menus - //#define LCD_TIMEOUT_TO_STATUS 15000 // (ms) - - #if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) - #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) - #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) - #endif - #endif - - // Scroll a longer status message into view - //#define STATUS_MESSAGE_SCROLLING - - // Apply a timeout to low-priority status messages - //#define STATUS_MESSAGE_TIMEOUT_SEC 30 // (seconds) - - // On the Info Screen, display XY with one decimal place when possible - //#define LCD_DECIMAL_SMALL_XY - - // Show the E position (filament used) during printing - //#define LCD_SHOW_E_TOTAL - /** * LED Control Menu * Add LED Control to the LCD menu @@ -1458,43 +1072,53 @@ //#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup #endif #if ENABLED(NEO2_COLOR_PRESETS) - #define NEO2_USER_PRESET_RED 255 // User defined RED value - #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value - #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value - #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value - #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity - //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip + #define NEO2_USER_PRESET_RED 255 // User defined RED value + #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value + #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value + #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value + #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity + //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip #endif #endif -#endif // HAS_DISPLAY || DWIN_LCD_PROUI +#endif // HAS_LCD_MENU -// Add the G-code 'M73' to set / report the current job progress -//#define SET_PROGRESS_MANUALLY -#if ENABLED(SET_PROGRESS_MANUALLY) - //#define SET_PROGRESS_PERCENT // Add 'P' parameter to set percentage done, otherwise use Marlin's estimate - //#define SET_REMAINING_TIME // Add 'R' parameter to set remaining time, otherwise use Marlin's estimate - //#define SET_INTERACTION_TIME // Add 'C' parameter to set time until next filament change or other user interaction - #if ENABLED(SET_INTERACTION_TIME) - #define SHOW_INTERACTION_TIME // Display time until next user interaction ('C' = filament change) - #endif - //#define M73_REPORT // Report progress to host with 'M73' +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + +// On the Info Screen, display XY with one decimal place when possible +//#define LCD_DECIMAL_SMALL_XY + +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + +// Add an 'M73' G-code to set the current percentage +//#define LCD_SET_PROGRESS_MANUALLY + +// Show the E position (filament used) during printing +//#define LCD_SHOW_E_TOTAL + +#if ENABLED(SHOW_BOOTSCREEN) + #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) #endif -// LCD Print Progress options, multiple can be rotated depending on screen layout -#if HAS_DISPLAY && EITHER(SDSUPPORT, SET_PROGRESS_MANUALLY) - #define SHOW_PROGRESS_PERCENT // Show print progress percentage (doesn't affect progress bar) - #define SHOW_ELAPSED_TIME // Display elapsed printing time (prefix 'E') - //#define SHOW_REMAINING_TIME // Display estimated time to completion (prefix 'R') +#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && (HAS_GRAPHICAL_LCD || HAS_CHARACTER_LCD) + //#define SHOW_REMAINING_TIME // Display estimated time to completion + #if ENABLED(SHOW_REMAINING_TIME) + //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation + //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time + #endif - //#define PRINT_PROGRESS_SHOW_DECIMALS // Show/report progress with decimal digits, not all UIs support this + #if HAS_GRAPHICAL_LCD + //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits + #endif - #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) + #if HAS_CHARACTER_LCD //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing #if ENABLED(LCD_PROGRESS_BAR) #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message - #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) + #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar #endif @@ -1502,26 +1126,13 @@ #endif #if ENABLED(SDSUPPORT) - /** - * SD Card SPI Speed - * May be required to resolve "volume init" errors. - * - * Enable and set to SPI_HALF_SPEED, SPI_QUARTER_SPEED, or SPI_EIGHTH_SPEED - * otherwise full speed will be applied. - * - * :['SPI_HALF_SPEED', 'SPI_QUARTER_SPEED', 'SPI_EIGHTH_SPEED'] - */ - //#define SD_SPI_SPEED SPI_HALF_SPEED // The standard SD detect circuit reads LOW when media is inserted and HIGH when empty. // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH - //#define SD_IGNORE_AT_STARTUP // Don't mount the SD card when starting up //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash) - //#define GCODE_REPEAT_MARKERS // Enable G-code M808 to set repeat markers and do looping - #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished @@ -1533,13 +1144,8 @@ #define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing - //#define NO_SD_AUTOSTART // Remove auto#.g file support completely to save some Flash, SRAM //#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files - //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted - - //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu - #define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27") #if ENABLED(PRINTER_EVENT_LEDS) @@ -1561,20 +1167,13 @@ //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. //#define POWER_LOSS_STATE HIGH // State of pin indicating power loss - //#define POWER_LOSS_PULLUP // Set pullup / pulldown as appropriate for your sensor - //#define POWER_LOSS_PULLDOWN + //#define POWER_LOSS_PULL // Set pullup / pulldown as appropriate //#define POWER_LOSS_PURGE_LEN 20 // (mm) Length of filament to purge on resume //#define POWER_LOSS_RETRACT_LEN 10 // (mm) Length of filament to retract on fail. Requires backup power. // Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card, // especially with "vase mode" printing. Set too high and vases cannot be continued. #define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data - - // Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled! - //#define POWER_LOSS_RECOVER_ZHOME - #if ENABLED(POWER_LOSS_RECOVER_ZHOME) - //#define POWER_LOSS_ZHOME_POS { 0, 0 } // Safe XY position to home Z while avoiding objects on the bed - #endif #endif /** @@ -1615,31 +1214,33 @@ // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. #endif - // Allow international symbols in long filenames. To display correctly, the - // LCD's font must contain the characters. Check your selected LCD language. - //#define UTF_FILENAME_SUPPORT - - //#define LONG_FILENAME_HOST_SUPPORT // Get the long filename of a file/folder with 'M33 ' and list long filenames with 'M20 L' - //#define LONG_FILENAME_WRITE_SUPPORT // Create / delete files with long filenames via M28, M30, and Binary Transfer Protocol - //#define M20_TIMESTAMP_SUPPORT // Include timestamps by adding the 'T' flag to M20 commands + // This allows hosts to request long names for files and folders with M33 + //#define LONG_FILENAME_HOST_SUPPORT - //#define SCROLL_LONG_FILENAMES // Scroll long filenames in the SD card menu + // Enable this option to scroll long filenames in the SD card menu + //#define SCROLL_LONG_FILENAMES - //#define SD_ABORT_NO_COOLDOWN // Leave the heaters on after Stop Print (not recommended!) + // Leave the heaters on after Stop Print (not recommended!) + //#define SD_ABORT_NO_COOLDOWN /** - * Abort SD printing when any endstop is triggered. - * This feature is enabled with 'M540 S1' or from the LCD menu. - * Endstops must be activated for this option to work. + * This option allows you to abort SD printing when any endstop is triggered. + * This feature must be enabled with "M540 S1" or from the LCD menu. + * To have any effect, endstops must be enabled during SD printing. */ //#define SD_ABORT_ON_ENDSTOP_HIT - #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) - //#define SD_ABORT_ON_ENDSTOP_HIT_GCODE "G28XY" // G-code to run on endstop hit (e.g., "G28XY" or "G27") - #endif - //#define SD_REPRINT_LAST_SELECTED_FILE // On print completion open the LCD Menu and select the same file + /** + * This option makes it easier to print the same SD Card file again. + * On print completion the LCD Menu will open with the file selected. + * You can just click to start the print, or navigate elsewhere. + */ + //#define SD_REPRINT_LAST_SELECTED_FILE - //#define AUTO_REPORT_SD_STATUS // Auto-report media status with 'M27 S' + /** + * Auto-report SdCard status with M27 S + */ + //#define AUTO_REPORT_SD_STATUS /** * Support for USB thumb drives using an Arduino USB Host Shield or @@ -1657,6 +1258,9 @@ */ //#define USB_FLASH_DRIVE_SUPPORT #if ENABLED(USB_FLASH_DRIVE_SUPPORT) + #define USB_CS_PIN SDSS + #define USB_INTR_PIN SD_DETECT_PIN + /** * USB Host Shield Library * @@ -1667,20 +1271,7 @@ * is less tested and is known to interfere with Servos. * [1] This requires USB_INTR_PIN to be interrupt-capable. */ - //#define USE_UHS2_USB //#define USE_UHS3_USB - - #define DISABLE_DUE_SD_MMC // Disable USB Host access to USB Drive to prevent hangs on block access for DUE platform - - /** - * Native USB Host supported by some boards (USB OTG) - */ - //#define USE_OTG_USB_HOST - - #if DISABLED(USE_OTG_USB_HOST) - #define USB_CS_PIN SDSS - #define USB_INTR_PIN SD_DETECT_PIN - #endif #endif /** @@ -1699,48 +1290,20 @@ #define SD_FIRMWARE_UPDATE_INACTIVE_VALUE 0xFF #endif - /** - * Enable this option if you have more than ~3K of unused flash space. - * Marlin will embed all settings in the firmware binary as compressed data. - * Use 'M503 C' to write the settings out to the SD Card as 'mc.zip'. - * See docs/ConfigEmbedding.md for details on how to use 'mc-apply.py'. - */ - //#define CONFIGURATION_EMBEDDING - // Add an optimized binary file transfer mode, initiated with 'M28 B1' //#define BINARY_FILE_TRANSFER - #if ENABLED(BINARY_FILE_TRANSFER) - // Include extra facilities (e.g., 'M20 F') supporting firmware upload via BINARY_FILE_TRANSFER - //#define CUSTOM_FIRMWARE_UPLOAD - #endif - /** * Set this option to one of the following (or the board's defaults apply): * * LCD - Use the SD drive in the external LCD controller. - * ONBOARD - Use the SD drive on the control board. + * ONBOARD - Use the SD drive on the control board. (No SD_DETECT_PIN. M21 to init.) * CUSTOM_CABLE - Use a custom cable to access the SD (as defined in a pins file). * * :[ 'LCD', 'ONBOARD', 'CUSTOM_CABLE' ] */ //#define SDCARD_CONNECTION LCD - // Enable if SD detect is rendered useless (e.g., by using an SD extender) - //#define NO_SD_DETECT - - /** - * Multiple volume support - EXPERIMENTAL. - * Adds 'M21 Pm' / 'M21 S' / 'M21 U' to mount SD Card / USB Drive. - */ - //#define MULTI_VOLUME - #if ENABLED(MULTI_VOLUME) - #define VOLUME_SD_ONBOARD - #define VOLUME_USB_FLASH_DRIVE - #define DEFAULT_VOLUME SV_SD_ONBOARD - #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE - #endif - #endif // SDSUPPORT /** @@ -1761,29 +1324,27 @@ * controller events, as there is a trade-off between reliable * printing performance versus fast display updates. */ -#if HAS_MARLINUI_U8GLIB +#if HAS_GRAPHICAL_LCD + // Show SD percentage next to the progress bar + //#define DOGM_SD_PERCENT + // Save many cycles by drawing a hollow frame or no frame on the Info Screen //#define XYZ_NO_FRAME #define XYZ_HOLLOW_FRAME - // A bigger font is available for edit items. Costs 3120 bytes of flash. + // Enable to save many cycles by drawing a hollow frame on Menu Screens + #define MENU_HOLLOW_FRAME + + // A bigger font is available for edit items. Costs 3120 bytes of PROGMEM. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_BIG_EDIT_FONT - // A smaller font may be used on the Info Screen. Costs 2434 bytes of flash. + // A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - /** - * Graphical Display Sleep - * - * The U8G library provides sleep / wake functions for SH1106, SSD1306, - * SSD1309, and some other DOGM displays. - * Enable this option to save energy and prevent OLED pixel burn-in. - * Adds the menu item Configuration > LCD Timeout (m) to set a wait period - * from 0 (disabled) to 99 minutes. - */ - //#define DISPLAY_SLEEP_MINUTES 2 // (minutes) Timeout before turning off the screen. Set with M255 S. + // Swap the CW/CCW indicators in the graphics overlay + //#define OVERLAY_GFX_REVERSE /** * ST7920-based LCDs can emulate a 16 x 4 character display using @@ -1797,7 +1358,7 @@ * Set STATUS_EXPIRE_SECONDS to zero to never clear the status. * This will prevent position updates from being displayed. */ - #if IS_U8GLIB_ST7920 + #if ENABLED(U8GLIB_ST7920) // Enable this option and reduce the value to optimize screen updates. // The normal delay is 10µs. Use the lowest value that still gives a reliable display. //#define DOGM_SPI_DELAY_US 5 @@ -1815,18 +1376,17 @@ */ //#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones //#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends) - #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM for numbered hotends) + #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM) #define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating #define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating #define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating //#define STATUS_CUTTER_ANIM // Use a second bitmap to indicate spindle / laser active - //#define STATUS_COOLER_ANIM // Use a second bitmap to indicate laser cooling - //#define STATUS_FLOWMETER_ANIM // Use multiple bitmaps to indicate coolant flow //#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. + //#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash) + //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~?3260 (or ~940) bytes of PROGMEM. // Frivolous Game Options //#define MARLIN_BRICKOUT @@ -1834,31 +1394,27 @@ //#define MARLIN_SNAKE //#define GAMES_EASTER_EGG // Add extra blank lines above the "Games" sub-menu -#endif // HAS_MARLINUI_U8GLIB - -#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI - #define MENU_HOLLOW_FRAME // Enable to save many cycles by drawing a hollow frame on Menu Screens - //#define OVERLAY_GFX_REVERSE // Swap the CW/CCW indicators in the graphics overlay -#endif +#endif // HAS_GRAPHICAL_LCD // // Additional options for DGUS / DWIN displays // #if HAS_DGUS_LCD - #define LCD_BAUDRATE 115200 + #define DGUS_SERIAL_PORT 3 + #define DGUS_BAUDRATE 115200 #define DGUS_RX_BUFFER_SIZE 128 #define DGUS_TX_BUFFER_SIZE 48 - //#define SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) + //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #if ANY(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS, DGUS_LCD_UI_HIPRECY) + #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing #define DGUS_PREHEAT_UI // Display a preheat screen during heatup - #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS) - //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for FYSETC and MKS + #if ENABLED(DGUS_LCD_UI_FYSETC) + //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC #else #define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY #endif @@ -1877,44 +1433,6 @@ #endif #endif // HAS_DGUS_LCD -// -// Additional options for AnyCubic Chiron TFT displays -// -#if ENABLED(ANYCUBIC_LCD_CHIRON) - // By default the type of panel is automatically detected. - // Enable one of these options if you know the panel type. - //#define CHIRON_TFT_STANDARD - //#define CHIRON_TFT_NEW - - // Enable the longer Anycubic powerup startup tune - //#define AC_DEFAULT_STARTUP_TUNE - - /** - * Display Folders - * By default the file browser lists all G-code files (including those in subfolders) in a flat list. - * Enable this option to display a hierarchical file browser. - * - * NOTES: - * - Without this option it helps to enable SDCARD_SORT_ALPHA so files are sorted before/after folders. - * - When used with the "new" panel, folder names will also have '.gcode' appended to their names. - * This hack is currently required to force the panel to show folders. - */ - #define AC_SD_FOLDER_VIEW -#endif - -// -// Specify additional languages for the UI. Default specified by LCD_LANGUAGE. -// -#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) - //#define LCD_LANGUAGE_2 fr - //#define LCD_LANGUAGE_3 de - //#define LCD_LANGUAGE_4 es - //#define LCD_LANGUAGE_5 it - #ifdef LCD_LANGUAGE_2 - //#define LCD_LANGUAGE_AUTO_SAVE // Automatically save language to EEPROM on change - #endif -#endif - // // Touch UI for the FTDI Embedded Video Engine (EVE) // @@ -1924,10 +1442,8 @@ //#define LCD_4DSYSTEMS_4DLCD_FT843 // 4D Systems 4.3" (480x272) //#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272) //#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480) - //#define LCD_LULZBOT_CLCD_UI // LulzBot Color LCD UI + //#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480) - //#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815 - //#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813 // Correct the resolution if not using the stock TFT panel. //#define TOUCH_UI_320x240 @@ -1935,8 +1451,8 @@ //#define TOUCH_UI_800x480 // Mappings for boards with a standard RepRapDiscount Display connector - //#define AO_EXP1_PINMAP // LulzBot CLCD UI EXP1 mapping - //#define AO_EXP2_PINMAP // LulzBot CLCD UI EXP2 mapping + //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping + //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping //#define F6_TFT_PINMAP // FYSETC F6 pin mapping @@ -1984,14 +1500,18 @@ //#define TOUCH_UI_UTF8_FRACTIONS // ¼ ½ ¾ //#define TOUCH_UI_UTF8_SYMBOLS // µ ¶ ¦ § ¬ #endif - - // Cyrillic character set, costs about 27KiB of flash - //#define TOUCH_UI_UTF8_CYRILLIC_CHARSET #endif // Use a smaller font when labels don't fit buttons #define TOUCH_UI_FIT_TEXT + // Allow language selection from menu at run-time (otherwise use LCD_LANGUAGE) + //#define LCD_LANGUAGE_1 en + //#define LCD_LANGUAGE_2 fr + //#define LCD_LANGUAGE_3 de + //#define LCD_LANGUAGE_4 es + //#define LCD_LANGUAGE_5 it + // Use a numeric passcode for "Screen lock" keypad. // (recommended for smaller displays) //#define TOUCH_UI_PASSCODE @@ -2004,9 +1524,10 @@ #endif // -// Classic UI Options +// FSMC / SPI Graphical TFT // #if TFT_SCALED_DOGLCD + //#define GRAPHICAL_TFT_ROTATE_180 //#define TFT_MARLINUI_COLOR 0xFFFF // White //#define TFT_MARLINBG_COLOR 0x0000 // Black //#define TFT_DISABLED_COLOR 0x0003 // Almost black @@ -2096,35 +1617,14 @@ */ //#define LIN_ADVANCE #if ENABLED(LIN_ADVANCE) - #if ENABLED(DISTINCT_E_FACTORS) - #define ADVANCE_K { 0.22 } // (mm) Compression length per 1mm/s extruder speed, per extruder - #else - #define ADVANCE_K 0.22 // (mm) Compression length applying to all extruders - #endif - //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with M900 L. - //#define LA_DEBUG // Print debug information to serial during operation. Disable for production use. - //#define EXPERIMENTAL_SCURVE // Allow S-Curve Acceleration to be used with LA. - //#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends. - //#define EXPERIMENTAL_I2S_LA // Allow I2S_STEPPER_STREAM to be used with LA. Performance degrades as the LA step rate reaches ~20kHz. + //#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants + #define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed + //#define LA_DEBUG // If enabled, this will generate debug information output over USB. + //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration #endif // @section leveling -/** - * Use Safe Bed Leveling coordinates to move axes to a useful position before bed probing. - * For example, after homing a rotational axis the Z probe might not be perpendicular to the bed. - * Choose values the orient the bed horizontally and the Z-probe vertically. - */ -//#define SAFE_BED_LEVELING_START_X 0.0 -//#define SAFE_BED_LEVELING_START_Y 0.0 -//#define SAFE_BED_LEVELING_START_Z 0.0 -//#define SAFE_BED_LEVELING_START_I 0.0 -//#define SAFE_BED_LEVELING_START_J 0.0 -//#define SAFE_BED_LEVELING_START_K 0.0 -//#define SAFE_BED_LEVELING_START_U 0.0 -//#define SAFE_BED_LEVELING_START_V 0.0 -//#define SAFE_BED_LEVELING_START_W 0.0 - /** * Points to probe for all 3-point Leveling procedures. * Override if the automatically selected points are inadequate. @@ -2172,10 +1672,6 @@ //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET) #endif -#if BOTH(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) - //#define OPTIMIZED_MESH_STORAGE // Store mesh with less precision to save EEPROM space -#endif - /** * Repeatedly attempt G29 leveling until it succeeds. * Stop after G29_MAX_RETRIES attempts. @@ -2196,69 +1692,59 @@ /** * Thermal Probe Compensation - * - * Adjust probe measurements to compensate for distortion associated with the temperature - * of the probe, bed, and/or hotend. - * Use G76 to automatically calibrate this feature for probe and bed temperatures. - * (Extruder temperature/offset values must be calibrated manually.) - * Use M871 to set temperature/offset values manually. - * For more details see https://marlinfw.org/docs/features/probe_temp_compensation.html + * Probe measurements are adjusted to compensate for temperature distortion. + * Use G76 to calibrate this feature. Use M871 to set values manually. + * For a more detailed explanation of the process see G76_M871.cpp. */ -//#define PTC_PROBE // Compensate based on probe temperature -//#define PTC_BED // Compensate based on bed temperature -//#define PTC_HOTEND // Compensate based on hotend temperature +#if HAS_BED_PROBE && TEMP_SENSOR_PROBE && TEMP_SENSOR_BED + // Enable thermal first layer compensation using bed and probe temperatures + #define PROBE_TEMP_COMPENSATION -#if ANY(PTC_PROBE, PTC_BED, PTC_HOTEND) - /** - * If the probe is outside the defined range, use linear extrapolation with the closest - * point and the point with index PTC_LINEAR_EXTRAPOLATION. e.g., If set to 4 it will use the - * linear extrapolation between data[0] and data[4] for values below PTC_PROBE_START. - */ - //#define PTC_LINEAR_EXTRAPOLATION 4 - - #if ENABLED(PTC_PROBE) - // Probe temperature calibration generates a table of values starting at PTC_PROBE_START - // (e.g., 30), in steps of PTC_PROBE_RES (e.g., 5) with PTC_PROBE_COUNT (e.g., 10) samples. - #define PTC_PROBE_START 30 // (°C) - #define PTC_PROBE_RES 5 // (°C) - #define PTC_PROBE_COUNT 10 - #define PTC_PROBE_ZOFFS { 0 } // (µm) Z adjustments per sample - #endif - - #if ENABLED(PTC_BED) - // Bed temperature calibration builds a similar table. - #define PTC_BED_START 60 // (°C) - #define PTC_BED_RES 5 // (°C) - #define PTC_BED_COUNT 10 - #define PTC_BED_ZOFFS { 0 } // (µm) Z adjustments per sample - #endif - - #if ENABLED(PTC_HOTEND) - // Note: There is no automatic calibration for the hotend. Use M871. - #define PTC_HOTEND_START 180 // (°C) - #define PTC_HOTEND_RES 5 // (°C) - #define PTC_HOTEND_COUNT 20 - #define PTC_HOTEND_ZOFFS { 0 } // (µm) Z adjustments per sample - #endif - - // G76 options - #if BOTH(PTC_PROBE, PTC_BED) + // Add additional compensation depending on hotend temperature + // Note: this values cannot be calibrated and have to be set manually + #if ENABLED(PROBE_TEMP_COMPENSATION) // Park position to wait for probe cooldown #define PTC_PARK_POS { 0, 0, 100 } // Probe position to probe and wait for probe to reach target temperature - //#define PTC_PROBE_POS { 12.0f, 7.3f } // Example: MK52 magnetic heatbed #define PTC_PROBE_POS { 90, 100 } - // The temperature the probe should be at while taking measurements during - // bed temperature calibration. - #define PTC_PROBE_TEMP 30 // (°C) + // Enable additional compensation using hotend temperature + // Note: this values cannot be calibrated automatically but have to be set manually + //#define USE_TEMP_EXT_COMPENSATION + + // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START + // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples. - // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: The Z=0.0 offset is determined by the probe Z offset (e.g., as set with M851 Z). - #define PTC_PROBE_HEATING_OFFSET 0.5 + //#define PTC_SAMPLE_START 30.0f + //#define PTC_SAMPLE_RES 5.0f + //#define PTC_SAMPLE_COUNT 10U + + // Bed temperature calibration builds a similar table. + + //#define BTC_SAMPLE_START 60.0f + //#define BTC_SAMPLE_RES 5.0f + //#define BTC_SAMPLE_COUNT 10U + + // The temperature the probe should be at while taking measurements during bed temperature + // calibration. + //#define BTC_PROBE_TEMP 30.0f + + // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. + // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. + //#define PTC_PROBE_HEATING_OFFSET 0.5f + + // Height to raise the Z-probe between heating and taking the next measurement. Some probes + // may fail to untrigger if they have been triggered for a long time, which can be solved by + // increasing the height the probe is raised to. + //#define PTC_PROBE_RAISE 15U + + // If the probe is outside of the defined range, use linear extrapolation using the closest + // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] + // and data[4] to perform linear extrapolation for values below PTC_SAMPLE_START. + //#define PTC_LINEAR_EXTRAPOLATION 4 #endif -#endif // PTC_PROBE || PTC_BED || PTC_HOTEND +#endif // @section extras @@ -2270,23 +1756,21 @@ // // G2/G3 Arc Support // -#define ARC_SUPPORT // Requires ~3226 bytes +#define ARC_SUPPORT // Disable this feature to save ~3226 bytes #if ENABLED(ARC_SUPPORT) + #define MM_PER_ARC_SEGMENT 1 // (mm) Length (or minimum length) of each arc segment + //#define ARC_SEGMENTS_PER_R 1 // Max segment length, MM_PER = Min + #define MIN_CIRCLE_SEGMENTS 24 // Minimum number of segments in a complete circle + //#define ARC_SEGMENTS_PER_SEC 50 // Use feedrate to choose segment length (with MM_PER_ARC_SEGMENT as the minimum) + #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections #define MIN_ARC_SEGMENT_MM 0.1 // (mm) Minimum length of each arc segment #define MAX_ARC_SEGMENT_MM 1.0 // (mm) Maximum length of each arc segment - #define MIN_CIRCLE_SEGMENTS 72 // Minimum number of segments in a complete circle - //#define ARC_SEGMENTS_PER_SEC 50 // Use the feedrate to choose the segment length - #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections - //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles - //#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure + //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles + //#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes #endif -// G5 Bézier Curve Support with XYZE destination and IJPQ offsets -//#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes - -#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) - //#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes -#endif +// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. +//#define BEZIER_CURVE_SUPPORT /** * Direct Stepping @@ -2369,7 +1853,7 @@ // @section motion // The number of linear moves that can be in the planner at once. -// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) #if BOTH(SDSUPPORT, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 #elif ENABLED(SDSUPPORT) @@ -2385,7 +1869,7 @@ #define BUFSIZE 4 // Transmission to Host Buffer Size -// To save 386 bytes of flash (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. +// To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. // To buffer a simple "ok" you need 4 bytes. // For ADVANCED_OK (M105) you need 32 bytes. // For debug-echo: 128 bytes for the optimal speed. @@ -2405,6 +1889,9 @@ //#define SERIAL_XON_XOFF #endif +// Add M575 G-code to change the baud rate +//#define BAUD_RATE_GCODE + #if ENABLED(SDSUPPORT) // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. @@ -2415,12 +1902,6 @@ //#define SERIAL_STATS_DROPPED_RX #endif -// Monitor RX buffer usage -// Dump an error to the serial port if the serial receive buffer overflows. -// If you see these errors, increase the RX_BUFFER_SIZE value. -// Not supported on all platforms. -//#define RX_BUFFER_MONITOR - /** * Emergency Command Parser * @@ -2431,26 +1912,6 @@ */ //#define EMERGENCY_PARSER -/** - * Realtime Reporting (requires EMERGENCY_PARSER) - * - * - Report position and state of the machine (like Grbl). - * - Auto-report position during long moves. - * - Useful for CNC/LASER. - * - * Adds support for commands: - * S000 : Report State and Position while moving. - * P000 : Instant Pause / Hold while moving. - * R000 : Resume from Pause / Hold. - * - * - During Hold all Emergency Parser commands are available, as usual. - * - Enable NANODLP_Z_SYNC and NANODLP_ALL_AXIS for move command end-state reports. - */ -//#define REALTIME_REPORTING_COMMANDS -#if ENABLED(REALTIME_REPORTING_COMMANDS) - //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC -#endif - // Bad Serial-connections can miss a received command by sending an 'ok' // Therefore some clients abort after 30 seconds in a timeout. // Some other clients start sending commands while receiving a 'wait'. @@ -2467,15 +1928,6 @@ // For serial echo, the number of digits after the decimal point //#define SERIAL_FLOAT_PRECISION 4 -/** - * Set the number of proportional font spaces required to fill up a typical character space. - * This can help to better align the output of commands like `G29 O` Mesh Output. - * - * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. - * Otherwise, adjust according to your client and font. - */ -#define PROPORTIONAL_FONT_RATIO 1.0 - // @section extras /** @@ -2500,24 +1952,25 @@ * Be sure to turn off auto-retract during filament change. * * Note that M207 / M208 / M209 settings are saved to EEPROM. + * */ //#define FWRETRACT #if ENABLED(FWRETRACT) - #define FWRETRACT_AUTORETRACT // Override slicer retractions + #define FWRETRACT_AUTORETRACT // Override slicer retractions #if ENABLED(FWRETRACT_AUTORETRACT) - #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length - #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length - #endif - #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) - #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) - #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting - #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise - #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) - #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) - #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction - #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction + #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length + #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length + #endif + #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) + #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) + #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting + #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise + #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) + #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction #if ENABLED(MIXING_EXTRUDER) - //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously + //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously #endif #endif @@ -2534,20 +1987,6 @@ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif - /** - * Extra G-code to run while executing tool-change commands. Can be used to use an additional - * stepper motor (e.g., I axis in Configuration.h) to drive the tool-changer. - */ - //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 - //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 - //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! - - /** - * Tool Sensors detect when tools have been picked up or dropped. - * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc. - */ - //#define TOOL_SENSOR - /** * Retract and prime filament on tool-change to reduce * ooze and stringing and to get cleaner transitions. @@ -2556,30 +1995,26 @@ #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) // Load / Unload #define TOOLCHANGE_FS_LENGTH 12 // (mm) Load / Unload length - #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart. Adjust with LCD or M217 B. + #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart, fine tune by LCD/Gcode) #define TOOLCHANGE_FS_RETRACT_SPEED (50*60) // (mm/min) (Unloading) #define TOOLCHANGE_FS_UNRETRACT_SPEED (25*60) // (mm/min) (On SINGLENOZZLE or Bowden loading must be slowed down) // Longer prime to clean out a SINGLENOZZLE #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/min) Extra priming feedrate - #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm) Cutting retraction out of park, for less stringing, better wipe, etc. Adjust with LCD or M217 G. + #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm/min) Retract before cooling for less stringing, better wipe, etc. // Cool after prime to reduce stringing #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip #define TOOLCHANGE_FS_FAN_SPEED 255 // 0-255 #define TOOLCHANGE_FS_FAN_TIME 10 // (seconds) - // Use TOOLCHANGE_FS_PRIME_SPEED feedrate the first time each extruder is primed - //#define TOOLCHANGE_FS_SLOW_FIRST_PRIME + // Swap uninitialized extruder with TOOLCHANGE_FS_PRIME_SPEED for all lengths (recover + prime) + // (May break filament if not retracted beforehand.) + //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP - /** - * Prime T0 the first time T0 is sent to the printer: - * [ Power-On -> T0 { Activate & Prime T0 } -> T1 { Retract T0, Activate & Prime T1 } ] - * If disabled, no priming on T0 until switching back to T0 from another extruder: - * [ Power-On -> T0 { T0 Activated } -> T1 { Activate & Prime T1 } -> T0 { Retract T1, Activate & Prime T0 } ] - * Enable with M217 V1 before printing to avoid unwanted priming on host connect. - */ + // Prime on the first T0 (If other, TOOLCHANGE_FS_INIT_BEFORE_SWAP applied) + // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect //#define TOOLCHANGE_FS_PRIME_FIRST_USED /** @@ -2609,18 +2044,15 @@ #endif #endif // HAS_MULTI_EXTRUDER -// @section advanced pause - /** - * Advanced Pause for Filament Change - * - Adds the G-code M600 Filament Change to initiate a filament change. - * - This feature is required for the default FILAMENT_RUNOUT_SCRIPT. - * - * Requirements: - * - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE. - * - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. + * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * - * Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park. + * Requires an LCD display. + * Requires NOZZLE_PARK_FEATURE. + * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ //#define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -2659,8 +2091,6 @@ #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety. #define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed. #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change. - //#define FILAMENT_CHANGE_RESUME_ON_INSERT // Automatically continue / load filament when runout sensor is triggered again. - //#define PAUSE_REHEAT_FAST_RESUME // Reduce number of waits by not prompting again post-timeout before continuing. //#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change. //#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change @@ -2669,12 +2099,13 @@ //#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302) #endif +// @section tmc + /** * TMC26X Stepper Driver options * * The TMC26XStepper library is required for this stepper driver. * https://github.com/trinamic/TMC26XStepper - * @section tmc/tmc26x */ #if HAS_DRIVER(TMC26X) @@ -2687,7 +2118,7 @@ #if AXIS_DRIVER_TYPE_X2(TMC26X) #define X2_MAX_CURRENT 1000 #define X2_SENSE_RESISTOR 91 - #define X2_MICROSTEPS X_MICROSTEPS + #define X2_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_Y(TMC26X) @@ -2699,7 +2130,7 @@ #if AXIS_DRIVER_TYPE_Y2(TMC26X) #define Y2_MAX_CURRENT 1000 #define Y2_SENSE_RESISTOR 91 - #define Y2_MICROSTEPS Y_MICROSTEPS + #define Y2_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_Z(TMC26X) @@ -2711,55 +2142,19 @@ #if AXIS_DRIVER_TYPE_Z2(TMC26X) #define Z2_MAX_CURRENT 1000 #define Z2_SENSE_RESISTOR 91 - #define Z2_MICROSTEPS Z_MICROSTEPS + #define Z2_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_Z3(TMC26X) #define Z3_MAX_CURRENT 1000 #define Z3_SENSE_RESISTOR 91 - #define Z3_MICROSTEPS Z_MICROSTEPS + #define Z3_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_Z4(TMC26X) #define Z4_MAX_CURRENT 1000 #define Z4_SENSE_RESISTOR 91 - #define Z4_MICROSTEPS Z_MICROSTEPS - #endif - - #if AXIS_DRIVER_TYPE_I(TMC26X) - #define I_MAX_CURRENT 1000 - #define I_SENSE_RESISTOR 91 - #define I_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_J(TMC26X) - #define J_MAX_CURRENT 1000 - #define J_SENSE_RESISTOR 91 - #define J_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_K(TMC26X) - #define K_MAX_CURRENT 1000 - #define K_SENSE_RESISTOR 91 - #define K_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_U(TMC26X) - #define U_MAX_CURRENT 1000 - #define U_SENSE_RESISTOR 91 - #define U_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_V(TMC26X) - #define V_MAX_CURRENT 1000 - #define V_SENSE_RESISTOR 91 - #define V_MICROSTEPS 16 - #endif - - #if AXIS_DRIVER_TYPE_W(TMC26X) - #define W_MAX_CURRENT 1000 - #define W_SENSE_RESISTOR 91 - #define W_MICROSTEPS 16 + #define Z4_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) @@ -2771,47 +2166,49 @@ #if AXIS_DRIVER_TYPE_E1(TMC26X) #define E1_MAX_CURRENT 1000 #define E1_SENSE_RESISTOR 91 - #define E1_MICROSTEPS E0_MICROSTEPS + #define E1_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E2(TMC26X) #define E2_MAX_CURRENT 1000 #define E2_SENSE_RESISTOR 91 - #define E2_MICROSTEPS E0_MICROSTEPS + #define E2_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E3(TMC26X) #define E3_MAX_CURRENT 1000 #define E3_SENSE_RESISTOR 91 - #define E3_MICROSTEPS E0_MICROSTEPS + #define E3_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E4(TMC26X) #define E4_MAX_CURRENT 1000 #define E4_SENSE_RESISTOR 91 - #define E4_MICROSTEPS E0_MICROSTEPS + #define E4_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E5(TMC26X) #define E5_MAX_CURRENT 1000 #define E5_SENSE_RESISTOR 91 - #define E5_MICROSTEPS E0_MICROSTEPS + #define E5_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E6(TMC26X) #define E6_MAX_CURRENT 1000 #define E6_SENSE_RESISTOR 91 - #define E6_MICROSTEPS E0_MICROSTEPS + #define E6_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E7(TMC26X) #define E7_MAX_CURRENT 1000 #define E7_SENSE_RESISTOR 91 - #define E7_MICROSTEPS E0_MICROSTEPS + #define E7_MICROSTEPS 16 #endif #endif // TMC26X +// @section tmc_smart + /** * To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode * connect your SPI pins to the hardware SPI interface on your board and define @@ -2827,36 +2224,26 @@ * * TMCStepper library is required to use TMC stepper drivers. * https://github.com/teemuatlut/TMCStepper - * @section tmc/config */ #if HAS_TRINAMIC_CONFIG #define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current - - /** - * Interpolate microsteps to 256 - * Override for each driver with _INTERPOLATE settings below - */ - #define INTERPOLATE true + #define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256 #if AXIS_IS_TMC(X) #define X_CURRENT 800 // (mA) RMS current. Multiply by 1.414 for peak current. #define X_CURRENT_HOME X_CURRENT // (mA) RMS current for sensorless homing - #define X_MICROSTEPS 16 // 0..256 + #define X_MICROSTEPS 16 // 0..256 #define X_RSENSE 0.11 - #define X_CHAIN_POS -1 // -1..0: Not chained. 1: MCU MOSI connected. 2: Next in chain, ... - //#define X_INTERPOLATE true // Enable to override 'INTERPOLATE' for the X axis - //#define X_HOLD_MULTIPLIER 0.5 // Enable to override 'HOLD_MULTIPLIER' for the X axis + #define X_CHAIN_POS -1 // <=0 : Not chained. 1 : MCU MOSI connected. 2 : Next in chain, ... #endif #if AXIS_IS_TMC(X2) #define X2_CURRENT 800 #define X2_CURRENT_HOME X2_CURRENT - #define X2_MICROSTEPS X_MICROSTEPS + #define X2_MICROSTEPS 16 #define X2_RSENSE 0.11 #define X2_CHAIN_POS -1 - //#define X2_INTERPOLATE true - //#define X2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y) @@ -2865,18 +2252,14 @@ #define Y_MICROSTEPS 16 #define Y_RSENSE 0.11 #define Y_CHAIN_POS -1 - //#define Y_INTERPOLATE true - //#define Y_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y2) #define Y2_CURRENT 800 #define Y2_CURRENT_HOME Y2_CURRENT - #define Y2_MICROSTEPS Y_MICROSTEPS + #define Y2_MICROSTEPS 16 #define Y2_RSENSE 0.11 #define Y2_CHAIN_POS -1 - //#define Y2_INTERPOLATE true - //#define Y2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z) @@ -2885,98 +2268,30 @@ #define Z_MICROSTEPS 16 #define Z_RSENSE 0.11 #define Z_CHAIN_POS -1 - //#define Z_INTERPOLATE true - //#define Z_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z2) #define Z2_CURRENT 800 #define Z2_CURRENT_HOME Z2_CURRENT - #define Z2_MICROSTEPS Z_MICROSTEPS + #define Z2_MICROSTEPS 16 #define Z2_RSENSE 0.11 #define Z2_CHAIN_POS -1 - //#define Z2_INTERPOLATE true - //#define Z2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z3) #define Z3_CURRENT 800 #define Z3_CURRENT_HOME Z3_CURRENT - #define Z3_MICROSTEPS Z_MICROSTEPS + #define Z3_MICROSTEPS 16 #define Z3_RSENSE 0.11 #define Z3_CHAIN_POS -1 - //#define Z3_INTERPOLATE true - //#define Z3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z4) #define Z4_CURRENT 800 #define Z4_CURRENT_HOME Z4_CURRENT - #define Z4_MICROSTEPS Z_MICROSTEPS + #define Z4_MICROSTEPS 16 #define Z4_RSENSE 0.11 #define Z4_CHAIN_POS -1 - //#define Z4_INTERPOLATE true - //#define Z4_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(I) - #define I_CURRENT 800 - #define I_CURRENT_HOME I_CURRENT - #define I_MICROSTEPS 16 - #define I_RSENSE 0.11 - #define I_CHAIN_POS -1 - //#define I_INTERPOLATE true - //#define I_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(J) - #define J_CURRENT 800 - #define J_CURRENT_HOME J_CURRENT - #define J_MICROSTEPS 16 - #define J_RSENSE 0.11 - #define J_CHAIN_POS -1 - //#define J_INTERPOLATE true - //#define J_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(K) - #define K_CURRENT 800 - #define K_CURRENT_HOME K_CURRENT - #define K_MICROSTEPS 16 - #define K_RSENSE 0.11 - #define K_CHAIN_POS -1 - //#define K_INTERPOLATE true - //#define K_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(U) - #define U_CURRENT 800 - #define U_CURRENT_HOME U_CURRENT - #define U_MICROSTEPS 8 - #define U_RSENSE 0.11 - #define U_CHAIN_POS -1 - //#define U_INTERPOLATE true - //#define U_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(V) - #define V_CURRENT 800 - #define V_CURRENT_HOME V_CURRENT - #define V_MICROSTEPS 8 - #define V_RSENSE 0.11 - #define V_CHAIN_POS -1 - //#define V_INTERPOLATE true - //#define V_HOLD_MULTIPLIER 0.5 - #endif - - #if AXIS_IS_TMC(W) - #define W_CURRENT 800 - #define W_CURRENT_HOME W_CURRENT - #define W_MICROSTEPS 8 - #define W_RSENSE 0.11 - #define W_CHAIN_POS -1 - //#define W_INTERPOLATE true - //#define W_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E0) @@ -2984,75 +2299,57 @@ #define E0_MICROSTEPS 16 #define E0_RSENSE 0.11 #define E0_CHAIN_POS -1 - //#define E0_INTERPOLATE true - //#define E0_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E1) #define E1_CURRENT 800 - #define E1_MICROSTEPS E0_MICROSTEPS + #define E1_MICROSTEPS 16 #define E1_RSENSE 0.11 #define E1_CHAIN_POS -1 - //#define E1_INTERPOLATE true - //#define E1_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E2) #define E2_CURRENT 800 - #define E2_MICROSTEPS E0_MICROSTEPS + #define E2_MICROSTEPS 16 #define E2_RSENSE 0.11 #define E2_CHAIN_POS -1 - //#define E2_INTERPOLATE true - //#define E2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E3) #define E3_CURRENT 800 - #define E3_MICROSTEPS E0_MICROSTEPS + #define E3_MICROSTEPS 16 #define E3_RSENSE 0.11 #define E3_CHAIN_POS -1 - //#define E3_INTERPOLATE true - //#define E3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E4) #define E4_CURRENT 800 - #define E4_MICROSTEPS E0_MICROSTEPS + #define E4_MICROSTEPS 16 #define E4_RSENSE 0.11 #define E4_CHAIN_POS -1 - //#define E4_INTERPOLATE true - //#define E4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E5) #define E5_CURRENT 800 - #define E5_MICROSTEPS E0_MICROSTEPS + #define E5_MICROSTEPS 16 #define E5_RSENSE 0.11 #define E5_CHAIN_POS -1 - //#define E5_INTERPOLATE true - //#define E5_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E6) #define E6_CURRENT 800 - #define E6_MICROSTEPS E0_MICROSTEPS + #define E6_MICROSTEPS 16 #define E6_RSENSE 0.11 #define E6_CHAIN_POS -1 - //#define E6_INTERPOLATE true - //#define E6_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E7) #define E7_CURRENT 800 - #define E7_MICROSTEPS E0_MICROSTEPS + #define E7_MICROSTEPS 16 #define E7_RSENSE 0.11 #define E7_CHAIN_POS -1 - //#define E7_INTERPOLATE true - //#define E7_HOLD_MULTIPLIER 0.5 #endif - // @section tmc/spi - /** * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. @@ -3064,13 +2361,6 @@ //#define Y2_CS_PIN -1 //#define Z2_CS_PIN -1 //#define Z3_CS_PIN -1 - //#define Z4_CS_PIN -1 - //#define I_CS_PIN -1 - //#define J_CS_PIN -1 - //#define K_CS_PIN -1 - //#define U_CS_PIN -1 - //#define V_CS_PIN -1 - //#define W_CS_PIN -1 //#define E0_CS_PIN -1 //#define E1_CS_PIN -1 //#define E2_CS_PIN -1 @@ -3090,8 +2380,6 @@ //#define TMC_SW_MISO -1 //#define TMC_SW_SCK -1 - // @section tmc/serial - /** * Four TMC2209 drivers can use the same HW/SW serial port with hardware configured addresses. * Set the address using jumpers on pins MS1 and MS2. @@ -3104,30 +2392,22 @@ * Set *_SERIAL_TX_PIN and *_SERIAL_RX_PIN to match for all drivers * on the same serial port, either here or in your board's pins file. */ - //#define X_SLAVE_ADDRESS 0 - //#define Y_SLAVE_ADDRESS 0 - //#define Z_SLAVE_ADDRESS 0 - //#define X2_SLAVE_ADDRESS 0 - //#define Y2_SLAVE_ADDRESS 0 - //#define Z2_SLAVE_ADDRESS 0 - //#define Z3_SLAVE_ADDRESS 0 - //#define Z4_SLAVE_ADDRESS 0 - //#define I_SLAVE_ADDRESS 0 - //#define J_SLAVE_ADDRESS 0 - //#define K_SLAVE_ADDRESS 0 - //#define U_SLAVE_ADDRESS 0 - //#define V_SLAVE_ADDRESS 0 - //#define W_SLAVE_ADDRESS 0 - //#define E0_SLAVE_ADDRESS 0 - //#define E1_SLAVE_ADDRESS 0 - //#define E2_SLAVE_ADDRESS 0 - //#define E3_SLAVE_ADDRESS 0 - //#define E4_SLAVE_ADDRESS 0 - //#define E5_SLAVE_ADDRESS 0 - //#define E6_SLAVE_ADDRESS 0 - //#define E7_SLAVE_ADDRESS 0 - - // @section tmc/smart + #define X_SLAVE_ADDRESS 0 + #define Y_SLAVE_ADDRESS 0 + #define Z_SLAVE_ADDRESS 0 + #define X2_SLAVE_ADDRESS 0 + #define Y2_SLAVE_ADDRESS 0 + #define Z2_SLAVE_ADDRESS 0 + #define Z3_SLAVE_ADDRESS 0 + #define Z4_SLAVE_ADDRESS 0 + #define E0_SLAVE_ADDRESS 0 + #define E1_SLAVE_ADDRESS 0 + #define E2_SLAVE_ADDRESS 0 + #define E3_SLAVE_ADDRESS 0 + #define E4_SLAVE_ADDRESS 0 + #define E5_SLAVE_ADDRESS 0 + #define E6_SLAVE_ADDRESS 0 + #define E7_SLAVE_ADDRESS 0 /** * Software enable @@ -3137,8 +2417,6 @@ */ //#define SOFTWARE_DRIVER_ENABLE - // @section tmc/stealthchop - /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * Use Trinamic's ultra quiet stepping mode. @@ -3146,12 +2424,6 @@ */ #define STEALTHCHOP_XY #define STEALTHCHOP_Z - #define STEALTHCHOP_I - #define STEALTHCHOP_J - #define STEALTHCHOP_K - #define STEALTHCHOP_U - #define STEALTHCHOP_V - #define STEALTHCHOP_W #define STEALTHCHOP_E /** @@ -3163,37 +2435,13 @@ * CHOPPER_DEFAULT_24V * CHOPPER_DEFAULT_36V * CHOPPER_09STEP_24V // 0.9 degree steppers (24V) - * CHOPPER_PRUSAMK3_24V // Imported parameters from the official Průša firmware for MK3 (24V) + * CHOPPER_PRUSAMK3_24V // Imported parameters from the official Pruša firmware for MK3 (24V) * CHOPPER_MARLIN_119 // Old defaults from Marlin v1.1.9 * - * Define your own with: + * Define you own with * { , , hysteresis_start[1..8] } */ - #define CHOPPER_TIMING CHOPPER_DEFAULT_12V // All axes (override below) - //#define CHOPPER_TIMING_X CHOPPER_TIMING // For X Axes (override below) - //#define CHOPPER_TIMING_X2 CHOPPER_TIMING_X - //#define CHOPPER_TIMING_Y CHOPPER_TIMING // For Y Axes (override below) - //#define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y - //#define CHOPPER_TIMING_Z CHOPPER_TIMING // For Z Axes (override below) - //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z - //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z - //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z - //#define CHOPPER_TIMING_I CHOPPER_TIMING // For I Axis - //#define CHOPPER_TIMING_J CHOPPER_TIMING // For J Axis - //#define CHOPPER_TIMING_K CHOPPER_TIMING // For K Axis - //#define CHOPPER_TIMING_U CHOPPER_TIMING // For U Axis - //#define CHOPPER_TIMING_V CHOPPER_TIMING // For V Axis - //#define CHOPPER_TIMING_W CHOPPER_TIMING // For W Axis - //#define CHOPPER_TIMING_E CHOPPER_TIMING // For Extruders (override below) - //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E3 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E4 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E5 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E - //#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E - - // @section tmc/status + #define CHOPPER_TIMING CHOPPER_DEFAULT_12V /** * Monitor Trinamic drivers @@ -3214,8 +2462,6 @@ #define STOP_ON_ERROR #endif - // @section tmc/hybrid - /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. @@ -3233,12 +2479,6 @@ #define Z2_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3 #define Z4_HYBRID_THRESHOLD 3 - #define I_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] - #define J_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] - #define K_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] - #define U_HYBRID_THRESHOLD 3 // [mm/s] - #define V_HYBRID_THRESHOLD 3 - #define W_HYBRID_THRESHOLD 3 #define E0_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30 @@ -3264,7 +2504,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** + * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * @@ -3272,7 +2512,6 @@ * homing and adds a guard period for endstop triggering. * * Comment *_STALL_SENSITIVITY to disable sensorless homing for that axis. - * @section tmc/stallguard */ //#define SENSORLESS_HOMING // StallGuard capable drivers only @@ -3286,18 +2525,10 @@ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY - //#define I_STALL_SENSITIVITY 8 - //#define J_STALL_SENSITIVITY 8 - //#define K_STALL_SENSITIVITY 8 - //#define U_STALL_SENSITIVITY 8 - //#define V_STALL_SENSITIVITY 8 - //#define W_STALL_SENSITIVITY 8 //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif - // @section tmc/config - /** * TMC Homing stepper phase. * @@ -3318,7 +2549,7 @@ /** * Enable M122 debugging command for TMC stepper drivers. - * M122 S0/1 will enable continuous reporting. + * M122 S0/1 will enable continous reporting. */ //#define TMC_DEBUG @@ -3337,6 +2568,200 @@ #endif // HAS_TRINAMIC_CONFIG +// @section L64XX + +/** + * L64XX Stepper Driver options + * + * Arduino-L6470 library (0.8.0 or higher) is required. + * https://github.com/ameyer/Arduino-L6470 + * + * Requires the following to be defined in your pins_YOUR_BOARD file + * L6470_CHAIN_SCK_PIN + * L6470_CHAIN_MISO_PIN + * L6470_CHAIN_MOSI_PIN + * L6470_CHAIN_SS_PIN + * ENABLE_RESET_L64XX_CHIPS(Q) where Q is 1 to enable and 0 to reset + */ + +#if HAS_L64XX + + //#define L6470_CHITCHAT // Display additional status info + + #if AXIS_IS_L64XX(X) + #define X_MICROSTEPS 128 // Number of microsteps (VALID: 1, 2, 4, 8, 16, 32, 128) - L6474 max is 16 + #define X_OVERCURRENT 2000 // (mA) Current where the driver detects an over current + // L6470 & L6474 - VALID: 375 x (1 - 16) - 6A max - rounds down + // POWERSTEP01: VALID: 1000 x (1 - 32) - 32A max - rounds down + #define X_STALLCURRENT 1500 // (mA) Current where the driver detects a stall (VALID: 31.25 * (1-128) - 4A max - rounds down) + // L6470 & L6474 - VALID: 31.25 * (1-128) - 4A max - rounds down + // POWERSTEP01: VALID: 200 x (1 - 32) - 6.4A max - rounds down + // L6474 - STALLCURRENT setting is used to set the nominal (TVAL) current + #define X_MAX_VOLTAGE 127 // 0-255, Maximum effective voltage seen by stepper - not used by L6474 + #define X_CHAIN_POS -1 // Position in SPI chain, 0=Not in chain, 1=Nearest MOSI + #define X_SLEW_RATE 1 // 0-3, Slew 0 is slowest, 3 is fastest + #endif + + #if AXIS_IS_L64XX(X2) + #define X2_MICROSTEPS 128 + #define X2_OVERCURRENT 2000 + #define X2_STALLCURRENT 1500 + #define X2_MAX_VOLTAGE 127 + #define X2_CHAIN_POS -1 + #define X2_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Y) + #define Y_MICROSTEPS 128 + #define Y_OVERCURRENT 2000 + #define Y_STALLCURRENT 1500 + #define Y_MAX_VOLTAGE 127 + #define Y_CHAIN_POS -1 + #define Y_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Y2) + #define Y2_MICROSTEPS 128 + #define Y2_OVERCURRENT 2000 + #define Y2_STALLCURRENT 1500 + #define Y2_MAX_VOLTAGE 127 + #define Y2_CHAIN_POS -1 + #define Y2_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Z) + #define Z_MICROSTEPS 128 + #define Z_OVERCURRENT 2000 + #define Z_STALLCURRENT 1500 + #define Z_MAX_VOLTAGE 127 + #define Z_CHAIN_POS -1 + #define Z_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Z2) + #define Z2_MICROSTEPS 128 + #define Z2_OVERCURRENT 2000 + #define Z2_STALLCURRENT 1500 + #define Z2_MAX_VOLTAGE 127 + #define Z2_CHAIN_POS -1 + #define Z2_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Z3) + #define Z3_MICROSTEPS 128 + #define Z3_OVERCURRENT 2000 + #define Z3_STALLCURRENT 1500 + #define Z3_MAX_VOLTAGE 127 + #define Z3_CHAIN_POS -1 + #define Z3_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(Z4) + #define Z4_MICROSTEPS 128 + #define Z4_OVERCURRENT 2000 + #define Z4_STALLCURRENT 1500 + #define Z4_MAX_VOLTAGE 127 + #define Z4_CHAIN_POS -1 + #define Z4_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E0) + #define E0_MICROSTEPS 128 + #define E0_OVERCURRENT 2000 + #define E0_STALLCURRENT 1500 + #define E0_MAX_VOLTAGE 127 + #define E0_CHAIN_POS -1 + #define E0_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E1) + #define E1_MICROSTEPS 128 + #define E1_OVERCURRENT 2000 + #define E1_STALLCURRENT 1500 + #define E1_MAX_VOLTAGE 127 + #define E1_CHAIN_POS -1 + #define E1_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E2) + #define E2_MICROSTEPS 128 + #define E2_OVERCURRENT 2000 + #define E2_STALLCURRENT 1500 + #define E2_MAX_VOLTAGE 127 + #define E2_CHAIN_POS -1 + #define E2_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E3) + #define E3_MICROSTEPS 128 + #define E3_OVERCURRENT 2000 + #define E3_STALLCURRENT 1500 + #define E3_MAX_VOLTAGE 127 + #define E3_CHAIN_POS -1 + #define E3_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E4) + #define E4_MICROSTEPS 128 + #define E4_OVERCURRENT 2000 + #define E4_STALLCURRENT 1500 + #define E4_MAX_VOLTAGE 127 + #define E4_CHAIN_POS -1 + #define E4_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E5) + #define E5_MICROSTEPS 128 + #define E5_OVERCURRENT 2000 + #define E5_STALLCURRENT 1500 + #define E5_MAX_VOLTAGE 127 + #define E5_CHAIN_POS -1 + #define E5_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E6) + #define E6_MICROSTEPS 128 + #define E6_OVERCURRENT 2000 + #define E6_STALLCURRENT 1500 + #define E6_MAX_VOLTAGE 127 + #define E6_CHAIN_POS -1 + #define E6_SLEW_RATE 1 + #endif + + #if AXIS_IS_L64XX(E7) + #define E7_MICROSTEPS 128 + #define E7_OVERCURRENT 2000 + #define E7_STALLCURRENT 1500 + #define E7_MAX_VOLTAGE 127 + #define E7_CHAIN_POS -1 + #define E7_SLEW_RATE 1 + #endif + + /** + * Monitor L6470 drivers for error conditions like over temperature and over current. + * In the case of over temperature Marlin can decrease the drive until the error condition clears. + * Other detected conditions can be used to stop the current print. + * Relevant G-codes: + * M906 - I1/2/3/4/5 Set or get motor drive level using axis codes X, Y, Z, E. Report values if no axis codes given. + * I not present or I0 or I1 - X, Y, Z or E0 + * I2 - X2, Y2, Z2 or E1 + * I3 - Z3 or E3 + * I4 - Z4 or E4 + * I5 - E5 + * M916 - Increase drive level until get thermal warning + * M917 - Find minimum current thresholds + * M918 - Increase speed until max or error + * M122 S0/1 - Report driver parameters + */ + //#define MONITOR_L6470_DRIVER_STATUS + + #if ENABLED(MONITOR_L6470_DRIVER_STATUS) + #define KVAL_HOLD_STEP_DOWN 1 + //#define L6470_STOP_ON_ERROR + #endif + +#endif // HAS_L64XX + // @section i2cbus // @@ -3378,7 +2803,7 @@ #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave #endif -// @section photo +// @section extras /** * Photo G-code @@ -3421,8 +2846,6 @@ #endif #endif -// @section cnc - /** * Spindle & Laser control * @@ -3436,46 +2859,22 @@ * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V * hardware PWM pin for the speed control and a pin for the rotation direction. * - * See https://marlinfw.org/docs/configuration/2.0.9/laser_spindle.html for more config details. + * See https://marlinfw.org/docs/configuration/laser_spindle.html for more config details. */ //#define SPINDLE_FEATURE //#define LASER_FEATURE #if EITHER(SPINDLE_FEATURE, LASER_FEATURE) - #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH - - #define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power - #if ENABLED(SPINDLE_LASER_USE_PWM) - #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower - #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR, ESP32, and LPC) - // ESP32: If SPINDLE_LASER_PWM_PIN is onboard then <=78125Hz. For I2S expander - // the frequency determines the PWM resolution. 2500Hz = 0-100, 977Hz = 0-255, ... - // (250000 / SPINDLE_LASER_FREQUENCY) = max value. - #endif + #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if the on/off function is active HIGH + #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower - //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 - #if ENABLED(AIR_EVACUATION) - #define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH - //#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin - #endif - - //#define AIR_ASSIST // Air Assist control with G-codes M8-M9 - #if ENABLED(AIR_ASSIST) - #define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin - //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin - #endif - - //#define SPINDLE_SERVO // A servo converting an angle to spindle power - #ifdef SPINDLE_SERVO - #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control - #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle - #endif + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) /** * Speed / Power can be set ('M3 S') and displayed in terms of: * - PWM255 (S0 - S255) * - PERCENT (S0 - S100) * - RPM (S0 - S50000) Best for use with a spindle - * - SERVO (S0 - S180) */ #define CUTTER_POWER_UNIT PWM255 @@ -3506,110 +2905,94 @@ * Speed/Power = (PWMDC / 255 * 100 - SPEED_POWER_INTERCEPT) / SPEED_POWER_SLOPE * PWMDC = (spdpwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) / SPEED_POWER_SLOPE */ - #if ENABLED(SPINDLE_LASER_USE_PWM) - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 5000 // (RPM) - #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM - #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) - #endif + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 5000 // (RPM) + #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) #else - #if ENABLED(SPINDLE_LASER_USE_PWM) - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 0 // (%) 0-100 - #define SPEED_POWER_MAX 100 // (%) 0-100 - #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) - #endif - - // Define the minimum and maximum test pulse time values for a laser test fire function - #define LASER_TEST_PULSE_MIN 1 // (ms) Used with Laser Control Menu - #define LASER_TEST_PULSE_MAX 999 // (ms) Caution: Menu may not show more than 3 characters - - #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop - - /** - * Laser Safety Timeout - * - * The laser should be turned off when there is no movement for a period of time. - * Consider material flammability, cut rate, and G-code order when setting this - * value. Too low and it could turn off during a very slow move; too high and - * the material could ignite. - */ - #define LASER_SAFETY_TIMEOUT_MS 1000 // (ms) + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 0 // (%) 0-100 + #define SPEED_POWER_MAX 100 // (%) 0-100 + #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) /** - * Any M3 or G1/2/3/5 command with the 'I' parameter enables continuous inline power mode. - * - * e.g., 'M3 I' enables continuous inline power which is processed by the planner. - * Power is stored in move blocks and applied when blocks are processed by the Stepper ISR. - * - * 'M4 I' sets dynamic mode which uses the current feedrate to calculate a laser power OCR value. + * Enable inline laser power to be handled in the planner / stepper routines. + * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) + * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). * - * Any move in dynamic mode will use the current feedrate to calculate the laser power. - * Feed rates are set by the F parameter of a move command e.g. G1 X0 Y10 F6000 - * Laser power would be calculated by bit shifting off 8 LSB's. In binary this is div 256. - * The calculation gives us ocr values from 0 to 255, values over F65535 will be set as 255 . - * More refined power control such as compesation for accell/decell will be addressed in future releases. - * - * M5 I clears inline mode and set power to 0, M5 sets the power output to 0 but leaves inline mode on. + * This allows the laser to keep in perfect sync with the planner and removes + * the powerup/down delay since lasers require negligible time. */ + #define LASER_POWER_INLINE - /** - * Enable M3 commands for laser mode inline power planner syncing. - * This feature enables any M3 S-value to be injected into the block buffers while in - * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be commited without waiting - * for a planner syncronization - */ - //#define LASER_POWER_SYNC + #if ENABLED(LASER_POWER_INLINE) + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + #define LASER_POWER_INLINE_TRAPEZOID - /** - * Scale the laser's power in proportion to the movement rate. - * - * - Sets the entry power proportional to the entry speed over the nominal speed. - * - Ramps the power up every N steps to approximate the speed trapezoid. - * - Due to the limited power resolution this is only approximate. - */ - //#define LASER_POWER_TRAP - - // - // Laser I2C Ammeter (High precision INA226 low/high side module) - // - //#define I2C_AMMETER - #if ENABLED(I2C_AMMETER) - #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range - #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value - #endif + /** + * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). + * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). + * This is a costly calculation so this option is discouraged on 8-bit AVR boards. + * + * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your + * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. + * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT + + /** + * Stepper iterations between power updates. Increase this value if the board + * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. + * Disable (or set to 0) to recalculate power on every stepper iteration. + */ + //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 + + /** + * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter + */ + //#define LASER_MOVE_POWER + + #if ENABLED(LASER_MOVE_POWER) + // Turn off the laser on G0 moves with no power parameter. + // If a power parameter is provided, use that instead. + //#define LASER_MOVE_G0_OFF - // - // Laser Coolant Flow Meter - // - //#define LASER_COOLANT_FLOW_METER - #if ENABLED(LASER_COOLANT_FLOW_METER) - #define FLOWMETER_PIN 20 // Requires an external interrupt-enabled pin (e.g., RAMPS 2,3,18,19,20,21) - #define FLOWMETER_PPL 5880 // (pulses/liter) Flow meter pulses-per-liter on the input pin - #define FLOWMETER_INTERVAL 1000 // (ms) Flow rate calculation interval in milliseconds - #define FLOWMETER_SAFETY // Prevent running the laser without the minimum flow rate set below - #if ENABLED(FLOWMETER_SAFETY) - #define FLOWMETER_MIN_LITERS_PER_MINUTE 1.5 // (liters/min) Minimum flow required when enabled + // Turn off the laser on G28 homing. + //#define LASER_MOVE_G28_OFF #endif - #endif - #endif -#endif // SPINDLE_FEATURE || LASER_FEATURE + /** + * Inline flag inverted + * + * WARNING: M5 will NOT turn off the laser unless another move + * is done (so G-code files must end with 'M5 I'). + */ + //#define LASER_POWER_INLINE_INVERT -/** - * Synchronous Laser Control with M106/M107 - * - * Marlin normally applies M106/M107 fan speeds at a time "soon after" processing - * a planner block. This is too inaccurate for a PWM/TTL laser attached to the fan - * header (as with some add-on laser kits). Enable this option to set fan/laser - * speeds with much more exact timing for improved print fidelity. - * - * NOTE: This option sacrifices some cooling fan speed options. - */ -//#define LASER_SYNCHRONOUS_M106_M107 + /** + * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') + * + * The laser might do some weird things, so only enable this + * feature if you understand the implications. + */ + //#define LASER_POWER_INLINE_CONTINUOUS + + #else + + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop + + #endif + #endif +#endif /** * Coolant Control @@ -3626,8 +3009,6 @@ #define COOLANT_FLOOD_INVERT false // Set "true" if the on/off function is reversed #endif -// @section filament width - /** * Filament Width Sensor * @@ -3661,8 +3042,6 @@ //#define FILAMENT_LCD_DISPLAY #endif -// @section power - /** * Power Monitor * Monitor voltage (V) and/or current (A), and -when possible- power (W) @@ -3674,31 +3053,13 @@ */ //#define POWER_MONITOR_CURRENT // Monitor the system current //#define POWER_MONITOR_VOLTAGE // Monitor the system voltage - -#if ENABLED(POWER_MONITOR_CURRENT) - #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! - #define POWER_MONITOR_CURRENT_OFFSET 0 // Offset (in amps) applied to the calculated current +#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) + #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! + #define POWER_MONITOR_CURRENT_OFFSET -1 // Offset value for current sensors with linear function output + #define POWER_MONITOR_VOLTS_PER_VOLT 0.11786 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! #define POWER_MONITOR_FIXED_VOLTAGE 13.6 // Voltage for a current sensor with no voltage sensor (for power display) #endif -#if ENABLED(POWER_MONITOR_VOLTAGE) - #define POWER_MONITOR_VOLTS_PER_VOLT 0.077933 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! - #define POWER_MONITOR_VOLTAGE_OFFSET 0 // Offset (in volts) applied to the calculated voltage -#endif - -// @section safety - -/** - * Stepper Driver Anti-SNAFU Protection - * - * If the SAFE_POWER_PIN is defined for your board, Marlin will check - * that stepper drivers are properly plugged in before applying power. - * Disable protection if your stepper drivers don't support the feature. - */ -//#define DISABLE_DRIVER_SAFE_POWER_PROTECT - -// @section cnc - /** * CNC Coordinate Systems * @@ -3707,26 +3068,10 @@ */ //#define CNC_COORDINATE_SYSTEMS -// @section reporting - -/** - * Auto-report fan speed with M123 S - * Requires fans with tachometer pins - */ -//#define AUTO_REPORT_FANS - /** * Auto-report temperatures with M155 S */ #define AUTO_REPORT_TEMPERATURES -#if ENABLED(AUTO_REPORT_TEMPERATURES) && TEMP_SENSOR_REDUNDANT - //#define AUTO_REPORT_REDUNDANT // Include the "R" sensor in the auto-report -#endif - -/** - * Auto-report position with M154 S - */ -//#define AUTO_REPORT_POSITION /** * Include capabilities in M115 output @@ -3736,8 +3081,6 @@ //#define M115_GEOMETRY_REPORT #endif -// @section security - /** * Expected Printer Check * Add the M16 G-code to compare a string to the MACHINE_NAME. @@ -3745,8 +3088,6 @@ */ //#define EXPECTED_PRINTER_CHECK -// @section volumetrics - /** * Disable all Volumetric extrusion options */ @@ -3775,7 +3116,14 @@ #endif #endif -// @section reporting +/** + * Enable this option for a leaner build of Marlin that removes all + * workspace offsets, simplifying coordinate transformations, leveling, etc. + * + * - M206 and M428 are disabled. + * - G92 will revert to its behavior from Marlin 1.0. + */ +//#define NO_WORKSPACE_OFFSETS // Extra options for the M114 "Current Position" report //#define M114_DETAIL // Use 'M114` for details to check planner calculations @@ -3784,10 +3132,17 @@ //#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others) -// @section gcode +/** + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. + * + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 /** - * Spend 28 bytes of SRAM to optimize the G-code parser + * Spend 28 bytes of SRAM to optimize the GCode parser */ #define FASTER_GCODE_PARSER @@ -3795,23 +3150,10 @@ //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif -// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) -//#define MEATPACK_ON_SERIAL_PORT_1 -//#define MEATPACK_ON_SERIAL_PORT_2 - //#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase //#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW -/** - * Enable this option for a leaner build of Marlin that removes all - * workspace offsets, simplifying coordinate transformations, leveling, etc. - * - * - M206 and M428 are disabled. - * - G92 will revert to its behavior from Marlin 1.0. - */ -//#define NO_WORKSPACE_OFFSETS - /** * CNC G-code options * Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc. @@ -3827,8 +3169,6 @@ //#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode #endif -// @section gcode - /** * Startup commands * @@ -3849,109 +3189,31 @@ #endif /** - * User-defined menu items to run custom G-code. - * Up to 25 may be defined, but the actual number is LCD-dependent. + * User-defined menu items that execute custom GCode */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + //#define CUSTOM_USER_MENU_TITLE "Custom Commands" + #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK + //#define USER_SCRIPT_RETURN // Return to status screen after a script -// @section custom main menu - -// Custom Menu: Main Menu -//#define CUSTOM_MENU_MAIN -#if ENABLED(CUSTOM_MENU_MAIN) - //#define CUSTOM_MENU_MAIN_TITLE "Custom Commands" - #define CUSTOM_MENU_MAIN_SCRIPT_DONE "M117 User Script Done" - #define CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK - //#define CUSTOM_MENU_MAIN_SCRIPT_RETURN // Return to status screen after a script - #define CUSTOM_MENU_MAIN_ONLY_IDLE // Only show custom menu when the machine is idle - - #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info" - #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W" - //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action - - #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL - #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) - //#define MAIN_MENU_ITEM_2_CONFIRM - - //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL - //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) - //#define MAIN_MENU_ITEM_3_CONFIRM - - //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level" - //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" - //#define MAIN_MENU_ITEM_4_CONFIRM - - //#define MAIN_MENU_ITEM_5_DESC "Home & Info" - //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503" - //#define MAIN_MENU_ITEM_5_CONFIRM -#endif - -// @section custom config menu + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" -// Custom Menu: Configuration Menu -//#define CUSTOM_MENU_CONFIG -#if ENABLED(CUSTOM_MENU_CONFIG) - //#define CUSTOM_MENU_CONFIG_TITLE "Custom Commands" - #define CUSTOM_MENU_CONFIG_SCRIPT_DONE "M117 Wireless Script Done" - #define CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK - //#define CUSTOM_MENU_CONFIG_SCRIPT_RETURN // Return to status screen after a script - #define CUSTOM_MENU_CONFIG_ONLY_IDLE // Only show custom menu when the machine is idle + #define USER_DESC_2 "Preheat for " PREHEAT_1_LABEL + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) - #define CONFIG_MENU_ITEM_1_DESC "Wifi ON" - #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678" - //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + #define USER_DESC_3 "Preheat for " PREHEAT_2_LABEL + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) - #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON" - #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678" - //#define CONFIG_MENU_ITEM_2_CONFIRM + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" - //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF" - //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678" - //#define CONFIG_MENU_ITEM_3_CONFIRM - - //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????" - //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????" - //#define CONFIG_MENU_ITEM_4_CONFIRM - - //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????" - //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????" - //#define CONFIG_MENU_ITEM_5_CONFIRM -#endif - -// @section custom buttons - -/** - * User-defined buttons to run custom G-code. - * Up to 25 may be defined. - */ -//#define CUSTOM_USER_BUTTONS -#if ENABLED(CUSTOM_USER_BUTTONS) - //#define BUTTON1_PIN -1 - #if PIN_EXISTS(BUTTON1) - #define BUTTON1_HIT_STATE LOW // State of the triggered button. NC=LOW. NO=HIGH. - #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing? - #define BUTTON1_GCODE "G28" - #define BUTTON1_DESC "Homing" // Optional string to set the LCD status - #endif - - //#define BUTTON2_PIN -1 - #if PIN_EXISTS(BUTTON2) - #define BUTTON2_HIT_STATE LOW - #define BUTTON2_WHEN_PRINTING false - #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) - #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL - #endif - - //#define BUTTON3_PIN -1 - #if PIN_EXISTS(BUTTON3) - #define BUTTON3_HIT_STATE LOW - #define BUTTON3_WHEN_PRINTING false - #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) - #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL - #endif + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" #endif -// @section host - /** * Host Action Commands * @@ -3968,26 +3230,16 @@ */ //#define HOST_ACTION_COMMANDS #if ENABLED(HOST_ACTION_COMMANDS) - //#define HOST_PAUSE_M76 // Tell the host to pause in response to M76 - //#define HOST_PROMPT_SUPPORT // Initiate host prompts to get user feedback - #if ENABLED(HOST_PROMPT_SUPPORT) - //#define HOST_STATUS_NOTIFICATIONS // Send some status messages to the host as notifications - #endif - //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start - //#define HOST_SHUTDOWN_MENU_ITEM // Add a menu item that tells the host to shut down + //#define HOST_PROMPT_SUPPORT + //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start #endif -// @section extras - /** * Cancel Objects * * Implement M486 to allow Marlin to skip objects */ //#define CANCEL_OBJECTS -#if ENABLED(CANCEL_OBJECTS) - #define CANCEL_OBJECTS_REPORTING // Emit the current object as a status message -#endif /** * I2C position encoders for closed loop control. @@ -4000,7 +3252,6 @@ * Alternative Supplier: https://reliabuild3d.com/ * * Reliabuild encoders have been modified to improve reliability. - * @section i2c encoders */ //#define I2C_POSITION_ENCODERS @@ -4065,14 +3316,13 @@ */ #define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks. - // Use a rolling average to identify persistent errors that indicate skips, as opposed to vibration and noise. + // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE #endif // I2C_POSITION_ENCODERS /** * Analog Joystick(s) - * @section joystick */ //#define JOYSTICK #if ENABLED(JOYSTICK) @@ -4092,43 +3342,11 @@ //#define JOYSTICK_DEBUG #endif -/** - * Mechanical Gantry Calibration - * Modern replacement for the Průša TMC_Z_CALIBRATION. - * Adds capability to work with any adjustable current drivers. - * Implemented as G34 because M915 is deprecated. - * @section calibrate - */ -//#define MECHANICAL_GANTRY_CALIBRATION -#if ENABLED(MECHANICAL_GANTRY_CALIBRATION) - #define GANTRY_CALIBRATION_CURRENT 600 // Default calibration current in ma - #define GANTRY_CALIBRATION_EXTRA_HEIGHT 15 // Extra distance in mm past Z_###_POS to move - #define GANTRY_CALIBRATION_FEEDRATE 500 // Feedrate for correction move - //#define GANTRY_CALIBRATION_TO_MIN // Enable to calibrate Z in the MIN direction - - //#define GANTRY_CALIBRATION_SAFE_POSITION XY_CENTER // Safe position for nozzle - //#define GANTRY_CALIBRATION_XY_PARK_FEEDRATE 3000 // XY Park Feedrate - MMM - //#define GANTRY_CALIBRATION_COMMANDS_PRE "" - #define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position -#endif - -/** - * Instant freeze / unfreeze functionality - * Potentially useful for emergency stop that allows being resumed. - * @section interface - */ -//#define FREEZE_FEATURE -#if ENABLED(FREEZE_FEATURE) - //#define FREEZE_PIN 41 // Override the default (KILL) pin here - #define FREEZE_STATE LOW // State of pin indicating freeze -#endif - /** * MAX7219 Debug Matrix * * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display. * Requires 3 signal wires. Some useful debug options are included to demonstrate its usage. - * @section debug matrix */ //#define MAX7219_DEBUG #if ENABLED(MAX7219_DEBUG) @@ -4141,8 +3359,7 @@ #define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain. #define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°) // connector at: right=0 bottom=-90 top=90 left=180 - //#define MAX7219_REVERSE_ORDER // The order of the LED matrix units may be reversed - //#define MAX7219_REVERSE_EACH // The LEDs in each matrix unit row may be reversed + //#define MAX7219_REVERSE_ORDER // The individual LED matrix units may be in reversed order //#define MAX7219_SIDE_BY_SIDE // Big chip+matrix boards can be chained side-by-side /** @@ -4150,42 +3367,31 @@ * If you add more debug displays, be careful to avoid conflicts! */ #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning - #define MAX7219_DEBUG_PLANNER_HEAD 2 // Show the planner queue head position on this and the next LED matrix row - #define MAX7219_DEBUG_PLANNER_TAIL 4 // Show the planner queue tail position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row #define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row // If you experience stuttering, reboots, etc. this option can reveal how // tweaks made to the configuration are affecting the printer in real-time. - #define MAX7219_DEBUG_PROFILE 6 // Display the fraction of CPU time spent in profiled code on this LED matrix - // row. By default idle() is profiled so this shows how "idle" the processor is. - // See class CodeProfiler. #endif /** * NanoDLP Sync support * - * Support for Synchronized Z moves when used with NanoDLP. G0/G1 axis moves will - * output a "Z_move_comp" string to enable synchronization with DLP projector exposure. - * This feature allows you to use [[WaitForDoneMessage]] instead of M400 commands. - * @section nanodlp + * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp" + * string to enable synchronization with DLP projector exposure. This change will allow to use + * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands */ //#define NANODLP_Z_SYNC #if ENABLED(NANODLP_Z_SYNC) - //#define NANODLP_ALL_AXIS // Send a "Z_move_comp" report for any axis move (not just Z). -#endif - -/** - * Ethernet. Use M552 to enable and set the IP address. - * @section network - */ -#if HAS_ETHERNET - #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xF0, 0x0D } // A MAC address unique to your network + //#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move. + // Default behavior is limited to Z axis only. #endif /** * WiFi Support (Espressif ESP32 WiFi) */ -//#define WIFISUPPORT // Marlin embedded WiFi management +//#define WIFISUPPORT // Marlin embedded WiFi managenent //#define ESP3D_WIFISUPPORT // ESP3D Library WiFi management (https://github.com/luc-github/ESP3DLib) #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -4204,29 +3410,17 @@ //#include "Configuration_Secure.h" // External file with WiFi SSID / Password #endif -// @section multi-material - /** - * Průša Multi-Material Unit (MMU) + * Pruša Multi-Material Unit v2 * Enable in Configuration.h - * - * These devices allow a single stepper driver on the board to drive - * multi-material feeders with any number of stepper motors. */ -#if HAS_PRUSA_MMU1 - /** - * This option only allows the multiplexer to switch on tool-change. - * Additional options to configure custom E moves are pending. - * - * Override the default DIO selector pins here, if needed. - * Some pins files may provide defaults for these pins. - */ - //#define E_MUX0_PIN 40 // Always Required - //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs - //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs -#elif HAS_PRUSA_MMU2 +#if ENABLED(PRUSA_MMU2) + // Serial port used for communication with MMU2. - #define MMU2_SERIAL_PORT 2 + // For AVR enable the UART port used for the MMU. (e.g., internalSerial) + // For 32-bit boards check your HAL for available serial ports. (e.g., Serial2) + #define INTERNAL_SERIAL_PORT 2 + #define MMU2_SERIAL internalSerial // Use hardware reset for MMU if a pin is defined for it //#define MMU2_RST_PIN 23 @@ -4239,9 +3433,9 @@ // Add an LCD menu for MMU2 //#define MMU2_MENUS - #if EITHER(MMU2_MENUS, HAS_PRUSA_MMU2S) + #if ENABLED(MMU2_MENUS) // Settings for filament load / unload from the LCD menu. - // This is for Průša MK3-style extruders. Customize for your hardware. + // This is for Pruša MK3-style extruders. Customize for your hardware. #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ { 7.2, 1145 }, \ @@ -4264,12 +3458,29 @@ { -50.0, 2000 } #endif + /** + * MMU Extruder Sensor + * + * Support for a Pruša (or other) IR Sensor to detect filament near the extruder + * and make loading more reliable. Suitable for an extruder equipped with a filament + * sensor less than 38mm from the gears. + * + * During loading the extruder will stop when the sensor is triggered, then do a last + * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. + * If all attempts fail, a filament runout will be triggered. + */ + //#define MMU_EXTRUDER_SENSOR + #if ENABLED(MMU_EXTRUDER_SENSOR) + #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail + #endif + /** * Using a sensor like the MMU2S * This mode requires a MK3S extruder with a sensor at the extruder idler, like the MMU2S. * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11 */ - #if HAS_PRUSA_MMU2S + //#define PRUSA_MMU2_S_MODE + #if ENABLED(PRUSA_MMU2_S_MODE) #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/min) @@ -4285,33 +3496,14 @@ #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \ { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE } - #else - - /** - * MMU1 Extruder Sensor - * - * Support for a Průša (or other) IR Sensor to detect filament near the extruder - * and make loading more reliable. Suitable for an extruder equipped with a filament - * sensor less than 38mm from the gears. - * - * During loading the extruder will stop when the sensor is triggered, then do a last - * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. - * If all attempts fail, a filament runout will be triggered. - */ - //#define MMU_EXTRUDER_SENSOR - #if ENABLED(MMU_EXTRUDER_SENSOR) - #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail - #endif - #endif //#define MMU2_DEBUG // Write debug info to serial output -#endif // HAS_PRUSA_MMU2 +#endif // PRUSA_MMU2 /** * Advanced Print Counter settings - * @section stats */ #if ENABLED(PRINTCOUNTER) #define SERVICE_WARNING_BUZZES 3 @@ -4331,42 +3523,10 @@ // //#define M100_FREE_MEMORY_WATCHER -// -// M42 - Set pin states -// -//#define DIRECT_PIN_CONTROL - // // M43 - display pin status, toggle pins, watch pins, watch endstops & toggle LED, test servo probe // //#define PINS_DEBUGGING -// Enable Tests that will run at startup and produce a report -//#define MARLIN_TEST_BUILD - // Enable Marlin dev mode which adds some special commands -//#define MARLIN_DEV_MODE - -#if ENABLED(MARLIN_DEV_MODE) - /** - * D576 - Buffer Monitoring - * To help diagnose print quality issues stemming from empty command buffers. - */ - //#define BUFFER_MONITORING -#endif - -/** - * Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial. - * When running in the debugger it will break for debugging. This is useful to help understand - * a crash from a remote location. Requires ~400 bytes of SRAM and 5Kb of flash. - */ -//#define POSTMORTEM_DEBUGGING - -/** - * Software Reset options - */ -//#define SOFT_RESET_VIA_SERIAL // 'KILL' and '^X' commands will soft-reset the controller -//#define SOFT_RESET_ON_KILL // Use a digital button to soft-reset the controller after KILL - -// Report uncleaned reset reason from register r2 instead of MCUSR. Supported by Optiboot on AVR. -//#define OPTIBOOT_RESET_REASON +//#define MARLIN_DEV_MODE \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 6c813f7b8700..6d925097f74b 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -47,8 +47,6 @@ void spiBegin() { SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); - - IF_DISABLED(SOFTWARE_SPI, spiInit(SPI_HALF_SPEED)); } #if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) @@ -66,7 +64,9 @@ void spiBegin() { * Initialize hardware SPI * Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6] */ - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore SPI pin hints. + // See avr processor documentation CBI( #ifdef PRR @@ -189,7 +189,7 @@ void spiBegin() { // nop to tune soft SPI timing #define nop asm volatile ("\tnop\n") - void spiInit(uint8_t) { /* do nothing */ } + void spiInit(uint8_t, int, int, int, int) { /* do nothing */ } void spiClose() { /* do nothing */ } // Begin SPI transaction, set clock, bit order, data mode diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 47181b018057..3c28879170b6 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -493,7 +493,7 @@ * 5 : 250 - 312 kHz * 6 : 125 - 156 kHz */ - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { switch (spiRate) { case 0: spiTransferTx = (pfnSpiTransfer)spiTransferTx0; @@ -517,8 +517,8 @@ } _SS_WRITE(HIGH); - WRITE(SD_MOSI_PIN, HIGH); - WRITE(SD_SCK_PIN, LOW); + WRITE(( hint_mosi != -1 ) ? hint_mosi : SD_MOSI_PIN, HIGH); + WRITE(( hint_sck != -1 ) ? hint_sck : SD_SCK_PIN, LOW); } void spiClose() {} @@ -532,10 +532,124 @@ #else // !SOFTWARE_SPI + // https://github.com/arduino/ArduinoCore-sam/blob/master/system/libsam/include/spi.h + #define WHILE_TX(N) while ((SPI0->SPI_SR & SPI_SR_TDRE) == (N)) #define WHILE_RX(N) while ((SPI0->SPI_SR & SPI_SR_RDRF) == (N)) #define FLUSH_TX() do{ WHILE_RX(1) SPI0->SPI_RDR; }while(0) + #if 0 + static SPISettings spiConfig; + + // Generic SPI implementation (test me please) + static bool _has_spi_pins = false; + static int _spi_pin_cs; // all SPI pins are tied together (CS, MISO, MOSI, SCK) + + // ------------------------ + // hardware SPI + // https://github.com/arduino/ArduinoCore-sam/blob/master/libraries/SPI/src/SPI.h + // ------------------------ + void spiBegin() {} + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 8000000; break; + case SPI_HALF_SPEED: clock = 4000000; break; + case SPI_QUARTER_SPEED: clock = 2000000; break; + case SPI_EIGHTH_SPEED: clock = 1000000; break; + case SPI_SIXTEENTH_SPEED: clock = 500000; break; + case SPI_SPEED_5: clock = 250000; break; + case SPI_SPEED_6: clock = 125000; break; + default: clock = 4000000; break; // Default from the SPI library + } + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + // We ignore all pins other than chip-select because they have to be tied together anyway. + if (hint_cs != -1) + { + sdSPI.begin(hint_cs); + _spi_pin_cs = hint_cs; + _has_spi_pins = true; + } + else + { + sdSPI.begin(); + _has_spi_pins = false; + } + } + + void spiClose() { + if (_has_spi_pins) + sdSPI.end(_spi_pin_cs); + else + sdSPI.end(); + _has_spi_pins = false; + _spi_pin_cs = -1; + } + + uint8_t spiRec() { + if (_has_spi_pins) + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + else + sdSPI.beginTransaction(spiConfig); + uint8_t returnByte = sdSPI.transfer(0xFF); + if (_has_spi_pins) + sdSPI.endTransaction(_spi_pin_cs); + else + sdSPI.endTransaction(); + return returnByte; + } + + void spiRead(uint8_t *buf, uint16_t nbyte) { + if (nbyte == 0) return; + memset(buf, 0xFF, nbyte); + if (_has_spi_pins == false) + { + sdSPI.beginTransaction(spiConfig); + sdSPI.transfer(buf, nbyte); + } + else + { + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + sdSPI.transfer(_spi_pin_cs, buf, nbyte); + } + // There is no pin-specific endTransaction method. + sdSPI.endTransaction(); + } + + void spiSend(uint8_t b) { + if (_has_spi_pins) + { + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + sdSPI.transfer(_spi_pin_cs, b); + } + else + { + sdSPI.beginTransaction(spiConfig); + sdSPI.transfer(b); + } + sdSPI.endTransaction(); + } + + // SD-card specific. + void spiSendBlock(uint8_t token, const uint8_t *buf) { + if (_has_spi_pins) + { + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + sdSPI.transfer(_spi_pin_cs, token); + sdSPI.transfer(_spi_pin_cs, (uint8_t*)buf, 512); + } + else + { + sdSPI.beginTransaction(spiConfig); + sdSPI.transfer(token); + sdSPI.transfer(buf, 512); + } + sdSPI.endTransaction(); + } + #endif + #if MB(ALLIGATOR) // slave selects controlled by SPI controller @@ -546,7 +660,9 @@ // ------------------------ static bool spiInitialized = false; - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // I guess ignore the hinted pins? + if (spiInitialized) return; // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz @@ -571,7 +687,8 @@ } void spiClose() { - // TODO? + spiInitialized = false; + SPI_Disable(SPI0); } void spiBegin() { @@ -745,7 +862,7 @@ * macro returns immediately which can result in the SPI chip select going * inactive before all the data has been sent. * - * The TMC2130 library uses SPI0->SPI_CSR[3]. + * The TMC2130 library uses SPI0->SPI_CSR[3] (???) * * The U8G hardware SPI uses SPI0->SPI_CSR[0]. The system hangs and/or the * FYSETC_MINI_12864 gets upset if lower baud rates are used and the SD card @@ -761,8 +878,13 @@ * display to use software SPI. */ - void spiInit(uint8_t spiRate=6) { // Default to slowest rate if not specified) - // Also sets U8G SPI rate to 4MHz and the SPI mode to 3 + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // We ignore the hinted pins? Why don't we use the standard, already implemented SPI library? + + // Default to slowest rate if not specified) + // Also sets U8G SPI rate to 4MHz and the SPI mode to 3 + if (spiRate == SPI_RATE_DEFAULT) + spiRate = 6; // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 }; @@ -793,7 +915,7 @@ // TODO? } - void spiBegin() { spiInit(); } + void spiBegin() { spiInit(SPI_RATE_DEFAULT); } static uint8_t spiTransfer(uint8_t data) { WHILE_TX(0); diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp index 68f6a5c1a7cb..42d0d85c25e2 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp @@ -85,6 +85,7 @@ void u8g_SetPILevel_DUE_hw_spi(u8g_t *u8g, uint8_t pin_index, uint8_t level) { uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { switch (msg) { case U8G_COM_MSG_STOP: + spiClose(); break; case U8G_COM_MSG_INIT: @@ -97,8 +98,9 @@ uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va u8g_Delay(5); spiBegin(); - - spiInit(LCD_SPI_SPEED); + // the Arduino Core SPI library of the DUE only cares about the chip-select pin. + // TODO: can we hint all the pins? + spiInit(LCD_SPI_SPEED, -1, -1, -1, U8G_PI_CS); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index b39df72c630a..daeb6676b28e 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -58,7 +58,7 @@ void spiBegin() { #endif } -void spiInit(uint8_t spiRate) { +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { uint32_t clock; switch (spiRate) { @@ -73,10 +73,12 @@ void spiInit(uint8_t spiRate) { } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - SPI.begin(); + // https://github.com/espressif/arduino-esp32/blob/master/libraries/SPI/src/SPI.cpp SPIClass::begin method. + SPI.begin(hint_sck, hint_miso, hint_mosi, hint_cs); } void spiClose() { + SPI.end(); } uint8_t spiRec() { diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 25143044afdf..8f95d7eef7d5 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -73,7 +73,7 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt OUT_WRITE(LCD_RESET_PIN, HIGH); u8g_Delay(5); spiBegin(); - spiInit(LCD_SPI_SPEED); + spiInit(LCD_SPI_SPEED); // TODO: we should hint the used SPI pins here. break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 6d1be8d1548f..800e23847dd9 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -76,8 +76,12 @@ swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); } - void spiInit(uint8_t spiRate) { - SPI_speed = swSpiInit(spiRate, SD_SCK_PIN, SD_MOSI_PIN); + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + SPI_speed = + swSpiInit(spiRate, + ( hint_sck != -1 ) ? hint_sck : SD_SCK_PIN, + ( hint_mosi != -1 ) ? hint_mosi : SD_MOSI_PIN + ); } void spiClose() { @@ -111,14 +115,22 @@ #define INIT_SPI_SPEED SPI_FULL_SPEED #endif - void spiBegin() { spiInit(INIT_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 + void spiBegin() {} // Set up SCK, MOSI & MISO pins for SSP0 - void spiInit(uint8_t spiRate) { - #if SD_MISO_PIN == BOARD_SPI1_MISO_PIN + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + if (spiRate == SPI_SPEED_DEFAULT) + spiRate = INIT_SPI_SPEED; + // We basically ignore all pins other than MISO because we assume that all + // belong to the same hardware SPI capable pin "module". + int used_miso_pin = ( hint_miso != -1 ) ? hint_miso : SD_MISO_PIN; +#ifdef BOARD_SPI1_MISO_PIN + if (used_miso_pin == BOARD_SPI1_MISO_PIN) SPI.setModule(1); - #elif SD_MISO_PIN == BOARD_SPI2_MISO_PIN +#endif +#ifdef BOARD_SPI2_MISO_PIN + if (used_miso_pin == BOARD_SPI2_MISO_PIN) SPI.setModule(2); - #endif +#endif SPI.setDataSize(DATA_SIZE_8BIT); SPI.setDataMode(SPI_MODE0); diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 6a4bf5cea44e..07d0ceeb53d4 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -85,7 +85,7 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, u8g_SetPIOutput(u8g, U8G_PI_RESET); u8g_Delay(5); spiBegin(); - spiInit(LCD_SPI_SPEED); + spiInit(LCD_SPI_SPEED); // TODO: hint the SPI pins here. break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index b6b4018dc699..5312bc29a8e8 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -64,7 +64,7 @@ #include "../../shared/Delay.h" void spiBegin(); -void spiInit(uint8_t spiRate); +void spiInit(uint8_t spiRate, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); void spiSend(uint8_t b); void spiSend(const uint8_t *buf, size_t n); @@ -89,6 +89,7 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar u8g_SetPIOutput(u8g, U8G_PI_CS); u8g_Delay(5); spiBegin(); + // TODO: hint the SPI pins here. spiInit(SPI_EIGHTH_SPEED); // ST7920 max speed is about 1.1 MHz u8g->pin_list[U8G_PI_A0_STATE] = 0; // initial RS state: command mode break; diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 2d6123911c31..c374bc824608 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -60,12 +60,15 @@ // ------------------------ // Hardware SPI + // https://github.com/arduino/ArduinoCore-samd/blob/master/libraries/SPI/SPI.h // ------------------------ void spiBegin() { - spiInit(SPI_HALF_SPEED); } - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore all pin hints. + if (spiRate == SPI_SPEED_DEFAULT) + spiRate = SPI_HALF_SPEED; // Use datarates Marlin uses uint32_t clock; switch (spiRate) { @@ -139,7 +142,7 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { sdSPI.beginTransaction(spiConfig); sdSPI.transfer(token); - sdSPI.transfer((uint8_t*)buf, nullptr, 512); + sdSPI.transfer(buf, nullptr, 512); sdSPI.endTransaction(); } diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 5ddeb0016cea..aac889a7e57d 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -67,7 +67,7 @@ static SPISettings spiConfig; void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); } void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); } - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Use datarates Marlin uses switch (spiRate) { case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M @@ -78,6 +78,11 @@ static SPISettings spiConfig; case SPI_SPEED_6: delaySPIFunc = &delaySPI_2000; break; // desired: 250,000 actual: ~210K default: delaySPIFunc = &delaySPI_4000; break; // desired: 125,000 actual: ~123K } + // TODO: there is an issue on Github by BTT(?) that this does not use software but hardware SPI. + // we are kind of lying to the user here, is that OK? + SPI.setMISO(hint_miso); + SPI.setMOSI(hint_mosi); + SPI.setSCLK(hint_sck); SPI.begin(); } @@ -156,7 +161,9 @@ static SPISettings spiConfig; } // Configure SPI for specified SPI speed - void spiInit(uint8_t spiRate) { + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore chip-select because the software manages it already. + // Use datarates Marlin uses uint32_t clock; switch (spiRate) { diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index a40bec9d644d..b6e2ec6dee1e 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -33,6 +33,10 @@ #define BLOCK_SIZE 512 #define PRODUCT_ID 0x29 +#ifndef SD_MULTIBLOCK_READ_RETRY_CNT + #define SD_MULTIBLOCK_READ_RETRY_CNT 1 +#endif + class Sd2CardUSBMscHandler : public USBMscHandler { public: DiskIODriver* diskIODriver() { @@ -58,19 +62,32 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->writeBlock(blkAddr, pBuf); - return true; + return sd2card->writeBlock(blkAddr, pBuf); } // multi block optimization - sd2card->writeStart(blkAddr, blkLen); - while (blkLen--) { + uint32_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; + + RETRY_MULTI: + uint32 i = blkLen; + uint8_t *cBuf = pBuf; + sd2card->writeStart(blkAddr); + while (i--) { hal.watchdog_refresh(); - sd2card->writeData(pBuf); - pBuf += BLOCK_SIZE; + if (sd2card->writeData(cBuf) == false) + { + sd2card->writeStop(); + if (--multi_retry_cnt == 0) + goto FAIL; + multi_retry_cnt--; + goto RETRY_MULTI: + } + cBuf += BLOCK_SIZE; } sd2card->writeStop(); return true; + FAIL: + return false; } bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { @@ -78,19 +95,32 @@ class Sd2CardUSBMscHandler : public USBMscHandler { // single block if (blkLen == 1) { hal.watchdog_refresh(); - sd2card->readBlock(blkAddr, pBuf); - return true; + return sd2card->readBlock(blkAddr, pBuf); } // multi block optimization + uint32_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; + + RETRY_MULTI: + uint32 i = blkLen; + uint8_t *cBuf = pBuf; sd2card->readStart(blkAddr); - while (blkLen--) { + while (i--) { hal.watchdog_refresh(); - sd2card->readData(pBuf); - pBuf += BLOCK_SIZE; + if (sd2card->readData(cBuf) == false) + { + sd2card->readStop(); + if (--multi_retry_cnt == 0) + goto FAIL; + multi_retry_cnt--; + goto RETRY_MULTI: + } + cBuf += BLOCK_SIZE; } sd2card->readStop(); return true; + FAIL: + return false; } bool IsReady() { diff --git a/Marlin/src/HAL/STM32/sdio.cpp b/Marlin/src/HAL/STM32/sdio.cpp index 41fe90b82540..04793c184de9 100644 --- a/Marlin/src/HAL/STM32/sdio.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -397,7 +397,13 @@ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { #else uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) return true; + while (retries--) + { + if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) return true; +#ifdef SD_RETRY_DO_DELAY + delay(SD_RETRY_DELAY_MS); +#endif + } return false; #endif @@ -433,7 +439,13 @@ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { #else uint8_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; + while (retries--) + { + if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; +#ifdef SD_RETRY_DO_DELAY + delay(SD_RETRY_DELAY_MS); +#endif + } return false; #endif diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index 678cc1d7cbef..a2dc7486d2d9 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -74,7 +74,8 @@ void spiBegin() { * * @details */ -void spiInit(uint8_t spiRate) { +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // TODO: maybe use the more generic STM32 SPI stuff instead, ignore the pins here. /** * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index bc48eef34fa3..4dc5fa931ae6 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -38,7 +38,12 @@ #endif size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } -bool PersistentStore::access_finish() { return true; } +bool PersistentStore::access_finish() { +#if ENABLED(SPI_EEPROM) + spiClose(); +#endif + return true; +} bool PersistentStore::access_start() { eeprom_init(); @@ -48,8 +53,10 @@ bool PersistentStore::access_start() { SET_OUTPUT(BOARD_SPI1_MOSI_PIN); SET_INPUT(BOARD_SPI1_MISO_PIN); SET_OUTPUT(SPI_EEPROM1_CS_PIN); + spiInit(0, BOARD_SPI1_SCK_PIN, BOARD_SPI1_MISO_PIN, BOARD_SPI1_MOSI_PIN, SPI_EEPROM1_CS_PIN); + #else + spiInit(0); #endif - spiInit(0); #endif return true; } diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 6e41d2cbf1b4..515cfadefa81 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -137,7 +137,13 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) { bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) { uint32_t retries = SDIO_READ_RETRIES; - while (retries--) if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; + while (retries--) + { + if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; +#ifdef SD_RETRY_DO_DELAY + delay(SD_RETRY_DELAY_MS); +#endif + } return false; } diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 355186dfe8b7..cb4dd4d0d16e 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -32,6 +32,7 @@ static SPISettings spiConfig; /** * Standard SPI functions + * https://github.com/arduino/ArduinoCore-avr/blob/master/libraries/SPI/src/SPI.h */ // Initialize SPI bus @@ -42,19 +43,11 @@ void spiBegin() { SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); - - #if 0 && DISABLED(SOFTWARE_SPI) - // set SS high - may be chip select for another SPI device - #if SET_SPI_SS_HIGH - WRITE(SD_SS_PIN, HIGH); - #endif - // set a default rate - spiInit(SPI_HALF_SPEED); // 1 - #endif } // Configure SPI for specified SPI speed -void spiInit(uint8_t spiRate) { +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore the pin hints, there is nothing we can do (see arduino core). // Use data rates Marlin uses uint32_t clock; switch (spiRate) { diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 312da3db5914..0d165749ef73 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -42,18 +42,11 @@ void spiBegin() { SET_OUTPUT(SD_SCK_PIN); SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); - - #if 0 && DISABLED(SOFTWARE_SPI) - // set SS high - may be chip select for another SPI device - #if SET_SPI_SS_HIGH - WRITE(SD_SS_PIN, HIGH); - #endif - // set a default rate - spiInit(SPI_HALF_SPEED); // 1 - #endif } -void spiInit(uint8_t spiRate) { +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore the SPI pin hints. + // Use Marlin data-rates uint32_t clock; switch (spiRate) { diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 534bd73b6d8f..1adf8a04a9dc 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -57,18 +57,11 @@ void spiBegin() { //SET_OUTPUT(SD_SCK_PIN); //SET_INPUT(SD_MISO_PIN); //SET_OUTPUT(SD_MOSI_PIN); - - #if 0 && DISABLED(SOFTWARE_SPI) - // set SS high - may be chip select for another SPI device - #if SET_SPI_SS_HIGH - WRITE(SD_SS_PIN, HIGH); - #endif - // set a default rate - spiInit(SPI_HALF_SPEED); // 1 - #endif } -void spiInit(uint8_t spiRate) { +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore the SPI pin hints. + // Use Marlin data-rates uint32_t clock; switch (spiRate) { diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 3b1c83f57050..60c188b7900d 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -53,6 +53,7 @@ #define SPI_SIXTEENTH_SPEED 4 // Set SCK rate to 1/16 of max rate #define SPI_SPEED_5 5 // Set SCK rate to 1/32 of max rate #define SPI_SPEED_6 6 // Set SCK rate to 1/64 of max rate +#define SPI_SPEED_DEFAULT 255 // Let the framework decide (usually recommended value) // // Standard SPI functions @@ -62,7 +63,7 @@ void spiBegin(); // Configure SPI for specified SPI speed -void spiInit(uint8_t spiRate); +void spiInit(uint8_t spiRate, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); // Terminates SPI connection. void spiClose(); @@ -80,7 +81,8 @@ void spiRead(uint8_t *buf, uint16_t nbyte); void spiSendBlock(uint8_t token, const uint8_t *buf); // Begin SPI transaction, set clock, bit order, data mode -void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode); +// DEPRECATED: use spiInit -> spiSend/spiRead -> spiClose instead +//void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode); // // Extended SPI functions taking a channel number (Hardware SPI only) diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 029a04bf97c8..a2af15397015 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -171,9 +171,12 @@ void TFTGLCD::clear_buffer() { void TFTGLCD::clr_screen() { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(CLR_SCREEN); WRITE(TFTGLCD_CS, HIGH); + spiClose(); #else Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address Wire.write(CLR_SCREEN); @@ -201,11 +204,14 @@ void TFTGLCD::print(const char *line) { void TFTGLCD::print_line() { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(LCD_PUT); SPI_SEND_ONE(cour_line); SPI_SEND_SOME(framebuffer, LCD_WIDTH, cour_line * LCD_WIDTH); WRITE(TFTGLCD_CS, HIGH); + spiClose(); #else Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); //set I2C device address Wire.write(LCD_PUT); @@ -222,10 +228,13 @@ void TFTGLCD::print_screen() { framebuffer[FBSIZE - 1] = ledBits; #if ENABLED(TFTGLCD_PANEL_SPI) // Send all framebuffer to panel + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(LCD_WRITE); SPI_SEND_SOME(framebuffer, FBSIZE, 0); WRITE(TFTGLCD_CS, HIGH); + spiClose(); #else uint8_t r; // Send framebuffer to panel by line @@ -250,10 +259,13 @@ void TFTGLCD::print_screen() { void TFTGLCD::setContrast(uint16_t contrast) { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(CONTRAST); SPI_SEND_ONE((uint8_t)contrast); WRITE(TFTGLCD_CS, HIGH); + spiClose(); #else Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); Wire.write(CONTRAST); @@ -269,6 +281,8 @@ uint8_t MarlinUI::read_slow_buttons() { if (!PanelDetected) return 0; #if ENABLED(TFTGLCD_PANEL_SPI) uint8_t b = 0; + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(READ_ENCODER); #ifndef STM32F4xx @@ -281,6 +295,7 @@ uint8_t MarlinUI::read_slow_buttons() { #endif b = SPI_SEND_ONE(GET_SPI_DATA); WRITE(TFTGLCD_CS, HIGH); + spiClose(); return b; #else Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); @@ -303,11 +318,14 @@ void MarlinUI::buzz(const long duration, const uint16_t freq) { if (!PanelDetected) return; if (!sound_on) return; #if ENABLED(TFTGLCD_PANEL_SPI) + spiBegin(); + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(BUZZER); SPI_SEND_TWO((uint16_t)duration); SPI_SEND_TWO(freq); WRITE(TFTGLCD_CS, HIGH); + spiClose(); #else Wire.beginTransmission((uint8_t)LCD_I2C_ADDRESS); Wire.write(BUZZER); @@ -327,6 +345,8 @@ void MarlinUI::init_lcd() { // SPI speed must be less 10MHz SET_OUTPUT(TFTGLCD_CS); WRITE(TFTGLCD_CS, HIGH); + // TODO: hint the SPI pins here. + spiBegin(); spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(GET_LCD_ROW); @@ -363,6 +383,9 @@ void MarlinUI::init_lcd() { } else PanelDetected = 0; +#if ENABLED(TFTGLCD_PANEL_SPI) + spiClose(); +#endif safe_delay(100); } diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 7df5510821fd..1784b589842a 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -167,7 +167,7 @@ void DiskIODriver_SPI_SD::chipDeselect() { } void DiskIODriver_SPI_SD::chipSelect() { - spiInit(spiRate_); + spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, chipSelectPin_); extDigitalWrite(chipSelectPin_, LOW); } @@ -266,7 +266,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Set SCK rate for initialization commands spiRate_ = SPI_SD_INIT_RATE; - spiInit(spiRate_); + spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, chipSelectPin_); // Must supply min of 74 clock cycles with CS high. LOOP_L_N(i, 10) spiSend(0xFF); @@ -354,7 +354,7 @@ bool DiskIODriver_SPI_SD::readBlock(uint32_t blockNumber, uint8_t *dst) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card #if ENABLED(SD_CHECK_AND_RETRY) - uint8_t retryCnt = 3; + uint8_t retryCnt = SD_RETRY_COUNT; for (;;) { if (cardCommand(CMD17, blockNumber)) error(SD_CARD_ERROR_CMD17); diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 9229da69ab69..1f2ecf10f2d8 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -42,19 +42,25 @@ void MAX3421e::ncs() { WRITE(USB_CS_PIN, HIGH); } // write single byte into MAX3421 register void MAX3421e::regWr(uint8_t reg, uint8_t data) { + spiBegin(); + spiInit(SD_SPI_SPEED); cs(); spiSend(reg | 0x02); spiSend(data); ncs(); + spiClose(); } // multiple-byte write // return a pointer to memory position after last written uint8_t* MAX3421e::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { + spiBegin(); + spiInit(SD_SPI_SPEED); cs(); spiSend(reg | 0x02); while (nbytes--) spiSend(*data_p++); ncs(); + spiClose(); return data_p; } @@ -69,20 +75,26 @@ void MAX3421e::gpioWr(uint8_t data) { // single host register read uint8_t MAX3421e::regRd(uint8_t reg) { + spiBegin(); + spiInit(SD_SPI_SPEED); cs(); spiSend(reg); uint8_t rv = spiRec(); ncs(); + spiClose(); return rv; } // multiple-byte register read // return a pointer to a memory position after last read uint8_t* MAX3421e::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { + spiBegin(); + spiInit(SD_SPI_SPEED); cs(); spiSend(reg); while (nbytes--) *data_p++ = spiRec(); ncs(); + spiClose(); return data_p; } @@ -111,9 +123,6 @@ bool MAX3421e::start() { SET_OUTPUT(USB_CS_PIN); SET_INPUT_PULLUP(USB_INTR_PIN); ncs(); - spiBegin(); - - spiInit(SD_SPI_SPEED); // MAX3421e - full-duplex, level interrupt, vbus off. regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL | GPX_VBDET)); @@ -149,10 +158,8 @@ bool MAX3421e::start() { // GPX pin on. This is done here so that busprobe will fail if we have a switch connected. regWr(rPINCTL, bmFDUPSPI | bmINTLEVEL); - spiClose(); return true; fail: - spiClose(); return false; } From c3f17d71c908d4695881e0da1c992e8cbfeffcce Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 15:57:33 +0200 Subject: [PATCH 08/83] - reverting configuration changes that were not meant to be committed (oops) --- Marlin/Configuration.h | 1659 +++++++++++++++++++------ Marlin/Configuration_adv.h | 2410 ++++++++++++++++++++++++------------ 2 files changed, 2924 insertions(+), 1145 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 92f5882dcca2..87a98298a58e 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -34,7 +34,6 @@ * - Extra features * * Advanced settings can be found in Configuration_adv.h - * */ #define CONFIGURATION_H_VERSION 02010200 @@ -43,35 +42,25 @@ //=========================================================================== /** - * Here are some standard links for getting your machine calibrated: + * Here are some useful links to help get your machine configured and calibrated: + * + * Example Configs: https://github.com/MarlinFirmware/Configurations/branches/all + * + * Průša Calculator: https://blog.prusaprinters.org/calculator_3416/ + * + * Calibration Guides: https://reprap.org/wiki/Calibration + * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * https://youtu.be/wAL9d7FgInk * - * https://reprap.org/wiki/Calibration - * https://youtu.be/wAL9d7FgInk - * http://calculator.josefprusa.cz - * https://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide - * https://www.thingiverse.com/thing:5573 - * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap - * https://www.thingiverse.com/thing:298812 + * Calibration Objects: https://www.thingiverse.com/thing:5573 + * https://www.thingiverse.com/thing:1278865 */ -//=========================================================================== -//============================= DELTA Printer =============================== -//=========================================================================== -// For a Delta printer start with one of the configuration files in the -// config/examples/delta directory and customize for your machine. -// - -//=========================================================================== -//============================= SCARA Printer =============================== -//=========================================================================== -// For a SCARA printer start with the configuration files in -// config/examples/SCARA and customize for your machine. -// - // @section info // Author info of this build printed to the host during boot and M115 -#define STRING_CONFIG_H_AUTHOR "EirDev" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. //#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes) /** @@ -96,6 +85,11 @@ // @section machine +// Choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_RAMPS_14_EFB +#endif + /** * Select the serial port on the board to use for communication with the host. * This allows the connection of wireless adapters (for instance) to non-default port pins. @@ -107,13 +101,9 @@ #define SERIAL_PORT 0 /** - * Select a secondary serial port on the board to use for communication with the host. - * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] - */ -//#define SERIAL_PORT_2 -1 - -/** - * This setting determines the communication speed of the printer. + * Serial Port Baud Rate + * This is the default communication speed for all serial ports. + * Set the baud rate defaults for additional serial ports below. * * 250000 works in most cases, but you might try a lower speed if * you commonly experience drop-outs during host printing. @@ -123,14 +113,27 @@ */ #define BAUDRATE 250000 +//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate + +/** + * Select a secondary serial port on the board to use for communication with the host. + * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. + * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_2 -1 +//#define BAUDRATE_2 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE + +/** + * Select a third serial port on the board to use for communication with the host. + * Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1 + * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] + */ +//#define SERIAL_PORT_3 1 +//#define BAUDRATE_3 250000 // :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] Enable to override BAUDRATE + // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH -// Choose the name from boards.h that matches your setup -#ifndef MOTHERBOARD - #define MOTHERBOARD BOARD_RAMPS_14_EFB -#endif - // Name displayed in the LCD "Ready" message and Info menu //#define CUSTOM_MACHINE_NAME "3D Printer" @@ -138,6 +141,88 @@ // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section stepper drivers + +/** + * Stepper Drivers + * + * These settings allow Marlin to tune stepper driver timing and enable advanced options for + * stepper drivers that support them. You may also override timing options in Configuration_adv.h. + * + * Use TMC2208/TMC2208_STANDALONE for TMC2225 drivers and TMC2209/TMC2209_STANDALONE for TMC2226 drivers. + * + * Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100, + * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, + * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, + * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, + * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE + * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] + */ +#define X_DRIVER_TYPE A4988 +#define Y_DRIVER_TYPE A4988 +#define Z_DRIVER_TYPE A4988 +//#define X2_DRIVER_TYPE A4988 +//#define Y2_DRIVER_TYPE A4988 +//#define Z2_DRIVER_TYPE A4988 +//#define Z3_DRIVER_TYPE A4988 +//#define Z4_DRIVER_TYPE A4988 +//#define I_DRIVER_TYPE A4988 +//#define J_DRIVER_TYPE A4988 +//#define K_DRIVER_TYPE A4988 +//#define U_DRIVER_TYPE A4988 +//#define V_DRIVER_TYPE A4988 +//#define W_DRIVER_TYPE A4988 +#define E0_DRIVER_TYPE A4988 +//#define E1_DRIVER_TYPE A4988 +//#define E2_DRIVER_TYPE A4988 +//#define E3_DRIVER_TYPE A4988 +//#define E4_DRIVER_TYPE A4988 +//#define E5_DRIVER_TYPE A4988 +//#define E6_DRIVER_TYPE A4988 +//#define E7_DRIVER_TYPE A4988 + +/** + * Additional Axis Settings + * + * Define AXISn_ROTATES for all axes that rotate or pivot. + * Rotational axis coordinates are expressed in degrees. + * + * AXISn_NAME defines the letter used to refer to the axis in (most) G-code commands. + * By convention the names and roles are typically: + * 'A' : Rotational axis parallel to X + * 'B' : Rotational axis parallel to Y + * 'C' : Rotational axis parallel to Z + * 'U' : Secondary linear axis parallel to X + * 'V' : Secondary linear axis parallel to Y + * 'W' : Secondary linear axis parallel to Z + * + * Regardless of these settings the axes are internally named I, J, K, U, V, W. + */ +#ifdef I_DRIVER_TYPE + #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] + #define AXIS4_ROTATES +#endif +#ifdef J_DRIVER_TYPE + #define AXIS5_NAME 'B' // :['B', 'C', 'U', 'V', 'W'] + #define AXIS5_ROTATES +#endif +#ifdef K_DRIVER_TYPE + #define AXIS6_NAME 'C' // :['C', 'U', 'V', 'W'] + #define AXIS6_ROTATES +#endif +#ifdef U_DRIVER_TYPE + #define AXIS7_NAME 'U' // :['U', 'V', 'W'] + //#define AXIS7_ROTATES +#endif +#ifdef V_DRIVER_TYPE + #define AXIS8_NAME 'V' // :['V', 'W'] + //#define AXIS8_ROTATES +#endif +#ifdef W_DRIVER_TYPE + #define AXIS9_NAME 'W' // :['W'] + //#define AXIS9_ROTATES +#endif + // @section extruder // This defines the number of extruders @@ -157,34 +242,23 @@ //#define SINGLENOZZLE_STANDBY_FAN #endif -/** - * Pruša MK2 Single Nozzle Multi-Material Multiplexer, and variants. - * - * This device allows one stepper driver on a control board to drive - * two to eight stepper motors, one at a time, in a manner suitable - * for extruders. - * - * This option only allows the multiplexer to switch on tool-change. - * Additional options to configure custom E moves are pending. - */ -//#define MK2_MULTIPLEXER -#if ENABLED(MK2_MULTIPLEXER) - // Override the default DIO selector pins here, if needed. - // Some pins files may provide defaults for these pins. - //#define E_MUX0_PIN 40 // Always Required - //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs - //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs -#endif +// @section multi-material /** - * Pruša Multi-Material Unit v2 + * Multi-Material Unit + * Set to one of these predefined models: * - * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. - * Requires EXTRUDERS = 5 + * PRUSA_MMU1 : Průša MMU1 (The "multiplexer" version) + * PRUSA_MMU2 : Průša MMU2 + * PRUSA_MMU2S : Průša MMU2S (Requires MK3S extruder with motion sensor, EXTRUDERS = 5) + * EXTENDABLE_EMU_MMU2 : MMU with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) + * EXTENDABLE_EMU_MMU2S : MMUS with configurable number of filaments (ERCF, SMuFF or similar with Průša MMU2 compatible firmware) * - * For additional configuration see Configuration_adv.h + * Requires NOZZLE_PARK_FEATURE to park print head in case MMU unit fails. + * See additional options in Configuration_adv.h. + * :["PRUSA_MMU1", "PRUSA_MMU2", "PRUSA_MMU2S", "EXTENDABLE_EMU_MMU2", "EXTENDABLE_EMU_MMU2S"] */ -//#define PRUSA_MMU2 +//#define MMU_MODEL PRUSA_MMU2 // A dual extruder that uses a single stepper motor //#define SWITCHING_EXTRUDER @@ -202,6 +276,7 @@ #define SWITCHING_NOZZLE_SERVO_NR 0 //#define SWITCHING_NOZZLE_E1_SERVO_NR 1 // If two servos are used, the index of the second #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 (single servo) or lowered/raised (dual servo) + #define SWITCHING_NOZZLE_SERVO_DWELL 2500 // Dwell time to wait for servo to make physical move #endif /** @@ -224,7 +299,6 @@ #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // (mm) Distance to move beyond the parking point to grab the extruder - //#define MANUAL_SOLENOID_CONTROL // Manual control of docking solenoids with M380 S / M381 #if ENABLED(PARKING_EXTRUDER) @@ -306,6 +380,7 @@ #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands //#define GRADIENT_MIX // Support for gradient mixing with M166 and LCD + //#define MIXING_PRESETS // Assign 8 default V-tool presets for 2 or 3 MIXING_STEPPERS #if ENABLED(GRADIENT_MIX) //#define GRADIENT_VTOOL // Add M166 T to use a V-tool index as a Gradient alias #endif @@ -318,7 +393,7 @@ //#define HOTEND_OFFSET_Y { 0.0, 5.00 } // (mm) relative Y-offset for each nozzle //#define HOTEND_OFFSET_Z { 0.0, 0.00 } // (mm) relative Z-offset for each nozzle -// @section machine +// @section psu control /** * Power Supply Control @@ -330,10 +405,20 @@ //#define PSU_NAME "Power Supply" #if ENABLED(PSU_CONTROL) + //#define MKS_PWC // Using the MKS PWC add-on + //#define PS_OFF_CONFIRM // Confirm dialog when power off + //#define PS_OFF_SOUND // Beep 1s when power off #define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box - //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 - //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power + //#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80 + //#define PSU_POWERUP_DELAY 250 // (ms) Delay for the PSU to warm up to full power + //#define LED_POWEROFF_TIMEOUT 10000 // (ms) Turn off LEDs after power-off, with this amount of delay + + //#define POWER_OFF_TIMER // Enable M81 D to power off after a delay + //#define POWER_OFF_WAIT_FOR_COOLDOWN // Enable M81 S to power off only after cooldown + + //#define PSU_POWERUP_GCODE "M355 S1" // G-code to run after power-on (e.g., case light on) + //#define PSU_POWEROFF_GCODE "M355 S0" // G-code to run before power-off (e.g., case light off) //#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin #if ENABLED(AUTO_POWER_CONTROL) @@ -341,80 +426,115 @@ #define AUTO_POWER_E_FANS #define AUTO_POWER_CONTROLLERFAN #define AUTO_POWER_CHAMBER_FAN - //#define AUTO_POWER_E_TEMP 50 // (°C) Turn on PSU over this temperature - //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) Turn on PSU over this temperature - #define POWER_TIMEOUT 30 + #define AUTO_POWER_COOLER_FAN + #define POWER_TIMEOUT 30 // (s) Turn off power if the machine is idle for this duration + //#define POWER_OFF_DELAY 60 // (s) Delay of poweroff after M81 command. Useful to let fans run for extra time. + #endif + #if EITHER(AUTO_POWER_CONTROL, POWER_OFF_WAIT_FOR_COOLDOWN) + //#define AUTO_POWER_E_TEMP 50 // (°C) PSU on if any extruder is over this temperature + //#define AUTO_POWER_CHAMBER_TEMP 30 // (°C) PSU on if the chamber is over this temperature + //#define AUTO_POWER_COOLER_TEMP 26 // (°C) PSU on if the cooler is over this temperature #endif #endif -// @section temperature - //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== +// @section temperature /** - * --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table + * --NORMAL IS 4.7kΩ PULLUP!-- 1kΩ pullup can be used on hotend sensor, using correct resistor and table * * Temperature sensors available: * - * -5 : PT100 / PT1000 with MAX31865 (only for sensors 0-1) - * -3 : thermocouple with MAX31855 (only for sensors 0-1) - * -2 : thermocouple with MAX6675 (only for sensors 0-1) - * -4 : thermocouple with AD8495 - * -1 : thermocouple with AD595 + * SPI RTD/Thermocouple Boards - IMPORTANT: Read the NOTE below! + * ------- + * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) + * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. + * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) + * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) + * + * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, + * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, + * Software SPI will be used on those ports instead. You can force Hardware SPI on the default bus in the + * Configuration_adv.h file. At this time, separate Hardware SPI buses for sensors are not supported. + * + * Analog Themocouple Boards + * ------- + * -4 : AD8495 with Thermocouple + * -1 : AD595 with Thermocouple + * + * Analog Thermistors - 4.7kΩ pullup - Normal + * ------- + * 1 : 100kΩ EPCOS - Best choice for EPCOS thermistors + * 331 : 100kΩ Same as #1, but 3.3V scaled for MEGA + * 332 : 100kΩ Same as #1, but 3.3V scaled for DUE + * 2 : 200kΩ ATC Semitec 204GT-2 + * 202 : 200kΩ Copymaster 3D + * 3 : ???Ω Mendel-parts thermistor + * 4 : 10kΩ Generic Thermistor !! DO NOT use for a hotend - it gives bad resolution at high temp. !! + * 5 : 100kΩ ATC Semitec 104GT-2/104NT-4-R025H42G - Used in ParCan, J-Head, and E3D, SliceEngineering 300°C + * 501 : 100kΩ Zonestar - Tronxy X3A + * 502 : 100kΩ Zonestar - used by hot bed in Zonestar Průša P802M + * 503 : 100kΩ Zonestar (Z8XM2) Heated Bed thermistor + * 504 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-B3950) Hotend Thermistor + * 505 : 100kΩ Zonestar P802QR2 (Part# QWG-104F-3950) Bed Thermistor + * 512 : 100kΩ RPW-Ultra hotend + * 6 : 100kΩ EPCOS - Not as accurate as table #1 (created using a fluke thermocouple) + * 7 : 100kΩ Honeywell 135-104LAG-J01 + * 71 : 100kΩ Honeywell 135-104LAF-J01 + * 8 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT + * 9 : 100kΩ GE Sensing AL03006-58.2K-97-G1 + * 10 : 100kΩ RS PRO 198-961 + * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% + * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed + * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% + * 15 : 100kΩ Calibrated for JGAurora A5 hotend + * 18 : 200kΩ ATC Semitec 204GT-2 Dagoma.Fr - MKS_Base_DKU001327 + * 22 : 100kΩ GTM32 Pro vB - hotend - 4.7kΩ pullup to 3.3V and 220Ω to analog input + * 23 : 100kΩ GTM32 Pro vB - bed - 4.7kΩ pullup to 3.3v and 220Ω to analog input + * 30 : 100kΩ Kis3d Silicone heating mat 200W/300W with 6mm precision cast plate (EN AW 5083) NTC100K - beta 3950 + * 60 : 100kΩ Maker's Tool Works Kapton Bed Thermistor - beta 3950 + * 61 : 100kΩ Formbot/Vivedino 350°C Thermistor - beta 3950 + * 66 : 4.7MΩ Dyze Design / Trianglelab T-D500 500°C High Temperature Thermistor + * 67 : 500kΩ SliceEngineering 450°C Thermistor + * 68 : PT100 amplifier board from Dyze Design + * 70 : 100kΩ bq Hephestos 2 + * 75 : 100kΩ Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32 + * 2000 : 100kΩ Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor + * + * Analog Thermistors - 1kΩ pullup - Atypical, and requires changing out the 4.7kΩ pullup for 1kΩ. + * ------- (but gives greater accuracy and more stable PID) + * 51 : 100kΩ EPCOS (1kΩ pullup) + * 52 : 200kΩ ATC Semitec 204GT-2 (1kΩ pullup) + * 55 : 100kΩ ATC Semitec 104GT-2 - Used in ParCan & J-Head (1kΩ pullup) + * + * Analog Thermistors - 10kΩ pullup - Atypical + * ------- + * 99 : 100kΩ Found on some Wanhao i3 machines with a 10kΩ pull-up resistor + * + * Analog RTDs (Pt100/Pt1000) + * ------- + * 110 : Pt100 with 1kΩ pullup (atypical) + * 147 : Pt100 with 4.7kΩ pullup + * 1010 : Pt1000 with 1kΩ pullup (atypical) + * 1022 : Pt1000 with 2.2kΩ pullup + * 1047 : Pt1000 with 4.7kΩ pullup (E3D) + * 20 : Pt100 with circuit in the Ultimainboard V2.x with mainboard ADC reference voltage = INA826 amplifier-board supply voltage. + * NOTE: (1) Must use an ADC input with no pullup. (2) Some INA826 amplifiers are unreliable at 3.3V so consider using sensor 147, 110, or 21. + * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v ADC reference voltage (STM32, LPC176x....) and 5V INA826 amplifier board supply. + * NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C. + * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x + * + * Custom/Dummy/Other Thermal Sensors + * ------ * 0 : not used - * 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup) - * 331 : (3.3V scaled thermistor 1 table for MEGA) - * 332 : (3.3V scaled thermistor 1 table for DUE) - * 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) - * 202 : 200k thermistor - Copymaster 3D - * 3 : Mendel-parts thermistor (4.7k pullup) - * 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! - * 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan, J-Head, and E3D) (4.7k pullup) - * 501 : 100K Zonestar (Tronxy X3A) Thermistor - * 502 : 100K Zonestar Thermistor used by hot bed in Zonestar Pruša P802M - * 512 : 100k RPW-Ultra hotend thermistor (4.7k pullup) - * 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) - * 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup) - * 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup) - * 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) - * 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup) - * 10 : 100k RS thermistor 198-961 (4.7k pullup) - * 11 : 100k beta 3950 1% thermistor (Used in Keenovo AC silicone mats and most Wanhao i3 machines) (4.7k pullup) - * 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed) - * 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE" - * 15 : 100k thermistor calibration for JGAurora A5 hotend - * 18 : ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - * 20 : Pt100 with circuit in the Ultimainboard V2.x with 5v excitation (AVR) - * 21 : Pt100 with circuit in the Ultimainboard V2.x with 3.3v excitation (STM32 \ LPC176x....) - * 22 : 100k (hotend) with 4.7k pullup to 3.3V and 220R to analog input (as in GTM32 Pro vB) - * 23 : 100k (bed) with 4.7k pullup to 3.3v and 220R to analog input (as in GTM32 Pro vB) - * 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x - * 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 - * 61 : 100k Formbot / Vivedino 3950 350C thermistor 4.7k pullup - * 66 : 4.7M High Temperature thermistor from Dyze Design - * 67 : 450C thermistor from SliceEngineering - * 70 : the 100K thermistor found in the bq Hephestos 2 - * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor - * 99 : 100k thermistor with a 10K pull-up resistor (found on some Wanhao i3 machines) - * - * 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k. - * (but gives greater accuracy and more stable PID) - * 51 : 100k thermistor - EPCOS (1k pullup) - * 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup) - * 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) - * - * 1047 : Pt1000 with 4k7 pullup (E3D) - * 1010 : Pt1000 with 1k pullup (non standard) - * 147 : Pt100 with 4k7 pullup - * 110 : Pt100 with 1k pullup (non standard) - * * 1000 : Custom - Specify parameters in Configuration_adv.h * - * Use these for Testing or Development purposes. NEVER for production machine. + * !!! Use these for Testing or Development purposes. NEVER for production machine. !!! * 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below. * 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below. + * */ #define TEMP_SENSOR_0 1 #define TEMP_SENSOR_1 0 @@ -427,23 +547,61 @@ #define TEMP_SENSOR_BED 0 #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 +#define TEMP_SENSOR_COOLER 0 +#define TEMP_SENSOR_BOARD 0 +#define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 -#define DUMMY_THERMISTOR_998_VALUE 25 +#define DUMMY_THERMISTOR_998_VALUE 25 #define DUMMY_THERMISTOR_999_VALUE 100 -// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings -// from the two sensors differ too much the print will be aborted. -//#define TEMP_SENSOR_1_AS_REDUNDANT -#define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 +// Resistor values when using MAX31865 sensors (-5) on TEMP_SENSOR_0 / 1 +#if TEMP_SENSOR_IS_MAX_TC(0) + #define MAX31865_SENSOR_OHMS_0 100 // (Ω) Typically 100 or 1000 (PT100 or PT1000) + #define MAX31865_CALIBRATION_OHMS_0 430 // (Ω) Typically 430 for Adafruit PT100; 4300 for Adafruit PT1000 +#endif +#if TEMP_SENSOR_IS_MAX_TC(1) + #define MAX31865_SENSOR_OHMS_1 100 + #define MAX31865_CALIBRATION_OHMS_1 430 +#endif +#if TEMP_SENSOR_IS_MAX_TC(2) + #define MAX31865_SENSOR_OHMS_2 100 + #define MAX31865_CALIBRATION_OHMS_2 430 +#endif + +#if HAS_E_TEMP_SENSOR + #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 + #define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif + +#if TEMP_SENSOR_BED + #define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 + #define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif -#define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 -#define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#if TEMP_SENSOR_CHAMBER + #define TEMP_CHAMBER_RESIDENCY_TIME 10 // (seconds) Time to wait for chamber to "settle" in M191 + #define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer + #define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +#endif -#define TEMP_BED_RESIDENCY_TIME 10 // (seconds) Time to wait for bed to "settle" in M190 -#define TEMP_BED_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer -#define TEMP_BED_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +/** + * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) + * + * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another + * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C), + * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting + * the Bed sensor (-1) will disable bed heating/monitoring. + * + * For selecting source/target use: COOLER, PROBE, BOARD, CHAMBER, BED, E0, E1, E2, E3, E4, E5, E6, E7 + */ +#if TEMP_SENSOR_REDUNDANT + #define TEMP_SENSOR_REDUNDANT_SOURCE E1 // The sensor that will provide the redundant reading. + #define TEMP_SENSOR_REDUNDANT_TARGET E0 // The sensor that we are providing a redundant reading for. + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. +#endif // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. @@ -456,6 +614,7 @@ #define HEATER_6_MINTEMP 5 #define HEATER_7_MINTEMP 5 #define BED_MINTEMP 5 +#define CHAMBER_MINTEMP 5 // Above this temperature the heater will be switched off. // This can protect components from overheating, but NOT from shorts and failures. @@ -469,35 +628,93 @@ #define HEATER_6_MAXTEMP 275 #define HEATER_7_MAXTEMP 275 #define BED_MAXTEMP 150 +#define CHAMBER_MAXTEMP 60 + +/** + * Thermal Overshoot + * During heatup (and printing) the temperature can often "overshoot" the target by many degrees + * (especially before PID tuning). Setting the target temperature too close to MAXTEMP guarantees + * a MAXTEMP shutdown! Use these values to forbid temperatures being set too close to MAXTEMP. + */ +#define HOTEND_OVERSHOOT 15 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT +#define BED_OVERSHOOT 10 // (°C) Forbid temperatures over MAXTEMP - OVERSHOOT +#define COOLER_OVERSHOOT 2 // (°C) Forbid temperatures closer than OVERSHOOT //=========================================================================== //============================= PID Settings ================================ //=========================================================================== -// PID Tuning Guide here: https://reprap.org/wiki/PID_Tuning -// Comment the following line to disable PID and enable bang-bang. -#define PIDTEMP +// @section hotend temp + +// Enable PIDTEMP for PID control or MPCTEMP for Predictive Model. +// temperature control. Disable both for bang-bang heating. +#define PIDTEMP // See the PID Tuning Guide at https://reprap.org/wiki/PID_Tuning +//#define MPCTEMP // ** EXPERIMENTAL ** + #define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current #define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current #define PID_K1 0.95 // Smoothing factor within any PID loop #if ENABLED(PIDTEMP) - //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of PROGMEM) - //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of PROGMEM) - //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) - // Set/get with gcode: M301 E[extruder number, 0-2] + //#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation. + //#define PID_PARAMS_PER_HOTEND // Use separate PID parameters for each extruder (useful for mismatched extruders) + // Set/get with G-code: M301 E[extruder number, 0-2] + #if ENABLED(PID_PARAMS_PER_HOTEND) - // Specify between 1 and HOTENDS values per array. - // If fewer than EXTRUDER values are provided, the last element will be repeated. - #define DEFAULT_Kp_LIST { 22.20, 20.0 } - #define DEFAULT_Ki_LIST { 1.08, 1.0 } - #define DEFAULT_Kd_LIST { 114.00, 112.0 } + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. + #define DEFAULT_Kp_LIST { 22.20, 22.20 } + #define DEFAULT_Ki_LIST { 1.08, 1.08 } + #define DEFAULT_Kd_LIST { 114.00, 114.00 } #else #define DEFAULT_Kp 22.20 #define DEFAULT_Ki 1.08 #define DEFAULT_Kd 114.00 #endif -#endif // PIDTEMP +#endif + +/** + * Model Predictive Control for hotend + * + * Use a physical model of the hotend to control temperature. When configured correctly + * this gives better responsiveness and stability than PID and it also removes the need + * for PID_EXTRUSION_SCALING and PID_FAN_SCALING. Use M306 T to autotune the model. + * @section mpctemp + */ +#if ENABLED(MPCTEMP) + //#define MPC_EDIT_MENU // Add MPC editing to the "Advanced Settings" menu. (~1300 bytes of flash) + //#define MPC_AUTOTUNE_MENU // Add MPC auto-tuning to the "Advanced Settings" menu. (~350 bytes of flash) + + #define MPC_MAX BANG_MAX // (0..255) Current to nozzle while MPC is active. + #define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers. + + #define MPC_INCLUDE_FAN // Model the fan speed? + + // Measured physical constants from M306 + #define MPC_BLOCK_HEAT_CAPACITY { 16.7f } // (J/K) Heat block heat capacities. + #define MPC_SENSOR_RESPONSIVENESS { 0.22f } // (K/s per ∆K) Rate of change of sensor temperature from heat block. + #define MPC_AMBIENT_XFER_COEFF { 0.068f } // (W/K) Heat transfer coefficients from heat block to room air with fan off. + #if ENABLED(MPC_INCLUDE_FAN) + #define MPC_AMBIENT_XFER_COEFF_FAN255 { 0.097f } // (W/K) Heat transfer coefficients from heat block to room air with fan on full. + #endif + + // For one fan and multiple hotends MPC needs to know how to apply the fan cooling effect. + #if ENABLED(MPC_INCLUDE_FAN) + //#define MPC_FAN_0_ALL_HOTENDS + //#define MPC_FAN_0_ACTIVE_HOTEND + #endif + + #define FILAMENT_HEAT_CAPACITY_PERMM { 5.6e-3f } // 0.0056 J/K/mm for 1.75mm PLA (0.0149 J/K/mm for 2.85mm PLA). + //#define FILAMENT_HEAT_CAPACITY_PERMM { 3.6e-3f } // 0.0036 J/K/mm for 1.75mm PETG (0.0094 J/K/mm for 2.85mm PETG). + + // Advanced options + #define MPC_SMOOTHING_FACTOR 0.5f // (0.0...1.0) Noisy temperature sensors may need a lower value for stabilization. + #define MPC_MIN_AMBIENT_CHANGE 1.0f // (K/s) Modeled ambient temperature rate of change, when correcting model inaccuracies. + #define MPC_STEADYSTATE 0.5f // (K/s) Temperature change rate for steady state logic to be enforced. + + #define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center at first layer height. + #define MPC_TUNING_END_Z 10.0f // (mm) M306 Autotuning final Z position. +#endif //=========================================================================== //====================== PID > Bed Temperature Control ====================== @@ -515,6 +732,7 @@ * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W * heater. If your configuration is significantly different than this and you don't understand * the issues involved, don't use bed PID until someone else verifies that your hardware works. + * @section bed temp */ //#define PIDTEMPBED @@ -530,32 +748,73 @@ #if ENABLED(PIDTEMPBED) //#define MIN_BED_POWER 0 - //#define PID_BED_DEBUG // Sends debug data to the serial port. + //#define PID_BED_DEBUG // Print Bed PID debug data to the serial port. - //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) - //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + // 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + // from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) #define DEFAULT_bedKp 10.00 #define DEFAULT_bedKi .023 #define DEFAULT_bedKd 305.4 - //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) - //from pidautotune - //#define DEFAULT_bedKp 97.1 - //#define DEFAULT_bedKi 1.41 - //#define DEFAULT_bedKd 1675.16 - // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. #endif // PIDTEMPBED -#if EITHER(PIDTEMP, PIDTEMPBED) - //#define PID_DEBUG // Sends debug data to the serial port. Use 'M303 D' to toggle activation. +//=========================================================================== +//==================== PID > Chamber Temperature Control ==================== +//=========================================================================== + +/** + * PID Chamber Heating + * + * If this option is enabled set PID constants below. + * If this option is disabled, bang-bang will be used and CHAMBER_LIMIT_SWITCHING will enable + * hysteresis. + * + * The PID frequency will be the same as the extruder PWM. + * If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz, + * which is fine for driving a square wave into a resistive load and does not significantly + * impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 200W + * heater. If your configuration is significantly different than this and you don't understand + * the issues involved, don't use chamber PID until someone else verifies that your hardware works. + * @section chamber temp + */ +//#define PIDTEMPCHAMBER +//#define CHAMBER_LIMIT_SWITCHING + +/** + * Max Chamber Power + * Applies to all forms of chamber control (PID, bang-bang, and bang-bang with hysteresis). + * When set to any value below 255, enables a form of PWM to the chamber heater that acts like a divider + * so don't use it unless you are OK with PWM on your heater. (See the comment on enabling PIDTEMPCHAMBER) + */ +#define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber heater; 255=full current + +#if ENABLED(PIDTEMPCHAMBER) + #define MIN_CHAMBER_POWER 0 + //#define PID_CHAMBER_DEBUG // Print Chamber PID debug data to the serial port. + + // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element + // and placed inside the small Creality printer enclosure tent. + // + #define DEFAULT_chamberKp 37.04 + #define DEFAULT_chamberKi 1.40 + #define DEFAULT_chamberKd 655.17 + // M309 P37.04 I1.04 D655.17 + + // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles. +#endif // PIDTEMPCHAMBER + +#if ANY(PIDTEMP, PIDTEMPBED, PIDTEMPCHAMBER) //#define PID_OPENLOOP // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay #define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. + + //#define PID_EDIT_MENU // Add PID editing to the "Advanced Settings" menu. (~700 bytes of flash) + //#define PID_AUTOTUNE_MENU // Add PID auto-tuning to the "Advanced Settings" menu. (~250 bytes of flash) #endif -// @section extruder +// @section safety /** * Prevent extrusion if the temperature is below EXTRUDE_MINTEMP. @@ -594,6 +853,7 @@ #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders #define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed #define THERMAL_PROTECTION_CHAMBER // Enable thermal protection for the heated chamber +#define THERMAL_PROTECTION_COOLER // Enable thermal protection for the laser cooling //=========================================================================== //============================= Mechanical Settings ========================= @@ -610,12 +870,166 @@ //#define COREZX //#define COREZY //#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 +//#define MARKFORGED_YX + +// Enable for a belt style printer with endless "Z" motion +//#define BELTPRINTER + +// Enable for Polargraph Kinematics +//#define POLARGRAPH +#if ENABLED(POLARGRAPH) + #define POLARGRAPH_MAX_BELT_LEN 1035.0 + #define POLAR_SEGMENTS_PER_SECOND 5 +#endif + +// @section delta + +// Enable for DELTA kinematics and configure below +//#define DELTA +#if ENABLED(DELTA) + + // Make delta curves from many straight lines (linear interpolation). + // This is a trade-off between visible corners (not enough segments) + // and processor overload (too many expensive sqrt calls). + #define DELTA_SEGMENTS_PER_SECOND 200 + + // After homing move down to a height where XY movement is unconstrained + //#define DELTA_HOME_TO_SAFE_ZONE + + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #if EITHER(DELTA_AUTO_CALIBRATION, DELTA_CALIBRATION_MENU) + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.05 // (mm) + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 140.0 // (mm) + + // Maximum reachable area + #define DELTA_MAX_RADIUS 140.0 // (mm) + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 250.0 // (mm) + + // Distance between bed and nozzle Z home position + #define DELTA_HEIGHT 250.00 // (mm) Get this value from G33 auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + + // Horizontal distance bridged by diagonal push rods when effector is centered. + #define DELTA_RADIUS 124.0 // (mm) Get this value from G33 auto calibrate + + // Trim adjustments for individual towers + // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 + // measured in degrees anticlockwise looking from above the printer + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // Get these values from G33 auto calibrate + + // Delta radius and diagonal rod adjustments (mm) + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } +#endif + +// @section scara + +/** + * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013. + * Implemented and slightly reworked by JCERNY in June, 2014. + * + * Mostly Printed SCARA is an open source design by Tyler Williams. See: + * https://www.thingiverse.com/thing:2487048 + * https://www.thingiverse.com/thing:1241491 + */ +//#define MORGAN_SCARA +//#define MP_SCARA +#if EITHER(MORGAN_SCARA, MP_SCARA) + // If movement is choppy try lowering this value + #define SCARA_SEGMENTS_PER_SECOND 200 + + // Length of inner and outer support arms. Measure arm lengths precisely. + #define SCARA_LINKAGE_1 150 // (mm) + #define SCARA_LINKAGE_2 150 // (mm) + + // SCARA tower offset (position of Tower relative to bed zero position) + // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. + #define SCARA_OFFSET_X 100 // (mm) + #define SCARA_OFFSET_Y -56 // (mm) + + #if ENABLED(MORGAN_SCARA) + + //#define DEBUG_SCARA_KINEMATICS + #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + + // Radius around the center where the arm cannot reach + #define MIDDLE_DEAD_ZONE_R 0 // (mm) + + #define THETA_HOMING_OFFSET 0 // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + #define PSI_HOMING_OFFSET 0 // Calculated from Calibration Guide and M364 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + + #elif ENABLED(MP_SCARA) + + #define SCARA_OFFSET_THETA1 12 // degrees + #define SCARA_OFFSET_THETA2 131 // degrees + + #endif + +#endif + +// @section tpara + +// Enable for TPARA kinematics and configure below +//#define AXEL_TPARA +#if ENABLED(AXEL_TPARA) + #define DEBUG_ROBOT_KINEMATICS + #define ROBOT_SEGMENTS_PER_SECOND 200 + + // Length of inner and outer support arms. Measure arm lengths precisely. + #define ROBOT_LINKAGE_1 120 // (mm) + #define ROBOT_LINKAGE_2 120 // (mm) + + // SCARA tower offset (position of Tower relative to bed zero position) + // This needs to be reasonably accurate as it defines the printbed position in the SCARA space. + #define ROBOT_OFFSET_X 0 // (mm) + #define ROBOT_OFFSET_Y 0 // (mm) + #define ROBOT_OFFSET_Z 0 // (mm) + + #define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly + + // Radius around the center where the arm cannot reach + #define MIDDLE_DEAD_ZONE_R 0 // (mm) + + // Calculated from Calibration Guide and M360 / M114. See http://reprap.harleystudio.co.za/?page_id=1073 + #define THETA_HOMING_OFFSET 0 + #define PSI_HOMING_OFFSET 0 +#endif + +// @section machine + +// Articulated robot (arm). Joints are directly mapped to axes with no kinematics. +//#define ARTICULATED_ROBOT_ARM + +// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire +// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics). +//#define FOAMCUTTER_XYUV //=========================================================================== //============================== Endstop Settings =========================== //=========================================================================== -// @section homing +// @section endstops // Specify here all the endstop connectors that are connected to any endstop or probe. // Almost all printers will be using one per axis. Probes will use one or more of the @@ -623,20 +1037,44 @@ #define USE_XMIN_PLUG #define USE_YMIN_PLUG #define USE_ZMIN_PLUG +//#define USE_IMIN_PLUG +//#define USE_JMIN_PLUG +//#define USE_KMIN_PLUG +//#define USE_UMIN_PLUG +//#define USE_VMIN_PLUG +//#define USE_WMIN_PLUG //#define USE_XMAX_PLUG //#define USE_YMAX_PLUG //#define USE_ZMAX_PLUG +//#define USE_IMAX_PLUG +//#define USE_JMAX_PLUG +//#define USE_KMAX_PLUG +//#define USE_UMAX_PLUG +//#define USE_VMAX_PLUG +//#define USE_WMAX_PLUG // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS #if DISABLED(ENDSTOPPULLUPS) // Disable ENDSTOPPULLUPS to set pullups individually - //#define ENDSTOPPULLUP_XMAX - //#define ENDSTOPPULLUP_YMAX - //#define ENDSTOPPULLUP_ZMAX //#define ENDSTOPPULLUP_XMIN //#define ENDSTOPPULLUP_YMIN //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_IMIN + //#define ENDSTOPPULLUP_JMIN + //#define ENDSTOPPULLUP_KMIN + //#define ENDSTOPPULLUP_UMIN + //#define ENDSTOPPULLUP_VMIN + //#define ENDSTOPPULLUP_WMIN + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_IMAX + //#define ENDSTOPPULLUP_JMAX + //#define ENDSTOPPULLUP_KMAX + //#define ENDSTOPPULLUP_UMAX + //#define ENDSTOPPULLUP_VMAX + //#define ENDSTOPPULLUP_WMAX //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -644,12 +1082,24 @@ //#define ENDSTOPPULLDOWNS #if DISABLED(ENDSTOPPULLDOWNS) // Disable ENDSTOPPULLDOWNS to set pulldowns individually - //#define ENDSTOPPULLDOWN_XMAX - //#define ENDSTOPPULLDOWN_YMAX - //#define ENDSTOPPULLDOWN_ZMAX //#define ENDSTOPPULLDOWN_XMIN //#define ENDSTOPPULLDOWN_YMIN //#define ENDSTOPPULLDOWN_ZMIN + //#define ENDSTOPPULLDOWN_IMIN + //#define ENDSTOPPULLDOWN_JMIN + //#define ENDSTOPPULLDOWN_KMIN + //#define ENDSTOPPULLDOWN_UMIN + //#define ENDSTOPPULLDOWN_VMIN + //#define ENDSTOPPULLDOWN_WMIN + //#define ENDSTOPPULLDOWN_XMAX + //#define ENDSTOPPULLDOWN_YMAX + //#define ENDSTOPPULLDOWN_ZMAX + //#define ENDSTOPPULLDOWN_IMAX + //#define ENDSTOPPULLDOWN_JMAX + //#define ENDSTOPPULLDOWN_KMAX + //#define ENDSTOPPULLDOWN_UMAX + //#define ENDSTOPPULLDOWN_VMAX + //#define ENDSTOPPULLDOWN_WMAX //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif @@ -657,44 +1107,23 @@ #define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define U_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define V_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define W_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define U_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define V_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define W_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe. -/** - * Stepper Drivers - * - * These settings allow Marlin to tune stepper driver timing and enable advanced options for - * stepper drivers that support them. You may also override timing options in Configuration_adv.h. - * - * A4988 is assumed for unspecified drivers. - * - * Options: A4988, A5984, DRV8825, LV8729, L6470, L6474, POWERSTEP01, - * TB6560, TB6600, TMC2100, - * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, - * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, - * TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE, - * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE - * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'L6470', 'L6474', 'POWERSTEP01', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] - */ -#define X_DRIVER_TYPE TMC2130 -#define Y_DRIVER_TYPE TMC2130 -#define Z_DRIVER_TYPE TMC2130 -//#define X2_DRIVER_TYPE A4988 -//#define Y2_DRIVER_TYPE A4988 -//#define Z2_DRIVER_TYPE A4988 -//#define Z3_DRIVER_TYPE A4988 -//#define Z4_DRIVER_TYPE A4988 -#define E0_DRIVER_TYPE TMC2130 -//#define E1_DRIVER_TYPE A4988 -//#define E2_DRIVER_TYPE A4988 -//#define E3_DRIVER_TYPE A4988 -//#define E4_DRIVER_TYPE A4988 -//#define E5_DRIVER_TYPE A4988 -//#define E6_DRIVER_TYPE A4988 -//#define E7_DRIVER_TYPE A4988 - // Enable this feature if all enabled endstop pins are interrupt-capable. // This will remove the need to poll the interrupt pins, saving many CPU cycles. //#define ENDSTOP_INTERRUPTS_FEATURE @@ -737,16 +1166,16 @@ //#define DISTINCT_E_FACTORS /** - * Default Axis Steps Per Unit (steps/mm) + * Default Axis Steps Per Unit (linear=steps/mm, rotational=steps/°) * Override with M92 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] */ -#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 } +#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 } /** - * Default Max Feed Rate (mm/s) + * Default Max Feed Rate (linear=mm/s, rotational=°/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -756,10 +1185,10 @@ #endif /** - * Default Max Acceleration (change/s) change = mm/s + * Default Max Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2)) * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } @@ -769,7 +1198,7 @@ #endif /** - * Default Acceleration (change/s) change = mm/s + * Default Acceleration (speed change with time) (linear=mm/(s^2), rotational=°/(s^2)) * Override with M204 * * M204 P Acceleration @@ -782,7 +1211,7 @@ /** * Default Jerk limits (mm/s) - * Override with M205 X Y Z E + * Override with M205 X Y Z . . . E * * "Jerk" specifies the minimum speed change that requires acceleration. * When changing speed and direction, if the difference is less than the @@ -793,6 +1222,12 @@ #define DEFAULT_XJERK 10.0 #define DEFAULT_YJERK 10.0 #define DEFAULT_ZJERK 0.3 + //#define DEFAULT_IJERK 0.3 + //#define DEFAULT_JJERK 0.3 + //#define DEFAULT_KJERK 0.3 + //#define DEFAULT_UJERK 0.3 + //#define DEFAULT_VJERK 0.3 + //#define DEFAULT_WJERK 0.3 //#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves @@ -860,7 +1295,6 @@ * - For simple switches connect... * - normally-closed switches to GND and D32. * - normally-open switches to 5V and D32. - * */ //#define Z_MIN_PROBE_PIN 32 // Pin 32 is the RAMPS default @@ -877,7 +1311,6 @@ * or (with LCD_BED_LEVELING) the LCD controller. */ //#define PROBE_MANUALLY -//#define MANUAL_PROBE_START_Z 0.2 /** * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. @@ -903,9 +1336,15 @@ //#define BLTOUCH /** - * Pressure sensor with a BLTouch-like interface + * MagLev V4 probe by MDD + * + * This probe is deployed and activated by powering a built-in electromagnet. */ -//#define CREALITY_TOUCH +//#define MAGLEV4 +#if ENABLED(MAGLEV4) + //#define MAGLEV_TRIGGER_PIN 11 // Set to the connected digital output + #define MAGLEV_TRIGGER_DELAY 15 // Changing this risks overheating the coil +#endif /** * Touch-MI Probe by hotends.fr @@ -938,8 +1377,29 @@ #define Z_PROBE_RETRACT_X X_MAX_POS #endif +/** + * Magnetically Mounted Probe + * For probes such as Euclid, Klicky, Klackender, etc. + */ +//#define MAG_MOUNTED_PROBE +#if ENABLED(MAG_MOUNTED_PROBE) + #define PROBE_DEPLOY_FEEDRATE (133*60) // (mm/min) Probe deploy speed + #define PROBE_STOW_FEEDRATE (133*60) // (mm/min) Probe stow speed + + #define MAG_MOUNTED_DEPLOY_1 { PROBE_DEPLOY_FEEDRATE, { 245, 114, 30 } } // Move to side Dock & Attach probe + #define MAG_MOUNTED_DEPLOY_2 { PROBE_DEPLOY_FEEDRATE, { 210, 114, 30 } } // Move probe off dock + #define MAG_MOUNTED_DEPLOY_3 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_DEPLOY_4 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_DEPLOY_5 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed + #define MAG_MOUNTED_STOW_1 { PROBE_STOW_FEEDRATE, { 245, 114, 20 } } // Move to dock + #define MAG_MOUNTED_STOW_2 { PROBE_STOW_FEEDRATE, { 245, 114, 0 } } // Place probe beside remover + #define MAG_MOUNTED_STOW_3 { PROBE_STOW_FEEDRATE, { 230, 114, 0 } } // Side move to remove probe + #define MAG_MOUNTED_STOW_4 { PROBE_STOW_FEEDRATE, { 210, 114, 20 } } // Side move to remove probe + #define MAG_MOUNTED_STOW_5 { PROBE_STOW_FEEDRATE, { 0, 0, 0 } } // Extra move if needed +#endif + // Duet Smart Effector (for delta printers) - https://bit.ly/2ul5U7J -// When the pin is defined you can use M672 to set/reset the probe sensivity. +// When the pin is defined you can use M672 to set/reset the probe sensitivity. //#define DUET_SMART_EFFECTOR #if ENABLED(DUET_SMART_EFFECTOR) #define SMART_EFFECTOR_MOD_PIN -1 // Connect a GPIO pin to the Smart Effector MOD pin @@ -953,17 +1413,55 @@ */ //#define SENSORLESS_PROBING -// -// For Z_PROBE_ALLEN_KEY see the Delta example configurations. -// +/** + * Allen key retractable z-probe as seen on many Kossel delta printers - https://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe + * Deploys by touching z-axis belt. Retracts by pushing the probe down. + */ +//#define Z_PROBE_ALLEN_KEY +#if ENABLED(Z_PROBE_ALLEN_KEY) + // 2 or 3 sets of coordinates for deploying and retracting the spring loaded touch probe on G29, + // if servo actuated touch probe is not defined. Uncomment as appropriate for your printer/probe. + + #define Z_PROBE_ALLEN_KEY_DEPLOY_1 { 30.0, DELTA_PRINTABLE_RADIUS, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_DEPLOY_2 { 0.0, DELTA_PRINTABLE_RADIUS, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 + + #define Z_PROBE_ALLEN_KEY_DEPLOY_3 { 0.0, (DELTA_PRINTABLE_RADIUS) * 0.75, 100.0 } + #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_1 { -64.0, 56.0, 23.0 } // Move the probe into position + #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_2 { -64.0, 56.0, 3.0 } // Push it down + #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE (XY_PROBE_FEEDRATE)/10 + + #define Z_PROBE_ALLEN_KEY_STOW_3 { -64.0, 56.0, 50.0 } // Move it up to clear + #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE XY_PROBE_FEEDRATE + + #define Z_PROBE_ALLEN_KEY_STOW_4 { 0.0, 0.0, 50.0 } + #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE XY_PROBE_FEEDRATE + +#endif // Z_PROBE_ALLEN_KEY /** * Nozzle-to-Probe offsets { X, Y, Z } * - * - Use a caliper or ruler to measure the distance from the tip of + * X and Y offset + * Use a caliper or ruler to measure the distance from the tip of * the Nozzle to the center-point of the Probe in the X and Y axes. + * + * Z offset * - For the Z offset use your best known value and adjust at runtime. - * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. + * - Common probes trigger below the nozzle and have negative values for Z offset. + * - Probes triggering above the nozzle height are uncommon but do exist. When using + * probes such as this, carefully set Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES + * to avoid collisions during probing. + * + * Tune and Adjust + * - Probe Offsets can be tuned at runtime with 'M851', LCD menus, babystepping, etc. + * - PROBE_OFFSET_WIZARD (configuration_adv.h) can be used for setting the Z offset. * * Assuming the typical work area orientation: * - Probe to RIGHT of the Nozzle has a Positive X offset @@ -997,11 +1495,47 @@ #define XY_PROBE_FEEDRATE (133*60) // Feedrate (mm/min) for the first approach when double-probing (MULTIPLE_PROBING == 2) -#define Z_PROBE_FEEDRATE_FAST HOMING_FEEDRATE_Z +#define Z_PROBE_FEEDRATE_FAST (4*60) // Feedrate (mm/min) for the "accurate" probe of each point #define Z_PROBE_FEEDRATE_SLOW (Z_PROBE_FEEDRATE_FAST / 2) +/** + * Probe Activation Switch + * A switch indicating proper deployment, or an optical + * switch triggered when the carriage is near the bed. + */ +//#define PROBE_ACTIVATION_SWITCH +#if ENABLED(PROBE_ACTIVATION_SWITCH) + #define PROBE_ACTIVATION_SWITCH_STATE LOW // State indicating probe is active + //#define PROBE_ACTIVATION_SWITCH_PIN PC6 // Override default pin +#endif + +/** + * Tare Probe (determine zero-point) prior to each probe. + * Useful for a strain gauge or piezo sensor that needs to factor out + * elements such as cables pulling on the carriage. + */ +//#define PROBE_TARE +#if ENABLED(PROBE_TARE) + #define PROBE_TARE_TIME 200 // (ms) Time to hold tare pin + #define PROBE_TARE_DELAY 200 // (ms) Delay after tare before + #define PROBE_TARE_STATE HIGH // State to write pin for tare + //#define PROBE_TARE_PIN PA5 // Override default pin + #if ENABLED(PROBE_ACTIVATION_SWITCH) + //#define PROBE_TARE_ONLY_WHILE_INACTIVE // Fail to tare/probe if PROBE_ACTIVATION_SWITCH is active + #endif +#endif + +/** + * Probe Enable / Disable + * The probe only provides a triggered signal when enabled. + */ +//#define PROBE_ENABLE_DISABLE +#if ENABLED(PROBE_ENABLE_DISABLE) + //#define PROBE_ENABLE_PIN -1 // Override the default pin here +#endif + /** * Multiple Probing * @@ -1058,23 +1592,44 @@ //#define PROBING_HEATERS_OFF // Turn heaters off when probing #if ENABLED(PROBING_HEATERS_OFF) //#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy) + //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude) #endif //#define PROBING_FANS_OFF // Turn fans off when probing -//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing +//#define PROBING_ESTEPPERS_OFF // Turn all extruder steppers off when probing +//#define PROBING_STEPPERS_OFF // Turn all steppers off (unless needed to hold position) when probing (including extruders) //#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors +// Require minimum nozzle and/or bed temperature for probing +//#define PREHEAT_BEFORE_PROBING +#if ENABLED(PREHEAT_BEFORE_PROBING) + #define PROBING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time + #define PROBING_BED_TEMP 50 +#endif + // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 // :{ 0:'Low', 1:'High' } #define X_ENABLE_ON 0 #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders +//#define I_ENABLE_ON 0 +//#define J_ENABLE_ON 0 +//#define K_ENABLE_ON 0 +//#define U_ENABLE_ON 0 +//#define V_ENABLE_ON 0 +//#define W_ENABLE_ON 0 // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! #define DISABLE_X false #define DISABLE_Y false #define DISABLE_Z false +//#define DISABLE_I false +//#define DISABLE_J false +//#define DISABLE_K false +//#define DISABLE_U false +//#define DISABLE_V false +//#define DISABLE_W false // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING @@ -1084,12 +1639,18 @@ #define DISABLE_E false // Disable the extruder when not stepping #define DISABLE_INACTIVE_EXTRUDER // Keep only the active extruder enabled -// @section machine +// @section motion // Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. #define INVERT_X_DIR false #define INVERT_Y_DIR true #define INVERT_Z_DIR false +//#define INVERT_I_DIR false +//#define INVERT_J_DIR false +//#define INVERT_K_DIR false +//#define INVERT_U_DIR false +//#define INVERT_V_DIR false +//#define INVERT_W_DIR false // @section extruder @@ -1105,9 +1666,15 @@ // @section homing -//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed +//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed. Also enable HOME_AFTER_DEACTIVATE for extra safety. +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated. Also enable NO_MOTION_BEFORE_HOMING for extra safety. -//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off. +/** + * Set Z_IDLE_HEIGHT if the Z-Axis moves on its own when steppers are disabled. + * - Use a low value (i.e., Z_MIN_POS) if the nozzle falls down to the bed. + * - Use a large value (i.e., Z_MAX_POS) if the bed falls down, away from the nozzle. + */ +//#define Z_IDLE_HEIGHT Z_HOME_POS //#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... // Be sure to have this much clearance over your Z_MAX_POS to prevent grinding. @@ -1119,20 +1686,38 @@ #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 +//#define I_HOME_DIR -1 +//#define J_HOME_DIR -1 +//#define K_HOME_DIR -1 +//#define U_HOME_DIR -1 +//#define V_HOME_DIR -1 +//#define W_HOME_DIR -1 -// @section machine +// @section geometry -// The size of the print bed +// The size of the printable area #define X_BED_SIZE 200 #define Y_BED_SIZE 200 -// Travel limits (mm) after homing, corresponding to endstop positions. +// Travel limits (linear=mm, rotational=°) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 #define X_MAX_POS X_BED_SIZE #define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 +//#define I_MIN_POS 0 +//#define I_MAX_POS 50 +//#define J_MIN_POS 0 +//#define J_MAX_POS 50 +//#define K_MIN_POS 0 +//#define K_MAX_POS 50 +//#define U_MIN_POS 0 +//#define U_MAX_POS 50 +//#define V_MIN_POS 0 +//#define V_MAX_POS 50 +//#define W_MIN_POS 0 +//#define W_MAX_POS 50 /** * Software Endstops @@ -1149,6 +1734,12 @@ #define MIN_SOFTWARE_ENDSTOP_X #define MIN_SOFTWARE_ENDSTOP_Y #define MIN_SOFTWARE_ENDSTOP_Z + #define MIN_SOFTWARE_ENDSTOP_I + #define MIN_SOFTWARE_ENDSTOP_J + #define MIN_SOFTWARE_ENDSTOP_K + #define MIN_SOFTWARE_ENDSTOP_U + #define MIN_SOFTWARE_ENDSTOP_V + #define MIN_SOFTWARE_ENDSTOP_W #endif // Max software endstops constrain movement within maximum coordinate bounds @@ -1157,6 +1748,12 @@ #define MAX_SOFTWARE_ENDSTOP_X #define MAX_SOFTWARE_ENDSTOP_Y #define MAX_SOFTWARE_ENDSTOP_Z + #define MAX_SOFTWARE_ENDSTOP_I + #define MAX_SOFTWARE_ENDSTOP_J + #define MAX_SOFTWARE_ENDSTOP_K + #define MAX_SOFTWARE_ENDSTOP_U + #define MAX_SOFTWARE_ENDSTOP_V + #define MAX_SOFTWARE_ENDSTOP_W #endif #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) @@ -1167,6 +1764,12 @@ * Filament Runout Sensors * Mechanical or opto endstops are used to check for the presence of filament. * + * IMPORTANT: Runout will only trigger if Marlin is aware that a print job is running. + * Marlin knows a print job is running when: + * 1. Running a print job from media started with M24. + * 2. The Print Job Timer has been started with M75. + * 3. The heaters were turned on and PRINTJOB_TIMER_AUTOSTART is enabled. + * * RAMPS-based boards use SERVO3_PIN for the first runout sensor. * For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc. */ @@ -1174,12 +1777,49 @@ #if ENABLED(FILAMENT_RUNOUT_SENSOR) #define FIL_RUNOUT_ENABLED_DEFAULT true // Enable the sensor on startup. Override with M412 followed by M500. #define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each. + #define FIL_RUNOUT_STATE LOW // Pin state indicating that filament is NOT present. #define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins. //#define FIL_RUNOUT_PULLDOWN // Use internal pulldown for filament runout pins. + //#define WATCH_ALL_RUNOUT_SENSORS // Execute runout script on any triggering sensor, not only for the active extruder. + // This is automatically enabled for MIXING_EXTRUDERs. + + // Override individually if the runout sensors vary + //#define FIL_RUNOUT1_STATE LOW + //#define FIL_RUNOUT1_PULLUP + //#define FIL_RUNOUT1_PULLDOWN - // Set one or more commands to execute on filament runout. - // (After 'M412 H' Marlin will ask the host to handle the process.) + //#define FIL_RUNOUT2_STATE LOW + //#define FIL_RUNOUT2_PULLUP + //#define FIL_RUNOUT2_PULLDOWN + + //#define FIL_RUNOUT3_STATE LOW + //#define FIL_RUNOUT3_PULLUP + //#define FIL_RUNOUT3_PULLDOWN + + //#define FIL_RUNOUT4_STATE LOW + //#define FIL_RUNOUT4_PULLUP + //#define FIL_RUNOUT4_PULLDOWN + + //#define FIL_RUNOUT5_STATE LOW + //#define FIL_RUNOUT5_PULLUP + //#define FIL_RUNOUT5_PULLDOWN + + //#define FIL_RUNOUT6_STATE LOW + //#define FIL_RUNOUT6_PULLUP + //#define FIL_RUNOUT6_PULLDOWN + + //#define FIL_RUNOUT7_STATE LOW + //#define FIL_RUNOUT7_PULLUP + //#define FIL_RUNOUT7_PULLDOWN + + //#define FIL_RUNOUT8_STATE LOW + //#define FIL_RUNOUT8_PULLUP + //#define FIL_RUNOUT8_PULLDOWN + + // Commands to execute on filament runout. + // With multiple runout sensors use the %c placeholder for the current tool in commands (e.g., "M600 T%c") + // NOTE: After 'M412 H1' the host handles filament runout and this script does not apply. #define FILAMENT_RUNOUT_SCRIPT "M600" // After a runout is detected, continue printing this length of filament @@ -1240,10 +1880,30 @@ //#define MESH_BED_LEVELING /** - * Normally G28 leaves leveling disabled on completion. Enable - * this option to have G28 restore the prior leveling state. + * Normally G28 leaves leveling disabled on completion. Enable one of + * these options to restore the prior leveling state or to always enable + * leveling immediately after G28. */ //#define RESTORE_LEVELING_AFTER_G28 +//#define ENABLE_LEVELING_AFTER_G28 + +/** + * Auto-leveling needs preheating + */ +//#define PREHEAT_BEFORE_LEVELING +#if ENABLED(PREHEAT_BEFORE_LEVELING) + #define LEVELING_NOZZLE_TEMP 120 // (°C) Only applies to E0 at this time + #define LEVELING_BED_TEMP 50 +#endif + +/** + * Bed Distance Sensor + * + * Measures the distance from bed to nozzle with accuracy of 0.01mm. + * For information about this sensor https://github.com/markniu/Bed_Distance_sensor + * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. + */ +//#define BD_SENSOR /** * Enable detailed logging of G28, G29, M48, etc. @@ -1252,11 +1912,19 @@ */ //#define DEBUG_LEVELING_FEATURE +#if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL, PROBE_MANUALLY) + // Set a height for the start of manual adjustment + #define MANUAL_PROBE_START_Z 0.2 // (mm) Comment out to use the last-measured height +#endif + #if ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, AUTO_BED_LEVELING_UBL) // Gradually reduce leveling correction until a set height is reached, // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z #define ENABLE_LEVELING_FADE_HEIGHT + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + #define DEFAULT_LEVELING_FADE_HEIGHT 10.0 // (mm) Default fade height. + #endif // For Cartesian machines, instead of dividing moves on mesh boundaries, // split up moves into short segments like a Delta. This follows the @@ -1270,10 +1938,11 @@ //#define G26_MESH_VALIDATION #if ENABLED(G26_MESH_VALIDATION) #define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle. - #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool. - #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool. - #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for the G26 Mesh Validation Tool. - #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for XY Moves for the G26 Mesh Validation Tool. + #define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for G26. + #define MESH_TEST_HOTEND_TEMP 205 // (°C) Default nozzle temperature for G26. + #define MESH_TEST_BED_TEMP 60 // (°C) Default bed temperature for G26. + #define G26_XY_FEEDRATE 20 // (mm/s) Feedrate for G26 XY moves. + #define G26_XY_FEEDRATE_TRAVEL 100 // (mm/s) Feedrate for G26 XY travel moves. #define G26_RETRACT_MULTIPLIER 1.0 // G26 Q (retraction) used by default between mesh test elements. #endif @@ -1318,12 +1987,16 @@ #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + //#define UBL_HILBERT_CURVE // Use Hilbert distribution for less travel when probing multiple points + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500 //#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used // as the Z-Height correction value. + //#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== @@ -1351,13 +2024,38 @@ #endif // Add a menu item to move between bed corners for manual bed adjustment -//#define LEVEL_BED_CORNERS +//#define LCD_BED_TRAMMING + +#if ENABLED(LCD_BED_TRAMMING) + #define BED_TRAMMING_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets + #define BED_TRAMMING_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points + #define BED_TRAMMING_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points + //#define BED_TRAMMING_INCLUDE_CENTER // Move to the center after the last corner + //#define BED_TRAMMING_USE_PROBE + #if ENABLED(BED_TRAMMING_USE_PROBE) + #define BED_TRAMMING_PROBE_TOLERANCE 0.1 // (mm) + #define BED_TRAMMING_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify + //#define BED_TRAMMING_AUDIO_FEEDBACK + #endif -#if ENABLED(LEVEL_BED_CORNERS) - #define LEVEL_CORNERS_INSET_LFRB { 30, 30, 30, 30 } // (mm) Left, Front, Right, Back insets - #define LEVEL_CORNERS_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points - #define LEVEL_CORNERS_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points - //#define LEVEL_CENTER_TOO // Move to the center after the last corner + /** + * Corner Leveling Order + * + * Set 2 or 4 points. When 2 points are given, the 3rd is the center of the opposite edge. + * + * LF Left-Front RF Right-Front + * LB Left-Back RB Right-Back + * + * Examples: + * + * Default {LF,RB,LB,RF} {LF,RF} {LB,LF} + * LB --------- RB LB --------- RB LB --------- RB LB --------- RB + * | 4 3 | | 3 2 | | <3> | | 1 | + * | | | | | | | <3>| + * | 1 2 | | 1 4 | | 1 2 | | 2 | + * LF --------- RF LF --------- RF LF --------- RF LF --------- RF + */ + #define BED_TRAMMING_LEVELING_ORDER { LF, RF, RB, LB } #endif /** @@ -1376,16 +2074,20 @@ //#define MANUAL_X_HOME_POS 0 //#define MANUAL_Y_HOME_POS 0 //#define MANUAL_Z_HOME_POS 0 +//#define MANUAL_I_HOME_POS 0 +//#define MANUAL_J_HOME_POS 0 +//#define MANUAL_K_HOME_POS 0 +//#define MANUAL_U_HOME_POS 0 +//#define MANUAL_V_HOME_POS 0 +//#define MANUAL_W_HOME_POS 0 -// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. -// -// With this feature enabled: -// -// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. -// - If stepper drivers time out, it will need X and Y homing again before Z homing. -// - Move the Z probe (or nozzle) to a defined XY point before Z Homing. -// - Prevent Z homing when the Z probe is outside bed area. -// +/** + * Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. + * + * - Moves the Z probe (or nozzle) to a defined XY point before Z homing. + * - Allows Z homing only when XY positions are known and trusted. + * - If stepper drivers sleep, XY homing may be required again before Z homing. + */ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) @@ -1393,7 +2095,7 @@ #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing #endif -// Homing speeds (mm/min) +// Homing speeds (linear=mm/min, rotational=°/min) #define HOMING_FEEDRATE_MM_M { (50*60), (50*60), (4*60) } // Validate that endstops are triggered on homing moves @@ -1437,9 +2139,8 @@ #define XY_DIAG_BD 282.8427124746 #define XY_SIDE_AD 200 - // Or, set the default skew factors directly here - // to override the above measurements: - #define XY_SKEW_FACTOR 0.0 + // Or, set the XY skew factor directly: + //#define XY_SKEW_FACTOR 0.0 //#define SKEW_CORRECTION_FOR_Z #if ENABLED(SKEW_CORRECTION_FOR_Z) @@ -1448,8 +2149,10 @@ #define YZ_DIAG_AC 282.8427124746 #define YZ_DIAG_BD 282.8427124746 #define YZ_SIDE_AD 200 - #define XZ_SKEW_FACTOR 0.0 - #define YZ_SKEW_FACTOR 0.0 + + // Or, set the Z skew factors directly: + //#define XZ_SKEW_FACTOR 0.0 + //#define YZ_SKEW_FACTOR 0.0 #endif // Enable this option for M852 to set skew at runtime @@ -1460,7 +2163,7 @@ //============================= Additional Features =========================== //============================================================================= -// @section extras +// @section eeprom /** * EEPROM @@ -1472,13 +2175,16 @@ * M502 - Revert settings to "factory" defaults. (Follow with M500 to init the EEPROM.) */ //#define EEPROM_SETTINGS // Persistent storage with M500 and M501 -//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! +//#define DISABLE_M503 // Saves ~2700 bytes of flash. Disable for release! #define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. #define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load #if ENABLED(EEPROM_SETTINGS) //#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors. + //#define EEPROM_INIT_NOW // Init EEPROM on first boot after a new build. #endif +// @section host + // // Host Keepalive // @@ -1489,6 +2195,8 @@ #define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113. #define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating +// @section units + // // G20/G21 Inch mode support // @@ -1501,17 +2209,23 @@ // @section temperature -// Preheat Constants +// +// Preheat Constants - Up to 10 are supported without changes +// #define PREHEAT_1_LABEL "PLA" #define PREHEAT_1_TEMP_HOTEND 180 #define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_TEMP_CHAMBER 35 #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 #define PREHEAT_2_LABEL "ABS" #define PREHEAT_2_TEMP_HOTEND 240 #define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_TEMP_CHAMBER 35 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 +// @section motion + /** * Nozzle Park * @@ -1528,8 +2242,7 @@ #if ENABLED(NOZZLE_PARK_FEATURE) // Specify a park position as { X, Y, Z_raise } #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } - //#define NOZZLE_PARK_X_ONLY // X move only is required to park - //#define NOZZLE_PARK_Y_ONLY // Y move only is required to park + #define NOZZLE_PARK_MOVE 0 // Park motion: 0 = XY Move, 1 = X Only, 2 = Y Only, 3 = X before Y, 4 = Y before X #define NOZZLE_PARK_Z_RAISE_MIN 2 // (mm) Always raise Z by at least this distance #define NOZZLE_PARK_XY_FEEDRATE 100 // (mm/s) X and Y axes feedrate (also used for delta Z axis) #define NOZZLE_PARK_Z_FEEDRATE 5 // (mm/s) Z axis feedrate (not used for delta printers) @@ -1571,7 +2284,6 @@ * * Caveats: The ending Z should be the same as starting Z. * Attention: EXPERIMENTAL. G-code arguments may change. - * */ //#define NOZZLE_CLEAN_FEATURE @@ -1603,19 +2315,34 @@ // For a purge/clean station mounted on the X axis //#define NOZZLE_CLEAN_NO_Y + // Require a minimum hotend temperature for cleaning + #define NOZZLE_CLEAN_MIN_TEMP 170 + //#define NOZZLE_CLEAN_HEATUP // Heat up the nozzle instead of skipping wipe + // Explicit wipe G-code script applies to a G12 with no arguments. //#define WIPE_SEQUENCE_COMMANDS "G1 X-17 Y25 Z10 F4000\nG1 Z1\nM114\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 X-17 Y25\nG1 X-17 Y95\nG1 Z15\nM400\nG0 X-10.0 Y-9.0" #endif +// @section host + /** * Print Job Timer * - * Automatically start and stop the print job timer on M104/M109/M190. + * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191. + * The print job timer will only be stopped if the bed/chamber target temp is + * below BED_MINTEMP/CHAMBER_MINTEMP. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M140 (bed, no wait) - high temp = none, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * M141 (chamber, no wait) - high temp = none, low temp = stop timer + * M191 (chamber, wait) - high temp = start timer, low temp = none * - * M104 (hotend, no wait) - high temp = none, low temp = stop timer - * M109 (hotend, wait) - high temp = start timer, low temp = stop timer - * M190 (bed, wait) - high temp = start timer, low temp = none + * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2. + * For M140/M190, high temp is anything over BED_MINTEMP. + * For M141/M191, high temp is anything over CHAMBER_MINTEMP. * * The timer can also be controlled with the following commands: * @@ -1625,6 +2352,8 @@ */ #define PRINTJOB_TIMER_AUTOSTART +// @section stats + /** * Print Counter * @@ -1638,6 +2367,11 @@ * View the current statistics with M78. */ //#define PRINTCOUNTER +#if ENABLED(PRINTCOUNTER) + #define PRINTCOUNTER_SAVE_INTERVAL 60 // (minutes) EEPROM save interval during print. A value of 0 will save stats at end of print. +#endif + +// @section security /** * Password @@ -1674,17 +2408,17 @@ //============================= LCD and SD support ============================ //============================================================================= -// @section lcd +// @section interface /** * LCD LANGUAGE * * Select the language to display on the LCD. These languages are available: * - * en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it, - * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, tr, uk, vi, zh_CN, zh_TW, test + * en, an, bg, ca, cz, da, de, el, el_CY, es, eu, fi, fr, gl, hr, hu, it, + * jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)', 'test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek (Greece)', 'el_CY':'Greek (Cyprus)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' } */ #define LCD_LANGUAGE en @@ -1713,9 +2447,9 @@ #define DISPLAY_CHARSET_HD44780 JAPANESE /** - * Info Screen Style (0:Classic, 1:Pruša) + * Info Screen Style (0:Classic, 1:Průša) * - * :[0:'Classic', 1:'Pruša'] + * :[0:'Classic', 1:'Průša'] */ #define LCD_INFO_SCREEN_STYLE 0 @@ -1724,20 +2458,9 @@ * * SD Card support is disabled by default. If your controller has an SD slot, * you must uncomment the following option or it won't work. - * */ //#define SDSUPPORT -/** - * SD CARD: SPI SPEED - * - * Enable one of the following items for a slower SPI transfer speed. - * This may be required to resolve "volume init" errors. - */ -//#define SPI_SPEED SPI_HALF_SPEED -//#define SPI_SPEED SPI_QUARTER_SPEED -//#define SPI_SPEED SPI_EIGHTH_SPEED - /** * SD CARD: ENABLE CRC * @@ -1801,12 +2524,23 @@ // //#define REVERSE_SELECT_DIRECTION +// +// Encoder EMI Noise Filter +// +// This option increases encoder samples to filter out phantom encoder clicks caused by EMI noise. +// +//#define ENCODER_NOISE_FILTER +#if ENABLED(ENCODER_NOISE_FILTER) + #define ENCODER_SAMPLES 10 +#endif + // // Individual Axis Homing // // Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. // //#define INDIVIDUAL_AXIS_HOMING_MENU +//#define INDIVIDUAL_AXIS_HOMING_SUBMENU // // SPEAKER/BUZZER @@ -1830,6 +2564,7 @@ //======================== LCD / Controller Selection ========================= //======================== (Character-based LCDs) ========================= //============================================================================= +// @section lcd // // RepRapDiscount Smart Controller. @@ -1839,6 +2574,14 @@ // //#define REPRAP_DISCOUNT_SMART_CONTROLLER +// +// GT2560 (YHCB2004) LCD Display +// +// Requires Testato, Koepel softwarewire library and +// Andriy Golovnya's LiquidCrystal_AIP31068 library. +// +//#define YHCB2004 + // // Original RADDS LCD Display+Encoder+SDCardReader // http://doku.radds.org/dokumentation/lcd-display/ @@ -1961,6 +2704,14 @@ // //#define FF_INTERFACEBOARD +// +// TFT GLCD Panel with Marlin UI +// Panel connected to main board by SPI or I2C interface. +// See https://github.com/Serhiy-K/TFTGLCDAdapter +// +//#define TFTGLCD_PANEL_SPI +//#define TFTGLCD_PANEL_I2C + //============================================================================= //======================= LCD / Controller Selection ======================= //========================= (Graphical LCDs) ======================== @@ -1981,6 +2732,11 @@ // //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +// +// K.3D Full Graphic Smart Controller +// +//#define K3D_FULL_GRAPHIC_SMART_CONTROLLER + // // ReprapWorld Graphical LCD // https://reprapworld.com/?products_details&products_id/1218 @@ -1995,6 +2751,11 @@ //#define VIKI2 //#define miniVIKI +// +// Alfawise Ex8 printer LCD marked as WYH L12864 COG +// +//#define WYH_L12864 + // // MakerLab Mini Panel with graphic // controller and SD support - https://reprap.org/wiki/Mini_panel @@ -2042,11 +2803,17 @@ // //#define MKS_MINI_12864 +// +// MKS MINI12864 V3 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// +//#define MKS_MINI_12864_V3 + // // MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout. // https://www.aliexpress.com/item/33018110072.html // -//#define MKS_LCD12864 +//#define MKS_LCD12864A +//#define MKS_LCD12864B // // FYSETC variant of the MINI12864 graphic controller with SD support @@ -2058,6 +2825,11 @@ //#define FYSETC_MINI_12864_2_1 // Type A/B. NeoPixel RGB Backlight //#define FYSETC_GENERIC_12864_1_1 // Larger display with basic ON/OFF backlight. +// +// BigTreeTech Mini 12864 V1.0 is an alias for FYSETC_MINI_12864_2_1. Type A/B. NeoPixel RGB Backlight. +// +//#define BTT_MINI_12864_V1 + // // Factory display for Creality CR-10 // https://www.aliexpress.com/item/32833148327.html @@ -2077,9 +2849,10 @@ // // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 // A clone of the RepRapDiscount full graphics display but with -// different pins/wiring (see pins_ANET_10.h). +// different pins/wiring (see pins_ANET_10.h). Enable one of these. // //#define ANET_FULL_GRAPHICS_LCD +//#define ANET_FULL_GRAPHICS_LCD_ALT_WIRING // // AZSMZ 12864 LCD with SD @@ -2093,6 +2866,12 @@ // //#define SILVER_GATE_GLCD_CONTROLLER +// +// eMotion Tech LCD with SD +// https://www.reprap-france.com/produit/1234568748-ecran-graphique-128-x-64-points-2-1 +// +//#define EMOTION_TECH_LCD + //============================================================================= //============================== OLED Displays ============================== //============================================================================= @@ -2117,7 +2896,7 @@ //#define OLED_PANEL_TINYBOY2 // -// MKS OLED 1.3" 128×64 FULL GRAPHICS CONTROLLER +// MKS OLED 1.3" 128×64 Full Graphics Controller // https://reprap.org/wiki/MKS_12864OLED // // Tiny, but very sharp OLED display @@ -2126,7 +2905,7 @@ //#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller // -// Zonestar OLED 128×64 FULL GRAPHICS CONTROLLER +// Zonestar OLED 128×64 Full Graphics Controller // //#define ZONESTAR_12864LCD // Graphical (DOGM) with ST7920 controller //#define ZONESTAR_12864OLED // 1.3" OLED with SH1106 controller (default) @@ -2143,22 +2922,59 @@ //#define OVERLORD_OLED // -// FYSETC OLED 2.42" 128×64 FULL GRAPHICS CONTROLLER with WS2812 RGB +// FYSETC OLED 2.42" 128×64 Full Graphics Controller with WS2812 RGB // Where to find : https://www.aliexpress.com/item/4000345255731.html //#define FYSETC_242_OLED_12864 // Uses the SSD1309 controller +// +// K.3D SSD1309 OLED 2.42" 128×64 Full Graphics Controller +// +//#define K3D_242_OLED_CONTROLLER // Software SPI + //============================================================================= //========================== Extensible UI Displays =========================== //============================================================================= -// -// DGUS Touch Display with DWIN OS. (Choose one.) -// ORIGIN : https://www.aliexpress.com/item/32993409517.html -// FYSETC : https://www.aliexpress.com/item/32961471929.html -// +/** + * DGUS Touch Display with DWIN OS. (Choose one.) + * ORIGIN : https://www.aliexpress.com/item/32993409517.html + * FYSETC : https://www.aliexpress.com/item/32961471929.html + * MKS : https://www.aliexpress.com/item/1005002008179262.html + * + * Flash display with DGUS Displays for Marlin: + * - Format the SD card to FAT32 with an allocation size of 4kb. + * - Download files as specified for your type of display. + * - Plug the microSD card into the back of the display. + * - Boot the display and wait for the update to complete. + * + * ORIGIN (Marlin DWIN_SET) + * - Download https://github.com/coldtobi/Marlin_DGUS_Resources + * - Copy the downloaded DWIN_SET folder to the SD card. + * + * FYSETC (Supplier default) + * - Download https://github.com/FYSETC/FYSTLCD-2.0 + * - Copy the downloaded SCREEN folder to the SD card. + * + * HIPRECY (Supplier default) + * - Download https://github.com/HiPrecy/Touch-Lcd-LEO + * - Copy the downloaded DWIN_SET folder to the SD card. + * + * MKS (MKS-H43) (Supplier default) + * - Download https://github.com/makerbase-mks/MKS-H43 + * - Copy the downloaded DWIN_SET folder to the SD card. + * + * RELOADED (T5UID1) + * - Download https://github.com/Desuuuu/DGUS-reloaded/releases + * - Copy the downloaded DWIN_SET folder to the SD card. + */ //#define DGUS_LCD_UI_ORIGIN //#define DGUS_LCD_UI_FYSETC //#define DGUS_LCD_UI_HIPRECY +//#define DGUS_LCD_UI_MKS +//#define DGUS_LCD_UI_RELOADED +#if ENABLED(DGUS_LCD_UI_MKS) + #define USE_MKS_GREEN_UI +#endif // // Touch-screen LCD for Malyan M200/M300 printers @@ -2177,13 +2993,18 @@ //#define ANYCUBIC_LCD_I3MEGA //#define ANYCUBIC_LCD_CHIRON #if EITHER(ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON) - #define ANYCUBIC_LCD_SERIAL_PORT 3 //#define ANYCUBIC_LCD_DEBUG + //#define ANYCUBIC_LCD_GCODE_EXT // Add ".gcode" to menu entries for DGUS clone compatibility #endif +// +// 320x240 Nextion 2.8" serial TFT Resistive Touch Screen NX3224T028 +// +//#define NEXTION_TFT + // // Third-party or vendor-customized controller interfaces. -// Sources should be installed in 'src/lcd/extensible_ui'. +// Sources should be installed in 'src/lcd/extui'. // //#define EXTENSIBLE_UI @@ -2195,43 +3016,133 @@ //=============================== Graphical TFTs ============================== //============================================================================= +/** + * Specific TFT Model Presets. Enable one of the following options + * or enable TFT_GENERIC and set sub-options. + */ + +// +// 480x320, 3.5", SPI Display with Rotary Encoder from MKS +// Usually paired with MKS Robin Nano V2 & V3 +// +//#define MKS_TS35_V2_0 + +// +// 320x240, 2.4", FSMC Display From MKS +// Usually paired with MKS Robin Nano V1.2 +// +//#define MKS_ROBIN_TFT24 + +// +// 320x240, 2.8", FSMC Display From MKS +// Usually paired with MKS Robin Nano V1.2 +// +//#define MKS_ROBIN_TFT28 + +// +// 320x240, 3.2", FSMC Display From MKS +// Usually paired with MKS Robin Nano V1.2 +// +//#define MKS_ROBIN_TFT32 + +// +// 480x320, 3.5", FSMC Display From MKS +// Usually paired with MKS Robin Nano V1.2 +// +//#define MKS_ROBIN_TFT35 + +// +// 480x272, 4.3", FSMC Display From MKS +// +//#define MKS_ROBIN_TFT43 + +// +// 320x240, 3.2", FSMC Display From MKS +// Usually paired with MKS Robin +// +//#define MKS_ROBIN_TFT_V1_1R + // -// TFT display with optional touch screen -// Color Marlin UI with standard menu system +// 480x320, 3.5", FSMC Stock Display from Tronxy // -//#define TFT_320x240 -//#define TFT_320x240_SPI -//#define TFT_480x320 -//#define TFT_480x320_SPI +//#define TFT_TRONXY_X5SA // -// Skip autodetect and force specific TFT driver -// Mandatory for SPI screens with no MISO line -// Available drivers are: ST7735, ST7789, ST7796, R61505, ILI9328, ILI9341, ILI9488 +// 480x320, 3.5", FSMC Stock Display from AnyCubic // -//#define TFT_DRIVER AUTO +//#define ANYCUBIC_TFT35 // -// SPI display (MKS Robin Nano V2.0, MKS Gen L V2.0) -// Upscaled 128x64 Marlin UI +// 320x240, 2.8", FSMC Stock Display from Longer/Alfawise // -//#define SPI_GRAPHICAL_TFT +//#define LONGER_LK_TFT28 // -// FSMC display (MKS Robin, Alfawise U20, JGAurora A5S, REXYZ A1, etc.) -// Upscaled 128x64 Marlin UI +// 320x240, 2.8", FSMC Stock Display from ET4 // -//#define FSMC_GRAPHICAL_TFT +//#define ANET_ET4_TFT28 // -// TFT LVGL UI +// 480x320, 3.5", FSMC Stock Display from ET5 +// +//#define ANET_ET5_TFT35 + +// +// 1024x600, 7", RGB Stock Display with Rotary Encoder from BIQU-BX +// +//#define BIQU_BX_TFT70 + +// +// 480x320, 3.5", SPI Stock Display with Rotary Encoder from BIQU B1 SE Series +// +//#define BTT_TFT35_SPI_V1_0 + // -// Using default MKS icons and fonts from: https://git.io/JJvzK -// Just copy the 'assets' folder from the build directory to the -// root of your SD card, together with the compiled firmware. +// Generic TFT with detailed options // -//#define TFT_LVGL_UI_FSMC // Robin nano v1.2 uses FSMC -//#define TFT_LVGL_UI_SPI // Robin nano v2.0 uses SPI +//#define TFT_GENERIC +#if ENABLED(TFT_GENERIC) + // :[ 'AUTO', 'ST7735', 'ST7789', 'ST7796', 'R61505', 'ILI9328', 'ILI9341', 'ILI9488' ] + #define TFT_DRIVER AUTO + + // Interface. Enable one of the following options: + //#define TFT_INTERFACE_FSMC + //#define TFT_INTERFACE_SPI + + // TFT Resolution. Enable one of the following options: + //#define TFT_RES_320x240 + //#define TFT_RES_480x272 + //#define TFT_RES_480x320 + //#define TFT_RES_1024x600 +#endif + +/** + * TFT UI - User Interface Selection. Enable one of the following options: + * + * TFT_CLASSIC_UI - Emulated DOGM - 128x64 Upscaled + * TFT_COLOR_UI - Marlin Default Menus, Touch Friendly, using full TFT capabilities + * TFT_LVGL_UI - A Modern UI using LVGL + * + * For LVGL_UI also copy the 'assets' folder from the build directory to the + * root of your SD card, together with the compiled firmware. + */ +//#define TFT_CLASSIC_UI +//#define TFT_COLOR_UI +//#define TFT_LVGL_UI + +#if ENABLED(TFT_LVGL_UI) + //#define MKS_WIFI_MODULE // MKS WiFi module +#endif + +/** + * TFT Rotation. Set to one of the following values: + * + * TFT_ROTATE_90, TFT_ROTATE_90_MIRROR_X, TFT_ROTATE_90_MIRROR_Y, + * TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y, + * TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y, + * TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION + */ +//#define TFT_ROTATION TFT_NO_ROTATION //============================================================================= //============================ Other Controllers ============================ @@ -2240,22 +3151,38 @@ // // Ender-3 v2 OEM display. A DWIN display with Rotary Encoder. // -//#define DWIN_CREALITY_LCD +//#define DWIN_CREALITY_LCD // Creality UI +//#define DWIN_LCD_PROUI // Pro UI by MRiscoC +//#define DWIN_CREALITY_LCD_JYERSUI // Jyers UI by Jacob Myers +//#define DWIN_MARLINUI_PORTRAIT // MarlinUI (portrait orientation) +//#define DWIN_MARLINUI_LANDSCAPE // MarlinUI (landscape orientation) // -// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 +// Touch Screen Settings // //#define TOUCH_SCREEN #if ENABLED(TOUCH_SCREEN) - #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens - #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus + #define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens + #define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus + + //#define DISABLE_ENCODER // Disable the click encoder, if any + //#define TOUCH_IDLE_SLEEP_MINS 5 // (minutes) Display Sleep after a period of inactivity. Set with M255 S. #define TOUCH_SCREEN_CALIBRATION - //#define XPT2046_X_CALIBRATION 12316 - //#define XPT2046_Y_CALIBRATION -8981 - //#define XPT2046_X_OFFSET -43 - //#define XPT2046_Y_OFFSET 257 + //#define TOUCH_CALIBRATION_X 12316 + //#define TOUCH_CALIBRATION_Y -8981 + //#define TOUCH_OFFSET_X -43 + //#define TOUCH_OFFSET_Y 257 + //#define TOUCH_ORIENTATION TOUCH_LANDSCAPE + + #if BOTH(TOUCH_SCREEN_CALIBRATION, EEPROM_SETTINGS) + #define TOUCH_CALIBRATION_AUTO_SAVE // Auto save successful calibration values to EEPROM + #endif + + #if ENABLED(TFT_COLOR_UI) + //#define SINGLE_TOUCH_NAVIGATION + #endif #endif // @@ -2265,19 +3192,21 @@ //#define REPRAPWORLD_KEYPAD //#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // (mm) Distance to move per key-press +// +// EasyThreeD ET-4000+ with button input and status LED +// +//#define EASYTHREED_UI + //============================================================================= //=============================== Extra Features ============================== //============================================================================= -// @section extras +// @section fans // Set number of user-controlled fans. Disable to use all board-defined fans. // :[1,2,3,4,5,6,7,8] //#define NUM_M106_FANS 1 -// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino -//#define FAST_PWM_FAN - // Use software PWM to drive the fan, as for the heaters. This uses a very low frequency // which is not as annoying as with the hardware PWM. On the other hand, if this frequency // is too low, you should also increment SOFT_PWM_SCALE. @@ -2296,17 +3225,18 @@ // duty cycle is attained. //#define SOFT_PWM_DITHER +// @section extras + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// @section lights + // Temperature status LEDs that display the hotend and bed temperature. // If all hotends, bed temperature, and target temperature are under 54C // then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) //#define TEMP_STAT_LEDS -// SkeinForge sends the wrong arc G-codes when using Arc Point as fillet procedure -//#define SF_ARC_FIX - -// Support for the BariCUDA Paste Extruder -//#define BARICUDA - // Support for BlinkM/CyzRgb //#define BLINKM @@ -2327,17 +3257,19 @@ * luminance values can be set from 0 to 255. * For NeoPixel LED an overall brightness parameter is also available. * - * *** CAUTION *** + * === CAUTION === * LED Strips require a MOSFET Chip between PWM lines and LEDs, * as the Arduino cannot handle the current the LEDs will require. * Failure to follow this precaution can destroy your Arduino! + * * NOTE: A separate 5V power supply is required! The NeoPixel LED needs * more current than the Arduino 5V linear regulator can produce. - * *** CAUTION *** - * - * LED Type. Enable only one of the following two options. * + * Requires PWM frequency between 50 <> 100Hz (Check HAL or variant) + * Use FAST_PWM_FAN, if possible, to reduce fan noise. */ + +// LED Type. Enable only one of the following two options: //#define RGB_LED //#define RGBW_LED @@ -2346,33 +3278,40 @@ //#define RGB_LED_G_PIN 43 //#define RGB_LED_B_PIN 35 //#define RGB_LED_W_PIN -1 + //#define RGB_STARTUP_TEST // For PWM pins, fade between all colors + #if ENABLED(RGB_STARTUP_TEST) + #define RGB_STARTUP_TEST_INNER_MS 10 // (ms) Reduce or increase fading speed + #endif #endif // Support for Adafruit NeoPixel LED driver //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) - #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) - #define NEOPIXEL_PIN 4 // LED driving pin - //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE - //#define NEOPIXEL2_PIN 5 - #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) - #define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once. - #define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255) - //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup + #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW, NEO_RGBW, NEO_GRB, NEO_RBG, etc. + // See https://github.com/adafruit/Adafruit_NeoPixel/blob/master/Adafruit_NeoPixel.h + //#define NEOPIXEL_PIN 4 // LED driving pin + //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE + //#define NEOPIXEL2_PIN 5 + #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) + #define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once. + #define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255) + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup // Support for second Adafruit NeoPixel LED driver controlled with M150 S1 ... //#define NEOPIXEL2_SEPARATE #if ENABLED(NEOPIXEL2_SEPARATE) - #define NEOPIXEL2_PIXELS 15 // Number of LEDs in the second strip - #define NEOPIXEL2_BRIGHTNESS 127 // Initial brightness (0-255) - #define NEOPIXEL2_STARTUP_TEST // Cycle through colors at startup + #define NEOPIXEL2_PIXELS 15 // Number of LEDs in the second strip + #define NEOPIXEL2_BRIGHTNESS 127 // Initial brightness (0-255) + #define NEOPIXEL2_STARTUP_TEST // Cycle through colors at startup #else - //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel + //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif - // Use a single NeoPixel LED for static (background) lighting - //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + // Use some of the NeoPixel LEDs for static (background) lighting + //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED + //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off #endif /** @@ -2390,21 +3329,18 @@ #define PRINTER_EVENT_LEDS #endif -/** - * R/C SERVO support - * Sponsored by TrinityLabs, Reworked by codexmas - */ +// @section servos /** * Number of servos * * For some servo-related options NUM_SERVOS will be set automatically. * Set this manually if there are extra servos needing manual control. - * Leave undefined or set to 0 to entirely disable the servo subsystem. + * Set to 0 to turn off servo support. */ -//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command +//#define NUM_SERVOS 3 // Note: Servo index starts with 0 for M280-M282 commands -// (ms) Delay before the next move will start, to give the servo time to reach its target angle. +// (ms) Delay before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. #define SERVO_DELAY { 300 } @@ -2412,5 +3348,8 @@ // Only power servos during movement, otherwise leave off to prevent jitter //#define DEACTIVATE_SERVOS_AFTER_MOVE -// Allow servo angle to be edited and saved to EEPROM -//#define EDITABLE_SERVO_ANGLES \ No newline at end of file +// Edit servo angles with M281 and save to EEPROM with M500 +//#define EDITABLE_SERVO_ANGLES + +// Disable servo with M282 to reduce power consumption, noise, and heat when not in use +//#define SERVO_DETACH_GCODE diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 06dca33a8579..9a54b10b82b1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -29,15 +29,31 @@ * Some of these settings can damage your printer if improperly set! * * Basic settings can be found in Configuration.h - * */ #define CONFIGURATION_ADV_H_VERSION 02010200 -// @section temperature +// @section develop + +/** + * Configuration Export + * + * Export the configuration as part of the build. (See signature.py) + * Output files are saved with the build (e.g., .pio/build/mega2560). + * + * See `build_all_examples --ini` as an example of config.ini archiving. + * + * 1 = marlin_config.json - Dictionary containing the configuration. + * This file is also generated for CONFIGURATION_EMBEDDING. + * 2 = config.ini - File format for PlatformIO preprocessing. + * 3 = schema.json - The entire configuration schema. (13 = pattern groups) + * 4 = schema.yml - The entire configuration schema. + */ +//#define CONFIG_EXPORT 2 // :[1:'JSON', 2:'config.ini', 3:'schema.json', 4:'schema.yml'] //=========================================================================== //============================= Thermal Settings ============================ //=========================================================================== +// @section temperature /** * Thermocouple sensors are quite sensitive to noise. Any noise induced in @@ -56,69 +72,126 @@ // Custom Thermistor 1000 parameters // #if TEMP_SENSOR_0 == 1000 - #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND0_BETA 3950 // Beta value + #define HOTEND0_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND0_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND0_BETA 3950 // Beta value + #define HOTEND0_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_1 == 1000 - #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND1_BETA 3950 // Beta value + #define HOTEND1_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND1_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND1_BETA 3950 // Beta value + #define HOTEND1_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_2 == 1000 - #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND2_BETA 3950 // Beta value + #define HOTEND2_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND2_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND2_BETA 3950 // Beta value + #define HOTEND2_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_3 == 1000 - #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND3_BETA 3950 // Beta value + #define HOTEND3_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND3_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND3_BETA 3950 // Beta value + #define HOTEND3_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_4 == 1000 - #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND4_BETA 3950 // Beta value + #define HOTEND4_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND4_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND4_BETA 3950 // Beta value + #define HOTEND4_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_5 == 1000 - #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND5_BETA 3950 // Beta value + #define HOTEND5_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND5_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND5_BETA 3950 // Beta value + #define HOTEND5_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_6 == 1000 - #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND6_BETA 3950 // Beta value + #define HOTEND6_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND6_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND6_BETA 3950 // Beta value + #define HOTEND6_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_7 == 1000 - #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define HOTEND7_BETA 3950 // Beta value + #define HOTEND7_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define HOTEND7_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define HOTEND7_BETA 3950 // Beta value + #define HOTEND7_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_BED == 1000 - #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define BED_BETA 3950 // Beta value + #define BED_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BED_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BED_BETA 3950 // Beta value + #define BED_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif #if TEMP_SENSOR_CHAMBER == 1000 - #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor - #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C - #define CHAMBER_BETA 3950 // Beta value + #define CHAMBER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define CHAMBER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define CHAMBER_BETA 3950 // Beta value + #define CHAMBER_SH_C_COEFF 0 // Steinhart-Hart C coefficient #endif -// -// Hephestos 2 24V heated bed upgrade kit. -// https://store.bq.com/en/heated-bed-kit-hephestos2 -// +#if TEMP_SENSOR_COOLER == 1000 + #define COOLER_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define COOLER_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define COOLER_BETA 3950 // Beta value + #define COOLER_SH_C_COEFF 0 // Steinhart-Hart C coefficient +#endif + +#if TEMP_SENSOR_PROBE == 1000 + #define PROBE_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define PROBE_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define PROBE_BETA 3950 // Beta value + #define PROBE_SH_C_COEFF 0 // Steinhart-Hart C coefficient +#endif + +#if TEMP_SENSOR_BOARD == 1000 + #define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define BOARD_BETA 3950 // Beta value + #define BOARD_SH_C_COEFF 0 // Steinhart-Hart C coefficient +#endif + +#if TEMP_SENSOR_REDUNDANT == 1000 + #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define REDUNDANT_BETA 3950 // Beta value + #define REDUNDANT_SH_C_COEFF 0 // Steinhart-Hart C coefficient +#endif + +/** + * Thermocouple Options — for MAX6675 (-2), MAX31855 (-3), and MAX31865 (-5). + */ +//#define TEMP_SENSOR_FORCE_HW_SPI // Ignore SCK/MOSI/MISO pins; use CS and the default SPI bus. +//#define MAX31865_SENSOR_WIRES_0 2 // (2-4) Number of wires for the probe connected to a MAX31865 board. +//#define MAX31865_SENSOR_WIRES_1 2 +//#define MAX31865_SENSOR_WIRES_2 2 + +//#define MAX31865_50HZ_FILTER // Use a 50Hz filter instead of the default 60Hz. +//#define MAX31865_USE_READ_ERROR_DETECTION // Treat value spikes (20°C delta in under 1s) as read errors. + +//#define MAX31865_USE_AUTO_MODE // Read faster and more often than 1-shot; bias voltage always on; slight effect on RTD temperature. +//#define MAX31865_MIN_SAMPLING_TIME_MSEC 100 // (ms) 1-shot: minimum read interval. Reduces bias voltage effects by leaving sensor unpowered for longer intervals. +//#define MAX31865_IGNORE_INITIAL_FAULTY_READS 10 // Ignore some read faults (keeping the temperature reading) to work around a possible issue (#23439). + +//#define MAX31865_WIRE_OHMS_0 0.95f // For 2-wire, set the wire resistances for more accurate readings. +//#define MAX31865_WIRE_OHMS_1 0.0f +//#define MAX31865_WIRE_OHMS_2 0.0f + +/** + * Hephestos 2 24V heated bed upgrade kit. + * https://store.bq.com/en/heated-bed-kit-hephestos2 + */ //#define HEPHESTOS2_HEATED_BED_KIT #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef TEMP_SENSOR_BED @@ -126,22 +199,87 @@ #define HEATER_BED_INVERTING true #endif -/** - * Heated Chamber settings - */ +// +// Heated Bed Bang-Bang options +// +#if DISABLED(PIDTEMPBED) + #define BED_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control + #if ENABLED(BED_LIMIT_SWITCHING) + #define BED_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > BED_HYSTERESIS + #endif +#endif + +// +// Heated Chamber options +// +#if DISABLED(PIDTEMPCHAMBER) + #define CHAMBER_CHECK_INTERVAL 5000 // (ms) Interval between checks in bang-bang control + #if ENABLED(CHAMBER_LIMIT_SWITCHING) + #define CHAMBER_HYSTERESIS 2 // (°C) Only set the relevant heater state when ABS(T-target) > CHAMBER_HYSTERESIS + #endif +#endif + #if TEMP_SENSOR_CHAMBER - #define CHAMBER_MINTEMP 5 - #define CHAMBER_MAXTEMP 60 - #define TEMP_CHAMBER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target - //#define CHAMBER_LIMIT_SWITCHING - //#define HEATER_CHAMBER_PIN 44 // Chamber heater on/off pin + //#define HEATER_CHAMBER_PIN P2_04 // Required heater on/off pin (example: SKR 1.4 Turbo HE1 plug) //#define HEATER_CHAMBER_INVERTING false + //#define FAN1_PIN -1 // Remove the fan signal on pin P2_04 (example: SKR 1.4 Turbo HE1 plug) + + //#define CHAMBER_FAN // Enable a fan on the chamber + #if ENABLED(CHAMBER_FAN) + //#define CHAMBER_FAN_INDEX 2 // Index of a fan to repurpose as the chamber fan. (Default: first unused fan) + #define CHAMBER_FAN_MODE 2 // Fan control mode: 0=Static; 1=Linear increase when temp is higher than target; 2=V-shaped curve; 3=similar to 1 but fan is always on. + #if CHAMBER_FAN_MODE == 0 + #define CHAMBER_FAN_BASE 255 // Chamber fan PWM (0-255) + #elif CHAMBER_FAN_MODE == 1 + #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255); turns on when chamber temperature is above the target + #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target + #elif CHAMBER_FAN_MODE == 2 + #define CHAMBER_FAN_BASE 128 // Minimum chamber fan PWM (0-255) + #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C difference from target + #elif CHAMBER_FAN_MODE == 3 + #define CHAMBER_FAN_BASE 128 // Base chamber fan PWM (0-255) + #define CHAMBER_FAN_FACTOR 25 // PWM increase per °C above target + #endif + #endif + + //#define CHAMBER_VENT // Enable a servo-controlled vent on the chamber + #if ENABLED(CHAMBER_VENT) + #define CHAMBER_VENT_SERVO_NR 1 // Index of the vent servo + #define HIGH_EXCESS_HEAT_LIMIT 5 // How much above target temp to consider there is excess heat in the chamber + #define LOW_EXCESS_HEAT_LIMIT 3 + #define MIN_COOLING_SLOPE_TIME_CHAMBER_VENT 20 + #define MIN_COOLING_SLOPE_DEG_CHAMBER_VENT 1.5 + #endif #endif -#if DISABLED(PIDTEMPBED) - #define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control - #if ENABLED(BED_LIMIT_SWITCHING) - #define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS +// +// Laser Cooler options +// +#if TEMP_SENSOR_COOLER + #define COOLER_MINTEMP 8 // (°C) + #define COOLER_MAXTEMP 26 // (°C) + #define COOLER_DEFAULT_TEMP 16 // (°C) + #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target + #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay) + #define COOLER_INVERTING false + #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required. + #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc. + #define COOLER_FAN_INDEX 0 // FAN number 0, 1, 2 etc. e.g. + #if ENABLED(COOLER_FAN) + #define COOLER_FAN_BASE 100 // Base Cooler fan PWM (0-255); turns on when Cooler temperature is above the target + #define COOLER_FAN_FACTOR 25 // PWM increase per °C above target + #endif +#endif + +// +// Motherboard Sensor options +// +#if TEMP_SENSOR_BOARD + #define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below. + #define BOARD_MINTEMP 8 // (°C) + #define BOARD_MAXTEMP 70 // (°C) + #ifndef TEMP_BOARD_PIN + //#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file. #endif #endif @@ -182,7 +320,7 @@ * and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set * below 2. */ - #define WATCH_TEMP_PERIOD 20 // Seconds + #define WATCH_TEMP_PERIOD 40 // Seconds #define WATCH_TEMP_INCREASE 2 // Degrees Celsius #endif @@ -214,6 +352,28 @@ #define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius #endif +/** + * Thermal Protection parameters for the laser cooler. + */ +#if ENABLED(THERMAL_PROTECTION_COOLER) + #define THERMAL_PROTECTION_COOLER_PERIOD 10 // Seconds + #define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degrees Celsius + + /** + * Laser cooling watch settings (M143/M193). + */ + #define WATCH_COOLER_TEMP_PERIOD 60 // Seconds + #define WATCH_COOLER_TEMP_INCREASE 3 // Degrees Celsius +#endif + +#if ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_COOLER) + /** + * Thermal Protection Variance Monitor - EXPERIMENTAL. + * Kill the machine on a stuck temperature sensor. Disable if you get false positives. + */ + //#define THERMAL_PROTECTION_VARIANCE_MONITOR // Detect a sensor malfunction preventing temperature updates +#endif + #if ENABLED(PIDTEMP) // Add an experimental additional term to the heater power, proportional to the extrusion speed. // A well-chosen Kc value should add just enough power to melt the increased material volume. @@ -260,8 +420,8 @@ // DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf - #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf - #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING + #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf + #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING #define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0 @@ -289,7 +449,7 @@ */ #define AUTOTEMP #if ENABLED(AUTOTEMP) - #define AUTOTEMP_OLDWEIGHT 0.98 + #define AUTOTEMP_OLDWEIGHT 0.98 // Factor used to weight previous readings (0.0 < value < 1.0) // Turn on AUTOTEMP on M104/M109 by default using proportions set here //#define AUTOTEMP_PROPORTIONAL #if ENABLED(AUTOTEMP_PROPORTIONAL) @@ -307,7 +467,7 @@ * High Temperature Thermistor Support * * Thermistors able to support high temperature tend to have a hard time getting - * good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP + * good readings at room and lower temperatures. This means TEMP_SENSOR_X_RAW_LO_TEMP * will probably be caught when the heating element first turns on during the * preheating process, which will trigger a min_temp_error as a safety measure * and force stop everything. @@ -323,18 +483,22 @@ // before a min_temp_error is triggered. (Shouldn't be more than 10.) //#define MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED 0 -// The number of milliseconds a hotend will preheat before starting to check -// the temperature. This value should NOT be set to the time it takes the -// hot end to reach the target temperature, but the time it takes to reach -// the minimum temperature your thermistor can read. The lower the better/safer. -// This shouldn't need to be more than 30 seconds (30000) +/** + * The number of milliseconds a hotend will preheat before starting to check + * the temperature. This value should NOT be set to the time it takes the + * hot end to reach the target temperature, but the time it takes to reach + * the minimum temperature your thermistor can read. The lower the better/safer. + * This shouldn't need to be more than 30 seconds (30000) + */ //#define MILLISECONDS_PREHEAT_TIME 0 // @section extruder -// Extruder runout prevention. -// If the machine is idle and the temperature over MINTEMP -// then extrude some filament every couple of SECONDS. +/** + * Extruder runout prevention. + * If the machine is idle and the temperature over MINTEMP + * then extrude some filament every couple of SECONDS. + */ //#define EXTRUDER_RUNOUT_PREVENT #if ENABLED(EXTRUDER_RUNOUT_PREVENT) #define EXTRUDER_RUNOUT_MINTEMP 190 @@ -373,23 +537,31 @@ */ //#define USE_CONTROLLER_FAN #if ENABLED(USE_CONTROLLER_FAN) - //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan - //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered - //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. - #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) - #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled - #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled - #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors - //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings + //#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan + //#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered + //#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled. + #define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.) + #define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled + #define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled + #define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors + + // Use TEMP_SENSOR_BOARD as a trigger for enabling the controller fan + //#define CONTROLLER_FAN_MIN_BOARD_TEMP 40 // (°C) Turn on the fan if the board reaches this temperature + + //#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings #if ENABLED(CONTROLLER_FAN_EDITABLE) - #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu + #define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu #endif #endif -// When first starting the main fan, run it at full speed for the -// given number of milliseconds. This gets the fan spinning reliably -// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu) -//#define FAN_KICKSTART_TIME 100 +/** + * Fan Kickstart + * When part cooling or controller fans first start, run at a speed that + * gets it spinning reliably for a short time before setting the requested speed. + * (Does not work on Sanguinololu with FAN_SOFT_PWM.) + */ +//#define FAN_KICKSTART_TIME 100 // (ms) +//#define FAN_KICKSTART_POWER 180 // 64-255 // Some coolers may require a non-zero "off" state. //#define FAN_OFF_PWM 1 @@ -410,32 +582,48 @@ //#define FAN_MAX_PWM 128 /** - * FAST PWM FAN Settings + * Fan Fast PWM * - * Use to change the FAST FAN PWM frequency (if enabled in Configuration.h) - * Combinations of PWM Modes, prescale values and TOP resolutions are used internally to produce a - * frequency as close as possible to the desired frequency. + * Combinations of PWM Modes, prescale values and TOP resolutions are used internally + * to produce a frequency as close as possible to the desired frequency. * - * FAST_PWM_FAN_FREQUENCY [undefined by default] + * FAST_PWM_FAN_FREQUENCY * Set this to your desired frequency. - * If left undefined this defaults to F = F_CPU/(2*255*1) - * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. - * These defaults are the same as with the old FAST_PWM_FAN implementation - no migration is required + * For AVR, if left undefined this defaults to F = F_CPU/(2*255*1) + * i.e., F = 31.4kHz on 16MHz microcontrollers or F = 39.2kHz on 20MHz microcontrollers. + * For non AVR, if left undefined this defaults to F = 1Khz. + * This F value is only to protect the hardware from an absence of configuration + * and not to complete it when users are not aware that the frequency must be specifically set to support the target board. + * * NOTE: Setting very low frequencies (< 10 Hz) may result in unexpected timer behavior. + * Setting very high frequencies can damage your hardware. * * USE_OCR2A_AS_TOP [undefined by default] * Boards that use TIMER2 for PWM have limitations resulting in only a few possible frequencies on TIMER2: - * 16MHz MCUs: [62.5KHz, 31.4KHz (default), 7.8KHz, 3.92KHz, 1.95KHz, 977Hz, 488Hz, 244Hz, 60Hz, 122Hz, 30Hz] - * 20MHz MCUs: [78.1KHz, 39.2KHz (default), 9.77KHz, 4.9KHz, 2.44KHz, 1.22KHz, 610Hz, 305Hz, 153Hz, 76Hz, 38Hz] + * 16MHz MCUs: [62.5kHz, 31.4kHz (default), 7.8kHz, 3.92kHz, 1.95kHz, 977Hz, 488Hz, 244Hz, 60Hz, 122Hz, 30Hz] + * 20MHz MCUs: [78.1kHz, 39.2kHz (default), 9.77kHz, 4.9kHz, 2.44kHz, 1.22kHz, 610Hz, 305Hz, 153Hz, 76Hz, 38Hz] * A greater range can be achieved by enabling USE_OCR2A_AS_TOP. But note that this option blocks the use of * PWM on pin OC2A. Only use this option if you don't need PWM on 0C2A. (Check your schematic.) * USE_OCR2A_AS_TOP sacrifices duty cycle control resolution to achieve this broader range of frequencies. */ +//#define FAST_PWM_FAN // Increase the fan PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino #if ENABLED(FAST_PWM_FAN) - //#define FAST_PWM_FAN_FREQUENCY 31400 + //#define FAST_PWM_FAN_FREQUENCY 31400 // Define here to override the defaults below //#define USE_OCR2A_AS_TOP + #ifndef FAST_PWM_FAN_FREQUENCY + #ifdef __AVR__ + #define FAST_PWM_FAN_FREQUENCY ((F_CPU) / (2 * 255 * 1)) + #else + #define FAST_PWM_FAN_FREQUENCY 1000U + #endif + #endif #endif +/** + * Use one of the PWM fans as a redundant part-cooling fan + */ +//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. + // @section extruder /** @@ -459,11 +647,48 @@ #define E6_AUTO_FAN_PIN -1 #define E7_AUTO_FAN_PIN -1 #define CHAMBER_AUTO_FAN_PIN -1 +#define COOLER_AUTO_FAN_PIN -1 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // 255 == full speed #define CHAMBER_AUTO_FAN_TEMPERATURE 30 #define CHAMBER_AUTO_FAN_SPEED 255 +#define COOLER_AUTO_FAN_TEMPERATURE 18 +#define COOLER_AUTO_FAN_SPEED 255 + +/** + * Hotend Cooling Fans tachometers + * + * Define one or more tachometer pins to enable fan speed + * monitoring, and reporting of fan speeds with M123. + * + * NOTE: Only works with fans up to 7000 RPM. + */ +//#define FOURWIRES_FANS // Needed with AUTO_FAN when 4-wire PWM fans are installed +//#define E0_FAN_TACHO_PIN -1 +//#define E0_FAN_TACHO_PULLUP +//#define E0_FAN_TACHO_PULLDOWN +//#define E1_FAN_TACHO_PIN -1 +//#define E1_FAN_TACHO_PULLUP +//#define E1_FAN_TACHO_PULLDOWN +//#define E2_FAN_TACHO_PIN -1 +//#define E2_FAN_TACHO_PULLUP +//#define E2_FAN_TACHO_PULLDOWN +//#define E3_FAN_TACHO_PIN -1 +//#define E3_FAN_TACHO_PULLUP +//#define E3_FAN_TACHO_PULLDOWN +//#define E4_FAN_TACHO_PIN -1 +//#define E4_FAN_TACHO_PULLUP +//#define E4_FAN_TACHO_PULLDOWN +//#define E5_FAN_TACHO_PIN -1 +//#define E5_FAN_TACHO_PULLUP +//#define E5_FAN_TACHO_PULLDOWN +//#define E6_FAN_TACHO_PIN -1 +//#define E6_FAN_TACHO_PULLUP +//#define E6_FAN_TACHO_PULLDOWN +//#define E7_FAN_TACHO_PIN -1 +//#define E7_FAN_TACHO_PULLUP +//#define E7_FAN_TACHO_PULLDOWN /** * Part-Cooling Fan Multiplexer @@ -485,12 +710,17 @@ #define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW #define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin) - //#define CASE_LIGHT_MAX_PWM 128 // Limit pwm - //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu //#define CASE_LIGHT_NO_BRIGHTNESS // Disable brightness control. Enable for non-PWM lighting. - //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light, requires NEOPIXEL_LED. - #if ENABLED(CASE_LIGHT_USE_NEOPIXEL) - #define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } + //#define CASE_LIGHT_MAX_PWM 128 // Limit PWM duty cycle (0-255) + //#define CASE_LIGHT_MENU // Add Case Light options to the LCD menu + #if ENABLED(NEOPIXEL_LED) + //#define CASE_LIGHT_USE_NEOPIXEL // Use NeoPixel LED as case light + #endif + #if EITHER(RGB_LED, RGBW_LED) + //#define CASE_LIGHT_USE_RGB_LED // Use RGB / RGBW LED as case light + #endif + #if EITHER(CASE_LIGHT_USE_NEOPIXEL, CASE_LIGHT_USE_RGB_LED) + #define CASE_LIGHT_DEFAULT_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White } #endif #endif @@ -511,58 +741,6 @@ //#define CLOSED_LOOP_MOVE_COMPLETE_PIN -1 #endif -/** - * Dual Steppers / Dual Endstops - * - * This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes. - * - * For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to - * spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop - * set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug - * that should be used for the second endstop. Extra endstops will appear in the output of 'M119'. - * - * Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors - * this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error - * in X2. Dual endstop offsets can be set at runtime with 'M666 X Y Z'. - */ - -//#define X_DUAL_STEPPER_DRIVERS -#if ENABLED(X_DUAL_STEPPER_DRIVERS) - #define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions - //#define X_DUAL_ENDSTOPS - #if ENABLED(X_DUAL_ENDSTOPS) - #define X2_USE_ENDSTOP _XMAX_ - #define X2_ENDSTOP_ADJUSTMENT 0 - #endif -#endif - -//#define Y_DUAL_STEPPER_DRIVERS -#if ENABLED(Y_DUAL_STEPPER_DRIVERS) - #define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions - //#define Y_DUAL_ENDSTOPS - #if ENABLED(Y_DUAL_ENDSTOPS) - #define Y2_USE_ENDSTOP _YMAX_ - #define Y2_ENDSTOP_ADJUSTMENT 0 - #endif -#endif - -// -// For Z set the number of stepper drivers -// -//#define Z_MULTI_ENDSTOPS -#if ENABLED(Z_MULTI_ENDSTOPS) - #define Z2_USE_ENDSTOP _XMAX_ - #define Z2_ENDSTOP_ADJUSTMENT 0 - #if NUM_Z_STEPPER_DRIVERS >= 3 - #define Z3_USE_ENDSTOP _YMAX_ - #define Z3_ENDSTOP_ADJUSTMENT 0 - #endif - #if NUM_Z_STEPPER_DRIVERS >= 4 - #define Z4_USE_ENDSTOP _ZMAX_ - #define Z4_ENDSTOP_ADJUSTMENT 0 - #endif -#endif - /** * Dual X Carriage * @@ -593,22 +771,95 @@ */ //#define DUAL_X_CARRIAGE #if ENABLED(DUAL_X_CARRIAGE) - #define X1_MIN_POS X_MIN_POS // Set to X_MIN_POS - #define X1_MAX_POS X_BED_SIZE // Set a maximum so the first X-carriage can't hit the parked second X-carriage - #define X2_MIN_POS 80 // Set a minimum to ensure the second X-carriage can't hit the parked first X-carriage - #define X2_MAX_POS 353 // Set this to the distance between toolheads when both heads are homed - #define X2_HOME_DIR 1 // Set to 1. The second X-carriage always homes to the maximum endstop position - #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. - // However: In this mode the HOTEND_OFFSET_X value for the second extruder provides a software - // override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops - // without modifying the firmware (through the "M218 T1 X???" command). - // Remember: you should set the second extruder x-offset to 0 in your slicer. - - // This is the default power-up mode which can be later using M605. + #define X1_MIN_POS X_MIN_POS // Set to X_MIN_POS + #define X1_MAX_POS X_BED_SIZE // A max coordinate so the X1 carriage can't hit the parked X2 carriage + #define X2_MIN_POS 80 // A min coordinate so the X2 carriage can't hit the parked X1 carriage + #define X2_MAX_POS 353 // The max position of the X2 carriage, typically also the home position + #define X2_HOME_DIR 1 // Set to 1. The X2 carriage always homes to the max endstop position + #define X2_HOME_POS X2_MAX_POS // Default X2 home position. Set to X2_MAX_POS. + // NOTE: For Dual X Carriage use M218 T1 Xn to override the X2_HOME_POS. + // This allows recalibration of endstops distance without a rebuild. + // Remember to set the second extruder's X-offset to 0 in your slicer. + + // This is the default power-up mode which can be changed later using M605 S. #define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_AUTO_PARK_MODE // Default x offset in duplication mode (typically set to half print bed width) #define DEFAULT_DUPLICATION_X_OFFSET 100 + + // Default action to execute following M605 mode change commands. Typically G28X to apply new mode. + //#define EVENT_GCODE_IDEX_AFTER_MODECHANGE "G28X" +#endif + +/** + * Multi-Stepper / Multi-Endstop + * + * When X2_DRIVER_TYPE is defined, this indicates that the X and X2 motors work in tandem. + * The following explanations for X also apply to Y and Z multi-stepper setups. + * Endstop offsets may be changed by 'M666 X Y Z' and stored to EEPROM. + * + * - Enable INVERT_X2_VS_X_DIR if the X2 motor requires an opposite DIR signal from X. + * + * - Enable X_DUAL_ENDSTOPS if the second motor has its own endstop, with adjustable offset. + * + * - Extra endstops are included in the output of 'M119'. + * + * - Set X_DUAL_ENDSTOP_ADJUSTMENT to the known error in the X2 endstop. + * Applied to the X2 motor on 'G28' / 'G28 X'. + * Get the offset by homing X and measuring the error. + * Also set with 'M666 X' and stored to EEPROM with 'M500'. + * + * - Use X2_USE_ENDSTOP to set the endstop plug by name. (_XMIN_, _XMAX_, _YMIN_, _YMAX_, _ZMIN_, _ZMAX_) + */ +#if HAS_X2_STEPPER && DISABLED(DUAL_X_CARRIAGE) + //#define INVERT_X2_VS_X_DIR // X2 direction signal is the opposite of X + //#define X_DUAL_ENDSTOPS // X2 has its own endstop + #if ENABLED(X_DUAL_ENDSTOPS) + #define X2_USE_ENDSTOP _XMAX_ // X2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define X2_ENDSTOP_ADJUSTMENT 0 // X2 offset relative to X endstop + #endif +#endif + +#if HAS_DUAL_Y_STEPPERS + //#define INVERT_Y2_VS_Y_DIR // Y2 direction signal is the opposite of Y + //#define Y_DUAL_ENDSTOPS // Y2 has its own endstop + #if ENABLED(Y_DUAL_ENDSTOPS) + #define Y2_USE_ENDSTOP _YMAX_ // Y2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Y2_ENDSTOP_ADJUSTMENT 0 // Y2 offset relative to Y endstop + #endif +#endif + +// +// Multi-Z steppers +// +#ifdef Z2_DRIVER_TYPE + //#define INVERT_Z2_VS_Z_DIR // Z2 direction signal is the opposite of Z + + //#define Z_MULTI_ENDSTOPS // Other Z axes have their own endstops + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z2_USE_ENDSTOP _XMAX_ // Z2 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z2_ENDSTOP_ADJUSTMENT 0 // Z2 offset relative to Y endstop + #endif + #ifdef Z3_DRIVER_TYPE + //#define INVERT_Z3_VS_Z_DIR // Z3 direction signal is the opposite of Z + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z3_USE_ENDSTOP _YMAX_ // Z3 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z3_ENDSTOP_ADJUSTMENT 0 // Z3 offset relative to Y endstop + #endif + #endif + #ifdef Z4_DRIVER_TYPE + //#define INVERT_Z4_VS_Z_DIR // Z4 direction signal is the opposite of Z + #if ENABLED(Z_MULTI_ENDSTOPS) + #define Z4_USE_ENDSTOP _ZMAX_ // Z4 endstop board plug. Don't forget to enable USE_*_PLUG. + #define Z4_ENDSTOP_ADJUSTMENT 0 // Z4 offset relative to Y endstop + #endif + #endif +#endif + +// Drive the E axis with two synchronized steppers +//#define E_DUAL_STEPPER_DRIVERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + //#define INVERT_E1_VS_E0_DIR // E direction signals are opposites #endif // Activate a solenoid on the active extruder with M380. Disable all with M381. @@ -623,15 +874,17 @@ * the position of the toolhead relative to the workspace. */ -//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing +//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (linear=mm, rotational=°) Backoff from endstops before sensorless homing -#define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump +#define HOMING_BUMP_MM { 5, 5, 2 } // (linear=mm, rotational=°) Backoff from endstops after first bump #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) -//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (mm) Backoff from endstops after homing +//#define HOMING_BACKOFF_POST_MM { 2, 2, 2 } // (linear=mm, rotational=°) Backoff from endstops after homing +//#define XY_COUNTERPART_BACKOFF_MM 0 // (mm) Backoff X after homing Y, and vice-versa //#define QUICK_HOME // If G28 contains XY do a diagonal move first //#define HOME_Y_BEFORE_X // If G28 contains XY home Y before X +//#define HOME_Z_FIRST // Home Z first. Requires a Z-MIN endstop (not a probe). //#define CODEPENDENT_XY_HOMING // If X/Y can't home without homing Y/X first // @section bltouch @@ -691,12 +944,14 @@ //#define BLTOUCH_FORCE_MODE_SET /** - * Use "HIGH SPEED" mode for probing. + * Enable "HIGH SPEED" option for probing. * Danger: Disable if your probe sometimes fails. Only suitable for stable well-adjusted systems. - * This feature was designed for Delta's with very fast Z moves however higher speed cartesians may function - * If the machine cannot raise the probe fast enough after a trigger, it may enter a fault state. + * This feature was designed for Deltabots with very fast Z moves; however, higher speed Cartesians + * might be able to use it. If the machine can't raise Z fast enough the BLTouch may go into ALARM. + * + * Set the default state here, change with 'M401 S' or UI, use M500 to save, M502 to reset. */ - //#define BLTOUCH_HS_MODE + //#define BLTOUCH_HS_MODE true // Safety: Enable voltage mode settings in the LCD menu. //#define BLTOUCH_LCD_VOLTAGE_MENU @@ -711,9 +966,12 @@ */ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) - // Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] - // If not defined, probe limits will be used. - // Override with 'M422 S X Y' + /** + * Define probe X and Y positions for Z1, Z2 [, Z3 [, Z4]] + * These positions are machine-relative and do not shift with the M206 home offset! + * If not defined, probe limits will be used. + * Override with 'M422 S X Y'. + */ //#define Z_STEPPER_ALIGN_XY { { 10, 190 }, { 100, 10 }, { 190, 190 } } /** @@ -734,21 +992,22 @@ * | 4 3 | 1 4 | 2 1 | 3 2 | * | | | | | * | 1 2 | 2 3 | 3 4 | 4 1 | - * */ #ifndef Z_STEPPER_ALIGN_XY //#define Z_STEPPERS_ORIENTATION 0 #endif - // Provide Z stepper positions for more rapid convergence in bed alignment. - // Requires triple stepper drivers (i.e., set NUM_Z_STEPPER_DRIVERS to 3) - //#define Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS - #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - // Define Stepper XY positions for Z1, Z2, Z3 corresponding to - // the Z screw positions in the bed carriage. - // Define one position per Z stepper in stepper driver order. - #define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } - #else + /** + * Z Stepper positions for more rapid convergence in bed alignment. + * Requires 3 or 4 Z steppers. + * + * Define Stepper XY positions for Z1, Z2, Z3... corresponding to the screw + * positions in the bed carriage, with one position per Z stepper in stepper + * driver order. + */ + //#define Z_STEPPER_ALIGN_STEPPER_XY { { 210.7, 102.5 }, { 152.6, 220.0 }, { 94.5, 102.5 } } + + #ifndef Z_STEPPER_ALIGN_STEPPER_XY // Amplification factor. Used to scale the correction step up or down in case // the stepper (spindle) position is farther out than the test point. #define Z_STEPPER_ALIGN_AMP 1.0 // Use a value > 1.0 NOTE: This may cause instability! @@ -769,20 +1028,22 @@ // //#define ASSISTED_TRAMMING #if ENABLED(ASSISTED_TRAMMING) - // Define positions for probing points, use the hotend as reference not the sensor. - #define TRAMMING_POINT_XY { { 20, 20 }, { 200, 20 }, { 200, 200 }, { 20, 200 } } - // Define positions names for probing points. + // Define positions for probe points. + #define TRAMMING_POINT_XY { { 20, 20 }, { 180, 20 }, { 180, 180 }, { 20, 180 } } + + // Define position names for probe points. #define TRAMMING_POINT_NAME_1 "Front-Left" #define TRAMMING_POINT_NAME_2 "Front-Right" #define TRAMMING_POINT_NAME_3 "Back-Right" #define TRAMMING_POINT_NAME_4 "Back-Left" - // Enable to restore leveling setup after operation - #define RESTORE_LEVELING_AFTER_G35 + #define RESTORE_LEVELING_AFTER_G35 // Enable to restore leveling setup after operation + //#define REPORT_TRAMMING_MM // Report Z deviation (mm) for each point relative to the first + + //#define ASSISTED_TRAMMING_WIZARD // Add a Tramming Wizard to the LCD menu - // Add a menu item for Assisted Tramming - //#define ASSISTED_TRAMMING_MENU_ITEM + //#define ASSISTED_TRAMMING_WAIT_POSITION { X_CENTER, Y_CENTER, 30 } // Move the nozzle out of the way for adjustment /** * Screw thread: @@ -791,10 +1052,40 @@ * M5: 50 = Clockwise, 51 = Counter-Clockwise */ #define TRAMMING_SCREW_THREAD 30 + #endif // @section motion +/** + * Input Shaping -- EXPERIMENTAL + * + * Zero Vibration (ZV) Input Shaping for X and/or Y movements. + * + * This option uses a lot of SRAM for the step buffer, which is proportional + * to the largest step rate possible for any axis. If the build fails due to + * low SRAM the buffer size may be reduced by setting smaller values for + * DEFAULT_AXIS_STEPS_PER_UNIT and/or DEFAULT_MAX_FEEDRATE. Runtime editing + * of max feedrate (M203) or resonant frequency (M593) may result feedrate + * being capped to prevent buffer overruns. + * + * Tune with M593 D F: + * + * D Set the zeta/damping factor. If axes (X, Y, etc.) are not specified, set for all axes. + * F Set the frequency. If axes (X, Y, etc.) are not specified, set for all axes. + * T[map] Input Shaping type, 0:ZV, 1:EI, 2:2H EI (not implemented yet) + * X<1> Set the given parameters only for the X axis. + * Y<1> Set the given parameters only for the Y axis. + */ +//#define INPUT_SHAPING +#if ENABLED(INPUT_SHAPING) + #define SHAPING_FREQ_X 40 // (Hz) The dominant resonant frequency of the X axis. + #define SHAPING_FREQ_Y 40 // (Hz) The dominant resonant frequency of the Y axis. + #define SHAPING_ZETA_X 0.3f // Damping ratio of the X axis (range: 0.0 = no damping to 1.0 = critical damping). + #define SHAPING_ZETA_Y 0.3f // Damping ratio of the Y axis (range: 0.0 = no damping to 1.0 = critical damping). + //#define SHAPING_MENU // Add a menu to the LCD to set shaping parameters. +#endif + #define AXIS_RELATIVE_MODES { false, false, false, false } // Add a Duplicate option for well-separated conjoined nozzles @@ -804,6 +1095,12 @@ #define INVERT_X_STEP_PIN false #define INVERT_Y_STEP_PIN false #define INVERT_Z_STEP_PIN false +#define INVERT_I_STEP_PIN false +#define INVERT_J_STEP_PIN false +#define INVERT_K_STEP_PIN false +#define INVERT_U_STEP_PIN false +#define INVERT_V_STEP_PIN false +#define INVERT_W_STEP_PIN false #define INVERT_E_STEP_PIN false /** @@ -815,16 +1112,17 @@ #define DISABLE_INACTIVE_X true #define DISABLE_INACTIVE_Y true #define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! +#define DISABLE_INACTIVE_I true +#define DISABLE_INACTIVE_J true +#define DISABLE_INACTIVE_K true +#define DISABLE_INACTIVE_U true +#define DISABLE_INACTIVE_V true +#define DISABLE_INACTIVE_W true #define DISABLE_INACTIVE_E true -// If the Nozzle or Bed falls when the Z stepper is disabled, set its resting position here. -//#define Z_AFTER_DEACTIVATE Z_HOME_POS - -//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated - // Default Minimum Feedrates for printing and travel moves -#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S. -#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T. +#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S. +#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T. // Minimum time that a segment needs to take as the buffer gets emptied #define DEFAULT_MINSEGMENTTIME 20000 // (µs) Set with M205 B. @@ -860,9 +1158,12 @@ #if ENABLED(BACKLASH_COMPENSATION) // Define values for backlash distance and correction. // If BACKLASH_GCODE is enabled these values are the defaults. - #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) + #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (linear=mm, rotational=°) One value for each linear axis #define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction + // Add steps for motor direction changes on CORE kinematics + //#define CORE_BACKLASH + // Set BACKLASH_SMOOTHING_MM to spread backlash correction over multiple segments // to reduce print artifacts. (Enabling this is costly in memory and computation!) //#define BACKLASH_SMOOTHING_MM 3 // (mm) @@ -880,13 +1181,13 @@ // increments while checking for the contact to be broken. #define BACKLASH_MEASUREMENT_LIMIT 0.5 // (mm) #define BACKLASH_MEASUREMENT_RESOLUTION 0.005 // (mm) - #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_SPEED_SLOW // (mm/min) + #define BACKLASH_MEASUREMENT_FEEDRATE Z_PROBE_FEEDRATE_SLOW // (mm/min) #endif #endif #endif /** - * Automatic backlash, position and hotend offset calibration + * Automatic backlash, position, and hotend offset calibration * * Enable G425 to run automatic calibration using an electrically- * conductive cube, bolt, or washer mounted on the bed. @@ -928,6 +1229,19 @@ #define CALIBRATION_MEASURE_LEFT #define CALIBRATION_MEASURE_BACK + //#define CALIBRATION_MEASURE_IMIN + //#define CALIBRATION_MEASURE_IMAX + //#define CALIBRATION_MEASURE_JMIN + //#define CALIBRATION_MEASURE_JMAX + //#define CALIBRATION_MEASURE_KMIN + //#define CALIBRATION_MEASURE_KMAX + //#define CALIBRATION_MEASURE_UMIN + //#define CALIBRATION_MEASURE_UMAX + //#define CALIBRATION_MEASURE_VMIN + //#define CALIBRATION_MEASURE_VMAX + //#define CALIBRATION_MEASURE_WMIN + //#define CALIBRATION_MEASURE_WMAX + // Probing at the exact top center only works if the center is flat. If // probing on a screwhead or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES @@ -990,7 +1304,7 @@ /** * I2C-based DIGIPOTs (e.g., Azteeg X3 Pro) */ -//#define DIGIPOT_MCP4018 // Requires https://github.com/stawel/SlowSoftI2CMaster +//#define DIGIPOT_MCP4018 // Requires https://github.com/felias-fogg/SlowSoftI2CMaster //#define DIGIPOT_MCP4451 #if EITHER(DIGIPOT_MCP4018, DIGIPOT_MCP4451) #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT:4 AZTEEG_X3_PRO:8 MKS_SBASE:5 MIGHTYBOARD_REVE:5 @@ -1021,10 +1335,10 @@ // @section lcd -#if EITHER(ULTIPANEL, EXTENSIBLE_UI) +#if HAS_MANUAL_MOVE_MENU #define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel - #define SHORT_MANUAL_Z_MOVE 0.025 // (mm) Smallest manual Z move (< 0.1mm) - #if ENABLED(ULTIPANEL) + #define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines + #if IS_ULTIPANEL #define MANUAL_E_MOVES_RELATIVE // Display extruder move distance rather than "position" #define ULTIPANEL_FEEDMULTIPLY // Encoder sets the feedrate multiplier on the Status Screen #endif @@ -1044,7 +1358,46 @@ #define FEEDRATE_CHANGE_BEEP_FREQUENCY 440 #endif -#if HAS_LCD_MENU +// +// LCD Backlight Timeout +// +//#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight + +#if HAS_BED_PROBE && EITHER(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) + //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu + #if ENABLED(PROBE_OFFSET_WIZARD) + /** + * Enable to init the Probe Z-Offset when starting the Wizard. + * Use a height slightly above the estimated nozzle-to-probe Z offset. + * For example, with an offset of -5, consider a starting height of -4. + */ + //#define PROBE_OFFSET_WIZARD_START_Z -4.0 + + // Set a convenient position to do the calibration (probing point and nozzle/bed-distance) + //#define PROBE_OFFSET_WIZARD_XY_POS { X_CENTER, Y_CENTER } + #endif +#endif + +#if HAS_MARLINUI_MENU + + #if HAS_BED_PROBE + // Add calibration in the Probe Offsets menu to compensate for X-axis twist. + //#define X_AXIS_TWIST_COMPENSATION + #if ENABLED(X_AXIS_TWIST_COMPENSATION) + /** + * Enable to init the Probe Z-Offset when starting the Wizard. + * Use a height slightly above the estimated nozzle-to-probe Z offset. + * For example, with an offset of -5, consider a starting height of -4. + */ + #define XATC_START_Z 0.0 + #define XATC_MAX_POINTS 3 // Number of points to probe in the wizard + #define XATC_Y_POSITION Y_CENTER // (mm) Y position to probe + #define XATC_Z_OFFSETS { 0, 0, 0 } // Z offsets for X axis sample points + #endif + + // Show Deploy / Stow Probe options in the Motion menu. + #define PROBE_DEPLOY_STOW_MENU + #endif // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU @@ -1055,6 +1408,39 @@ // BACK menu items keep the highlight at the top //#define TURBO_BACK_MENU_ITEM + // Insert a menu for preheating at the top level to allow for quick access + //#define PREHEAT_SHORTCUT_MENU_ITEM + +#endif // HAS_MARLINUI_MENU + +#if ANY(HAS_DISPLAY, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu + #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state +#endif + +#if EITHER(HAS_DISPLAY, DWIN_LCD_PROUI) + // The timeout to return to the status screen from sub-menus + //#define LCD_TIMEOUT_TO_STATUS 15000 // (ms) + + #if ENABLED(SHOW_BOOTSCREEN) + #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) + #if EITHER(HAS_MARLINUI_U8GLIB, TFT_COLOR_UI) + #define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving lots of flash) + #endif + #endif + + // Scroll a longer status message into view + //#define STATUS_MESSAGE_SCROLLING + + // Apply a timeout to low-priority status messages + //#define STATUS_MESSAGE_TIMEOUT_SEC 30 // (seconds) + + // On the Info Screen, display XY with one decimal place when possible + //#define LCD_DECIMAL_SMALL_XY + + // Show the E position (filament used) during printing + //#define LCD_SHOW_E_TOTAL + /** * LED Control Menu * Add LED Control to the LCD menu @@ -1072,53 +1458,43 @@ //#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup #endif #if ENABLED(NEO2_COLOR_PRESETS) - #define NEO2_USER_PRESET_RED 255 // User defined RED value - #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value - #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value - #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value - #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity - //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip + #define NEO2_USER_PRESET_RED 255 // User defined RED value + #define NEO2_USER_PRESET_GREEN 128 // User defined GREEN value + #define NEO2_USER_PRESET_BLUE 0 // User defined BLUE value + #define NEO2_USER_PRESET_WHITE 255 // User defined WHITE value + #define NEO2_USER_PRESET_BRIGHTNESS 255 // User defined intensity + //#define NEO2_USER_PRESET_STARTUP // Have the printer display the user preset color on startup for the second strip #endif #endif -#endif // HAS_LCD_MENU +#endif // HAS_DISPLAY || DWIN_LCD_PROUI -// Scroll a longer status message into view -//#define STATUS_MESSAGE_SCROLLING - -// On the Info Screen, display XY with one decimal place when possible -//#define LCD_DECIMAL_SMALL_XY - -// The timeout (in ms) to return to the status screen from sub-menus -//#define LCD_TIMEOUT_TO_STATUS 15000 - -// Add an 'M73' G-code to set the current percentage -//#define LCD_SET_PROGRESS_MANUALLY - -// Show the E position (filament used) during printing -//#define LCD_SHOW_E_TOTAL - -#if ENABLED(SHOW_BOOTSCREEN) - #define BOOTSCREEN_TIMEOUT 4000 // (ms) Total Duration to display the boot screen(s) +// Add the G-code 'M73' to set / report the current job progress +//#define SET_PROGRESS_MANUALLY +#if ENABLED(SET_PROGRESS_MANUALLY) + //#define SET_PROGRESS_PERCENT // Add 'P' parameter to set percentage done, otherwise use Marlin's estimate + //#define SET_REMAINING_TIME // Add 'R' parameter to set remaining time, otherwise use Marlin's estimate + //#define SET_INTERACTION_TIME // Add 'C' parameter to set time until next filament change or other user interaction + #if ENABLED(SET_INTERACTION_TIME) + #define SHOW_INTERACTION_TIME // Display time until next user interaction ('C' = filament change) + #endif + //#define M73_REPORT // Report progress to host with 'M73' #endif -#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY) && (HAS_GRAPHICAL_LCD || HAS_CHARACTER_LCD) - //#define SHOW_REMAINING_TIME // Display estimated time to completion - #if ENABLED(SHOW_REMAINING_TIME) - //#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation - //#define ROTATE_PROGRESS_DISPLAY // Display (P)rogress, (E)lapsed, and (R)emaining time - #endif +// LCD Print Progress options, multiple can be rotated depending on screen layout +#if HAS_DISPLAY && EITHER(SDSUPPORT, SET_PROGRESS_MANUALLY) + #define SHOW_PROGRESS_PERCENT // Show print progress percentage (doesn't affect progress bar) + #define SHOW_ELAPSED_TIME // Display elapsed printing time (prefix 'E') + //#define SHOW_REMAINING_TIME // Display estimated time to completion (prefix 'R') - #if HAS_GRAPHICAL_LCD - //#define PRINT_PROGRESS_SHOW_DECIMALS // Show progress with decimal digits - #endif + //#define PRINT_PROGRESS_SHOW_DECIMALS // Show/report progress with decimal digits, not all UIs support this - #if HAS_CHARACTER_LCD + #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) //#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing #if ENABLED(LCD_PROGRESS_BAR) #define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar #define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message - #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) + #define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever) //#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it //#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar #endif @@ -1126,13 +1502,26 @@ #endif #if ENABLED(SDSUPPORT) + /** + * SD Card SPI Speed + * May be required to resolve "volume init" errors. + * + * Enable and set to SPI_HALF_SPEED, SPI_QUARTER_SPEED, or SPI_EIGHTH_SPEED + * otherwise full speed will be applied. + * + * :['SPI_HALF_SPEED', 'SPI_QUARTER_SPEED', 'SPI_EIGHTH_SPEED'] + */ + //#define SD_SPI_SPEED SPI_HALF_SPEED // The standard SD detect circuit reads LOW when media is inserted and HIGH when empty. // Enable this option and set to HIGH if your SD cards are incorrectly detected. //#define SD_DETECT_STATE HIGH + //#define SD_IGNORE_AT_STARTUP // Don't mount the SD card when starting up //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash) + //#define GCODE_REPEAT_MARKERS // Enable G-code M808 to set repeat markers and do looping + #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished @@ -1144,8 +1533,13 @@ #define SD_MENU_CONFIRM_START // Confirm the selected SD file before printing + //#define NO_SD_AUTOSTART // Remove auto#.g file support completely to save some Flash, SRAM //#define MENU_ADDAUTOSTART // Add a menu option to run auto#.g files + //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted + + //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu + #define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27") #if ENABLED(PRINTER_EVENT_LEDS) @@ -1167,13 +1561,20 @@ //#define POWER_LOSS_ZRAISE 2 // (mm) Z axis raise on resume (on power loss with UPS) //#define POWER_LOSS_PIN 44 // Pin to detect power loss. Set to -1 to disable default pin on boards without module. //#define POWER_LOSS_STATE HIGH // State of pin indicating power loss - //#define POWER_LOSS_PULL // Set pullup / pulldown as appropriate + //#define POWER_LOSS_PULLUP // Set pullup / pulldown as appropriate for your sensor + //#define POWER_LOSS_PULLDOWN //#define POWER_LOSS_PURGE_LEN 20 // (mm) Length of filament to purge on resume //#define POWER_LOSS_RETRACT_LEN 10 // (mm) Length of filament to retract on fail. Requires backup power. // Without a POWER_LOSS_PIN the following option helps reduce wear on the SD card, // especially with "vase mode" printing. Set too high and vases cannot be continued. #define POWER_LOSS_MIN_Z_CHANGE 0.05 // (mm) Minimum Z change before saving power-loss data + + // Enable if Z homing is needed for proper recovery. 99.9% of the time this should be disabled! + //#define POWER_LOSS_RECOVER_ZHOME + #if ENABLED(POWER_LOSS_RECOVER_ZHOME) + //#define POWER_LOSS_ZHOME_POS { 0, 0 } // Safe XY position to home Z while avoiding objects on the bed + #endif #endif /** @@ -1214,33 +1615,31 @@ // Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM. #endif - // This allows hosts to request long names for files and folders with M33 - //#define LONG_FILENAME_HOST_SUPPORT + // Allow international symbols in long filenames. To display correctly, the + // LCD's font must contain the characters. Check your selected LCD language. + //#define UTF_FILENAME_SUPPORT + + //#define LONG_FILENAME_HOST_SUPPORT // Get the long filename of a file/folder with 'M33 ' and list long filenames with 'M20 L' + //#define LONG_FILENAME_WRITE_SUPPORT // Create / delete files with long filenames via M28, M30, and Binary Transfer Protocol + //#define M20_TIMESTAMP_SUPPORT // Include timestamps by adding the 'T' flag to M20 commands - // Enable this option to scroll long filenames in the SD card menu - //#define SCROLL_LONG_FILENAMES + //#define SCROLL_LONG_FILENAMES // Scroll long filenames in the SD card menu - // Leave the heaters on after Stop Print (not recommended!) - //#define SD_ABORT_NO_COOLDOWN + //#define SD_ABORT_NO_COOLDOWN // Leave the heaters on after Stop Print (not recommended!) /** - * This option allows you to abort SD printing when any endstop is triggered. - * This feature must be enabled with "M540 S1" or from the LCD menu. - * To have any effect, endstops must be enabled during SD printing. + * Abort SD printing when any endstop is triggered. + * This feature is enabled with 'M540 S1' or from the LCD menu. + * Endstops must be activated for this option to work. */ //#define SD_ABORT_ON_ENDSTOP_HIT + #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) + //#define SD_ABORT_ON_ENDSTOP_HIT_GCODE "G28XY" // G-code to run on endstop hit (e.g., "G28XY" or "G27") + #endif - /** - * This option makes it easier to print the same SD Card file again. - * On print completion the LCD Menu will open with the file selected. - * You can just click to start the print, or navigate elsewhere. - */ - //#define SD_REPRINT_LAST_SELECTED_FILE + //#define SD_REPRINT_LAST_SELECTED_FILE // On print completion open the LCD Menu and select the same file - /** - * Auto-report SdCard status with M27 S - */ - //#define AUTO_REPORT_SD_STATUS + //#define AUTO_REPORT_SD_STATUS // Auto-report media status with 'M27 S' /** * Support for USB thumb drives using an Arduino USB Host Shield or @@ -1258,9 +1657,6 @@ */ //#define USB_FLASH_DRIVE_SUPPORT #if ENABLED(USB_FLASH_DRIVE_SUPPORT) - #define USB_CS_PIN SDSS - #define USB_INTR_PIN SD_DETECT_PIN - /** * USB Host Shield Library * @@ -1271,7 +1667,20 @@ * is less tested and is known to interfere with Servos. * [1] This requires USB_INTR_PIN to be interrupt-capable. */ + //#define USE_UHS2_USB //#define USE_UHS3_USB + + #define DISABLE_DUE_SD_MMC // Disable USB Host access to USB Drive to prevent hangs on block access for DUE platform + + /** + * Native USB Host supported by some boards (USB OTG) + */ + //#define USE_OTG_USB_HOST + + #if DISABLED(USE_OTG_USB_HOST) + #define USB_CS_PIN SDSS + #define USB_INTR_PIN SD_DETECT_PIN + #endif #endif /** @@ -1290,20 +1699,48 @@ #define SD_FIRMWARE_UPDATE_INACTIVE_VALUE 0xFF #endif + /** + * Enable this option if you have more than ~3K of unused flash space. + * Marlin will embed all settings in the firmware binary as compressed data. + * Use 'M503 C' to write the settings out to the SD Card as 'mc.zip'. + * See docs/ConfigEmbedding.md for details on how to use 'mc-apply.py'. + */ + //#define CONFIGURATION_EMBEDDING + // Add an optimized binary file transfer mode, initiated with 'M28 B1' //#define BINARY_FILE_TRANSFER + #if ENABLED(BINARY_FILE_TRANSFER) + // Include extra facilities (e.g., 'M20 F') supporting firmware upload via BINARY_FILE_TRANSFER + //#define CUSTOM_FIRMWARE_UPLOAD + #endif + /** * Set this option to one of the following (or the board's defaults apply): * * LCD - Use the SD drive in the external LCD controller. - * ONBOARD - Use the SD drive on the control board. (No SD_DETECT_PIN. M21 to init.) + * ONBOARD - Use the SD drive on the control board. * CUSTOM_CABLE - Use a custom cable to access the SD (as defined in a pins file). * * :[ 'LCD', 'ONBOARD', 'CUSTOM_CABLE' ] */ //#define SDCARD_CONNECTION LCD + // Enable if SD detect is rendered useless (e.g., by using an SD extender) + //#define NO_SD_DETECT + + /** + * Multiple volume support - EXPERIMENTAL. + * Adds 'M21 Pm' / 'M21 S' / 'M21 U' to mount SD Card / USB Drive. + */ + //#define MULTI_VOLUME + #if ENABLED(MULTI_VOLUME) + #define VOLUME_SD_ONBOARD + #define VOLUME_USB_FLASH_DRIVE + #define DEFAULT_VOLUME SV_SD_ONBOARD + #define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE + #endif + #endif // SDSUPPORT /** @@ -1324,27 +1761,29 @@ * controller events, as there is a trade-off between reliable * printing performance versus fast display updates. */ -#if HAS_GRAPHICAL_LCD - // Show SD percentage next to the progress bar - //#define DOGM_SD_PERCENT - +#if HAS_MARLINUI_U8GLIB // Save many cycles by drawing a hollow frame or no frame on the Info Screen //#define XYZ_NO_FRAME #define XYZ_HOLLOW_FRAME - // Enable to save many cycles by drawing a hollow frame on Menu Screens - #define MENU_HOLLOW_FRAME - - // A bigger font is available for edit items. Costs 3120 bytes of PROGMEM. + // A bigger font is available for edit items. Costs 3120 bytes of flash. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_BIG_EDIT_FONT - // A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM. + // A smaller font may be used on the Info Screen. Costs 2434 bytes of flash. // Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese. //#define USE_SMALL_INFOFONT - // Swap the CW/CCW indicators in the graphics overlay - //#define OVERLAY_GFX_REVERSE + /** + * Graphical Display Sleep + * + * The U8G library provides sleep / wake functions for SH1106, SSD1306, + * SSD1309, and some other DOGM displays. + * Enable this option to save energy and prevent OLED pixel burn-in. + * Adds the menu item Configuration > LCD Timeout (m) to set a wait period + * from 0 (disabled) to 99 minutes. + */ + //#define DISPLAY_SLEEP_MINUTES 2 // (minutes) Timeout before turning off the screen. Set with M255 S. /** * ST7920-based LCDs can emulate a 16 x 4 character display using @@ -1358,7 +1797,7 @@ * Set STATUS_EXPIRE_SECONDS to zero to never clear the status. * This will prevent position updates from being displayed. */ - #if ENABLED(U8GLIB_ST7920) + #if IS_U8GLIB_ST7920 // Enable this option and reduce the value to optimize screen updates. // The normal delay is 10µs. Use the lowest value that still gives a reliable display. //#define DOGM_SPI_DELAY_US 5 @@ -1376,17 +1815,18 @@ */ //#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones //#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends) - #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM) + #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM for numbered hotends) #define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating #define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating #define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating //#define STATUS_CUTTER_ANIM // Use a second bitmap to indicate spindle / laser active + //#define STATUS_COOLER_ANIM // Use a second bitmap to indicate laser cooling + //#define STATUS_FLOWMETER_ANIM // Use multiple bitmaps to indicate coolant flow //#define STATUS_ALT_BED_BITMAP // Use the alternative bed bitmap //#define STATUS_ALT_FAN_BITMAP // Use the alternative fan bitmap //#define STATUS_FAN_FRAMES 3 // :[0,1,2,3,4] Number of fan animation frames //#define STATUS_HEAT_PERCENT // Show heating in a progress bar - //#define BOOT_MARLIN_LOGO_SMALL // Show a smaller Marlin logo on the Boot Screen (saving 399 bytes of flash) - //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~?3260 (or ~940) bytes of PROGMEM. + //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. // Frivolous Game Options //#define MARLIN_BRICKOUT @@ -1394,27 +1834,31 @@ //#define MARLIN_SNAKE //#define GAMES_EASTER_EGG // Add extra blank lines above the "Games" sub-menu -#endif // HAS_GRAPHICAL_LCD +#endif // HAS_MARLINUI_U8GLIB + +#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI + #define MENU_HOLLOW_FRAME // Enable to save many cycles by drawing a hollow frame on Menu Screens + //#define OVERLAY_GFX_REVERSE // Swap the CW/CCW indicators in the graphics overlay +#endif // // Additional options for DGUS / DWIN displays // #if HAS_DGUS_LCD - #define DGUS_SERIAL_PORT 3 - #define DGUS_BAUDRATE 115200 + #define LCD_BAUDRATE 115200 #define DGUS_RX_BUFFER_SIZE 128 #define DGUS_TX_BUFFER_SIZE 48 - //#define DGUS_SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) + //#define SERIAL_STATS_RX_BUFFER_OVERRUNS // Fix Rx overrun situation (Currently only for AVR) #define DGUS_UPDATE_INTERVAL_MS 500 // (ms) Interval between automatic screen updates - #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_HIPRECY) + #if ANY(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS, DGUS_LCD_UI_HIPRECY) #define DGUS_PRINT_FILENAME // Display the filename during printing #define DGUS_PREHEAT_UI // Display a preheat screen during heatup - #if ENABLED(DGUS_LCD_UI_FYSETC) - //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for UI_FYSETC + #if EITHER(DGUS_LCD_UI_FYSETC, DGUS_LCD_UI_MKS) + //#define DGUS_UI_MOVE_DIS_OPTION // Disabled by default for FYSETC and MKS #else #define DGUS_UI_MOVE_DIS_OPTION // Enabled by default for UI_HIPRECY #endif @@ -1433,6 +1877,44 @@ #endif #endif // HAS_DGUS_LCD +// +// Additional options for AnyCubic Chiron TFT displays +// +#if ENABLED(ANYCUBIC_LCD_CHIRON) + // By default the type of panel is automatically detected. + // Enable one of these options if you know the panel type. + //#define CHIRON_TFT_STANDARD + //#define CHIRON_TFT_NEW + + // Enable the longer Anycubic powerup startup tune + //#define AC_DEFAULT_STARTUP_TUNE + + /** + * Display Folders + * By default the file browser lists all G-code files (including those in subfolders) in a flat list. + * Enable this option to display a hierarchical file browser. + * + * NOTES: + * - Without this option it helps to enable SDCARD_SORT_ALPHA so files are sorted before/after folders. + * - When used with the "new" panel, folder names will also have '.gcode' appended to their names. + * This hack is currently required to force the panel to show folders. + */ + #define AC_SD_FOLDER_VIEW +#endif + +// +// Specify additional languages for the UI. Default specified by LCD_LANGUAGE. +// +#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) + //#define LCD_LANGUAGE_2 fr + //#define LCD_LANGUAGE_3 de + //#define LCD_LANGUAGE_4 es + //#define LCD_LANGUAGE_5 it + #ifdef LCD_LANGUAGE_2 + //#define LCD_LANGUAGE_AUTO_SAVE // Automatically save language to EEPROM on change + #endif +#endif + // // Touch UI for the FTDI Embedded Video Engine (EVE) // @@ -1442,8 +1924,10 @@ //#define LCD_4DSYSTEMS_4DLCD_FT843 // 4D Systems 4.3" (480x272) //#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272) //#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480) - //#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI + //#define LCD_LULZBOT_CLCD_UI // LulzBot Color LCD UI //#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480) + //#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815 + //#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813 // Correct the resolution if not using the stock TFT panel. //#define TOUCH_UI_320x240 @@ -1451,8 +1935,8 @@ //#define TOUCH_UI_800x480 // Mappings for boards with a standard RepRapDiscount Display connector - //#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping - //#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping + //#define AO_EXP1_PINMAP // LulzBot CLCD UI EXP1 mapping + //#define AO_EXP2_PINMAP // LulzBot CLCD UI EXP2 mapping //#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping //#define S6_TFT_PINMAP // FYSETC S6 pin mapping //#define F6_TFT_PINMAP // FYSETC F6 pin mapping @@ -1500,18 +1984,14 @@ //#define TOUCH_UI_UTF8_FRACTIONS // ¼ ½ ¾ //#define TOUCH_UI_UTF8_SYMBOLS // µ ¶ ¦ § ¬ #endif + + // Cyrillic character set, costs about 27KiB of flash + //#define TOUCH_UI_UTF8_CYRILLIC_CHARSET #endif // Use a smaller font when labels don't fit buttons #define TOUCH_UI_FIT_TEXT - // Allow language selection from menu at run-time (otherwise use LCD_LANGUAGE) - //#define LCD_LANGUAGE_1 en - //#define LCD_LANGUAGE_2 fr - //#define LCD_LANGUAGE_3 de - //#define LCD_LANGUAGE_4 es - //#define LCD_LANGUAGE_5 it - // Use a numeric passcode for "Screen lock" keypad. // (recommended for smaller displays) //#define TOUCH_UI_PASSCODE @@ -1524,10 +2004,9 @@ #endif // -// FSMC / SPI Graphical TFT +// Classic UI Options // #if TFT_SCALED_DOGLCD - //#define GRAPHICAL_TFT_ROTATE_180 //#define TFT_MARLINUI_COLOR 0xFFFF // White //#define TFT_MARLINBG_COLOR 0x0000 // Black //#define TFT_DISABLED_COLOR 0x0003 // Almost black @@ -1617,14 +2096,35 @@ */ //#define LIN_ADVANCE #if ENABLED(LIN_ADVANCE) - //#define EXTRA_LIN_ADVANCE_K // Enable for second linear advance constants - #define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed - //#define LA_DEBUG // If enabled, this will generate debug information output over USB. - //#define EXPERIMENTAL_SCURVE // Enable this option to permit S-Curve Acceleration + #if ENABLED(DISTINCT_E_FACTORS) + #define ADVANCE_K { 0.22 } // (mm) Compression length per 1mm/s extruder speed, per extruder + #else + #define ADVANCE_K 0.22 // (mm) Compression length applying to all extruders + #endif + //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with M900 L. + //#define LA_DEBUG // Print debug information to serial during operation. Disable for production use. + //#define EXPERIMENTAL_SCURVE // Allow S-Curve Acceleration to be used with LA. + //#define ALLOW_LOW_EJERK // Allow a DEFAULT_EJERK value of <10. Recommended for direct drive hotends. + //#define EXPERIMENTAL_I2S_LA // Allow I2S_STEPPER_STREAM to be used with LA. Performance degrades as the LA step rate reaches ~20kHz. #endif // @section leveling +/** + * Use Safe Bed Leveling coordinates to move axes to a useful position before bed probing. + * For example, after homing a rotational axis the Z probe might not be perpendicular to the bed. + * Choose values the orient the bed horizontally and the Z-probe vertically. + */ +//#define SAFE_BED_LEVELING_START_X 0.0 +//#define SAFE_BED_LEVELING_START_Y 0.0 +//#define SAFE_BED_LEVELING_START_Z 0.0 +//#define SAFE_BED_LEVELING_START_I 0.0 +//#define SAFE_BED_LEVELING_START_J 0.0 +//#define SAFE_BED_LEVELING_START_K 0.0 +//#define SAFE_BED_LEVELING_START_U 0.0 +//#define SAFE_BED_LEVELING_START_V 0.0 +//#define SAFE_BED_LEVELING_START_W 0.0 + /** * Points to probe for all 3-point Leveling procedures. * Override if the automatically selected points are inadequate. @@ -1672,6 +2172,10 @@ //#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET) #endif +#if BOTH(AUTO_BED_LEVELING_UBL, EEPROM_SETTINGS) + //#define OPTIMIZED_MESH_STORAGE // Store mesh with less precision to save EEPROM space +#endif + /** * Repeatedly attempt G29 leveling until it succeeds. * Stop after G29_MAX_RETRIES attempts. @@ -1692,59 +2196,69 @@ /** * Thermal Probe Compensation - * Probe measurements are adjusted to compensate for temperature distortion. - * Use G76 to calibrate this feature. Use M871 to set values manually. - * For a more detailed explanation of the process see G76_M871.cpp. + * + * Adjust probe measurements to compensate for distortion associated with the temperature + * of the probe, bed, and/or hotend. + * Use G76 to automatically calibrate this feature for probe and bed temperatures. + * (Extruder temperature/offset values must be calibrated manually.) + * Use M871 to set temperature/offset values manually. + * For more details see https://marlinfw.org/docs/features/probe_temp_compensation.html */ -#if HAS_BED_PROBE && TEMP_SENSOR_PROBE && TEMP_SENSOR_BED - // Enable thermal first layer compensation using bed and probe temperatures - #define PROBE_TEMP_COMPENSATION +//#define PTC_PROBE // Compensate based on probe temperature +//#define PTC_BED // Compensate based on bed temperature +//#define PTC_HOTEND // Compensate based on hotend temperature - // Add additional compensation depending on hotend temperature - // Note: this values cannot be calibrated and have to be set manually - #if ENABLED(PROBE_TEMP_COMPENSATION) - // Park position to wait for probe cooldown - #define PTC_PARK_POS { 0, 0, 100 } - - // Probe position to probe and wait for probe to reach target temperature - #define PTC_PROBE_POS { 90, 100 } - - // Enable additional compensation using hotend temperature - // Note: this values cannot be calibrated automatically but have to be set manually - //#define USE_TEMP_EXT_COMPENSATION - - // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START - // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples. - - //#define PTC_SAMPLE_START 30.0f - //#define PTC_SAMPLE_RES 5.0f - //#define PTC_SAMPLE_COUNT 10U +#if ANY(PTC_PROBE, PTC_BED, PTC_HOTEND) + /** + * If the probe is outside the defined range, use linear extrapolation with the closest + * point and the point with index PTC_LINEAR_EXTRAPOLATION. e.g., If set to 4 it will use the + * linear extrapolation between data[0] and data[4] for values below PTC_PROBE_START. + */ + //#define PTC_LINEAR_EXTRAPOLATION 4 + + #if ENABLED(PTC_PROBE) + // Probe temperature calibration generates a table of values starting at PTC_PROBE_START + // (e.g., 30), in steps of PTC_PROBE_RES (e.g., 5) with PTC_PROBE_COUNT (e.g., 10) samples. + #define PTC_PROBE_START 30 // (°C) + #define PTC_PROBE_RES 5 // (°C) + #define PTC_PROBE_COUNT 10 + #define PTC_PROBE_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif + #if ENABLED(PTC_BED) // Bed temperature calibration builds a similar table. + #define PTC_BED_START 60 // (°C) + #define PTC_BED_RES 5 // (°C) + #define PTC_BED_COUNT 10 + #define PTC_BED_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif - //#define BTC_SAMPLE_START 60.0f - //#define BTC_SAMPLE_RES 5.0f - //#define BTC_SAMPLE_COUNT 10U + #if ENABLED(PTC_HOTEND) + // Note: There is no automatic calibration for the hotend. Use M871. + #define PTC_HOTEND_START 180 // (°C) + #define PTC_HOTEND_RES 5 // (°C) + #define PTC_HOTEND_COUNT 20 + #define PTC_HOTEND_ZOFFS { 0 } // (µm) Z adjustments per sample + #endif - // The temperature the probe should be at while taking measurements during bed temperature - // calibration. - //#define BTC_PROBE_TEMP 30.0f + // G76 options + #if BOTH(PTC_PROBE, PTC_BED) + // Park position to wait for probe cooldown + #define PTC_PARK_POS { 0, 0, 100 } - // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. - //#define PTC_PROBE_HEATING_OFFSET 0.5f + // Probe position to probe and wait for probe to reach target temperature + //#define PTC_PROBE_POS { 12.0f, 7.3f } // Example: MK52 magnetic heatbed + #define PTC_PROBE_POS { 90, 100 } - // Height to raise the Z-probe between heating and taking the next measurement. Some probes - // may fail to untrigger if they have been triggered for a long time, which can be solved by - // increasing the height the probe is raised to. - //#define PTC_PROBE_RAISE 15U + // The temperature the probe should be at while taking measurements during + // bed temperature calibration. + #define PTC_PROBE_TEMP 30 // (°C) - // If the probe is outside of the defined range, use linear extrapolation using the closest - // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] - // and data[4] to perform linear extrapolation for values below PTC_SAMPLE_START. - //#define PTC_LINEAR_EXTRAPOLATION 4 + // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. + // Note: The Z=0.0 offset is determined by the probe Z offset (e.g., as set with M851 Z). + #define PTC_PROBE_HEATING_OFFSET 0.5 #endif -#endif +#endif // PTC_PROBE || PTC_BED || PTC_HOTEND // @section extras @@ -1756,21 +2270,23 @@ // // G2/G3 Arc Support // -#define ARC_SUPPORT // Disable this feature to save ~3226 bytes +#define ARC_SUPPORT // Requires ~3226 bytes #if ENABLED(ARC_SUPPORT) - #define MM_PER_ARC_SEGMENT 1 // (mm) Length (or minimum length) of each arc segment - //#define ARC_SEGMENTS_PER_R 1 // Max segment length, MM_PER = Min - #define MIN_CIRCLE_SEGMENTS 24 // Minimum number of segments in a complete circle - //#define ARC_SEGMENTS_PER_SEC 50 // Use feedrate to choose segment length (with MM_PER_ARC_SEGMENT as the minimum) - #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections #define MIN_ARC_SEGMENT_MM 0.1 // (mm) Minimum length of each arc segment #define MAX_ARC_SEGMENT_MM 1.0 // (mm) Maximum length of each arc segment - //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles - //#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes + #define MIN_CIRCLE_SEGMENTS 72 // Minimum number of segments in a complete circle + //#define ARC_SEGMENTS_PER_SEC 50 // Use the feedrate to choose the segment length + #define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections + //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles + //#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure #endif -// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. -//#define BEZIER_CURVE_SUPPORT +// G5 Bézier Curve Support with XYZE destination and IJPQ offsets +//#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes + +#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT) + //#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes +#endif /** * Direct Stepping @@ -1853,7 +2369,7 @@ // @section motion // The number of linear moves that can be in the planner at once. -// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) #if BOTH(SDSUPPORT, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 #elif ENABLED(SDSUPPORT) @@ -1869,7 +2385,7 @@ #define BUFSIZE 4 // Transmission to Host Buffer Size -// To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. +// To save 386 bytes of flash (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. // To buffer a simple "ok" you need 4 bytes. // For ADVANCED_OK (M105) you need 32 bytes. // For debug-echo: 128 bytes for the optimal speed. @@ -1889,9 +2405,6 @@ //#define SERIAL_XON_XOFF #endif -// Add M575 G-code to change the baud rate -//#define BAUD_RATE_GCODE - #if ENABLED(SDSUPPORT) // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. @@ -1902,6 +2415,12 @@ //#define SERIAL_STATS_DROPPED_RX #endif +// Monitor RX buffer usage +// Dump an error to the serial port if the serial receive buffer overflows. +// If you see these errors, increase the RX_BUFFER_SIZE value. +// Not supported on all platforms. +//#define RX_BUFFER_MONITOR + /** * Emergency Command Parser * @@ -1912,6 +2431,26 @@ */ //#define EMERGENCY_PARSER +/** + * Realtime Reporting (requires EMERGENCY_PARSER) + * + * - Report position and state of the machine (like Grbl). + * - Auto-report position during long moves. + * - Useful for CNC/LASER. + * + * Adds support for commands: + * S000 : Report State and Position while moving. + * P000 : Instant Pause / Hold while moving. + * R000 : Resume from Pause / Hold. + * + * - During Hold all Emergency Parser commands are available, as usual. + * - Enable NANODLP_Z_SYNC and NANODLP_ALL_AXIS for move command end-state reports. + */ +//#define REALTIME_REPORTING_COMMANDS +#if ENABLED(REALTIME_REPORTING_COMMANDS) + //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC +#endif + // Bad Serial-connections can miss a received command by sending an 'ok' // Therefore some clients abort after 30 seconds in a timeout. // Some other clients start sending commands while receiving a 'wait'. @@ -1928,6 +2467,15 @@ // For serial echo, the number of digits after the decimal point //#define SERIAL_FLOAT_PRECISION 4 +/** + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. + * + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + // @section extras /** @@ -1952,25 +2500,24 @@ * Be sure to turn off auto-retract during filament change. * * Note that M207 / M208 / M209 settings are saved to EEPROM. - * */ //#define FWRETRACT #if ENABLED(FWRETRACT) - #define FWRETRACT_AUTORETRACT // Override slicer retractions + #define FWRETRACT_AUTORETRACT // Override slicer retractions #if ENABLED(FWRETRACT_AUTORETRACT) - #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length - #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length - #endif - #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) - #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) - #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting - #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise - #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) - #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) - #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction - #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction + #define MIN_AUTORETRACT 0.1 // (mm) Don't convert E moves under this length + #define MAX_AUTORETRACT 10.0 // (mm) Don't convert E moves over this length + #endif + #define RETRACT_LENGTH 3 // (mm) Default retract length (positive value) + #define RETRACT_LENGTH_SWAP 13 // (mm) Default swap retract length (positive value) + #define RETRACT_FEEDRATE 45 // (mm/s) Default feedrate for retracting + #define RETRACT_ZRAISE 0 // (mm) Default retract Z-raise + #define RETRACT_RECOVER_LENGTH 0 // (mm) Default additional recover length (added to retract length on recover) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // (mm) Default additional swap recover length (added to retract length on recover from toolchange) + #define RETRACT_RECOVER_FEEDRATE 8 // (mm/s) Default feedrate for recovering from retraction + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // (mm/s) Default feedrate for recovering from swap retraction #if ENABLED(MIXING_EXTRUDER) - //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously + //#define RETRACT_SYNC_MIXING // Retract and restore all mixing steppers simultaneously #endif #endif @@ -1987,6 +2534,20 @@ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif + /** + * Extra G-code to run while executing tool-change commands. Can be used to use an additional + * stepper motor (e.g., I axis in Configuration.h) to drive the tool-changer. + */ + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 + //#define EVENT_GCODE_TOOLCHANGE_ALWAYS_RUN // Always execute above G-code sequences. Use with caution! + + /** + * Tool Sensors detect when tools have been picked up or dropped. + * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc. + */ + //#define TOOL_SENSOR + /** * Retract and prime filament on tool-change to reduce * ooze and stringing and to get cleaner transitions. @@ -1995,26 +2556,30 @@ #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) // Load / Unload #define TOOLCHANGE_FS_LENGTH 12 // (mm) Load / Unload length - #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart, fine tune by LCD/Gcode) + #define TOOLCHANGE_FS_EXTRA_RESUME_LENGTH 0 // (mm) Extra length for better restart. Adjust with LCD or M217 B. #define TOOLCHANGE_FS_RETRACT_SPEED (50*60) // (mm/min) (Unloading) #define TOOLCHANGE_FS_UNRETRACT_SPEED (25*60) // (mm/min) (On SINGLENOZZLE or Bowden loading must be slowed down) // Longer prime to clean out a SINGLENOZZLE #define TOOLCHANGE_FS_EXTRA_PRIME 0 // (mm) Extra priming length #define TOOLCHANGE_FS_PRIME_SPEED (4.6*60) // (mm/min) Extra priming feedrate - #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm/min) Retract before cooling for less stringing, better wipe, etc. + #define TOOLCHANGE_FS_WIPE_RETRACT 0 // (mm) Cutting retraction out of park, for less stringing, better wipe, etc. Adjust with LCD or M217 G. // Cool after prime to reduce stringing #define TOOLCHANGE_FS_FAN -1 // Fan index or -1 to skip #define TOOLCHANGE_FS_FAN_SPEED 255 // 0-255 #define TOOLCHANGE_FS_FAN_TIME 10 // (seconds) - // Swap uninitialized extruder with TOOLCHANGE_FS_PRIME_SPEED for all lengths (recover + prime) - // (May break filament if not retracted beforehand.) - //#define TOOLCHANGE_FS_INIT_BEFORE_SWAP + // Use TOOLCHANGE_FS_PRIME_SPEED feedrate the first time each extruder is primed + //#define TOOLCHANGE_FS_SLOW_FIRST_PRIME - // Prime on the first T0 (If other, TOOLCHANGE_FS_INIT_BEFORE_SWAP applied) - // Enable it (M217 V[0/1]) before printing, to avoid unwanted priming on host connect + /** + * Prime T0 the first time T0 is sent to the printer: + * [ Power-On -> T0 { Activate & Prime T0 } -> T1 { Retract T0, Activate & Prime T1 } ] + * If disabled, no priming on T0 until switching back to T0 from another extruder: + * [ Power-On -> T0 { T0 Activated } -> T1 { Activate & Prime T1 } -> T0 { Retract T1, Activate & Prime T0 } ] + * Enable with M217 V1 before printing to avoid unwanted priming on host connect. + */ //#define TOOLCHANGE_FS_PRIME_FIRST_USED /** @@ -2044,15 +2609,18 @@ #endif #endif // HAS_MULTI_EXTRUDER +// @section advanced pause + /** - * Advanced Pause - * Experimental feature for filament change support and for parking the nozzle when paused. - * Adds the GCode M600 for initiating filament change. - * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. + * Advanced Pause for Filament Change + * - Adds the G-code M600 Filament Change to initiate a filament change. + * - This feature is required for the default FILAMENT_RUNOUT_SCRIPT. + * + * Requirements: + * - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE. + * - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER. * - * Requires an LCD display. - * Requires NOZZLE_PARK_FEATURE. - * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. + * Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park. */ //#define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -2091,6 +2659,8 @@ #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety. #define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed. #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change. + //#define FILAMENT_CHANGE_RESUME_ON_INSERT // Automatically continue / load filament when runout sensor is triggered again. + //#define PAUSE_REHEAT_FAST_RESUME // Reduce number of waits by not prompting again post-timeout before continuing. //#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change. //#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change @@ -2099,13 +2669,12 @@ //#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302) #endif -// @section tmc - /** * TMC26X Stepper Driver options * * The TMC26XStepper library is required for this stepper driver. * https://github.com/trinamic/TMC26XStepper + * @section tmc/tmc26x */ #if HAS_DRIVER(TMC26X) @@ -2118,7 +2687,7 @@ #if AXIS_DRIVER_TYPE_X2(TMC26X) #define X2_MAX_CURRENT 1000 #define X2_SENSE_RESISTOR 91 - #define X2_MICROSTEPS 16 + #define X2_MICROSTEPS X_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Y(TMC26X) @@ -2130,7 +2699,7 @@ #if AXIS_DRIVER_TYPE_Y2(TMC26X) #define Y2_MAX_CURRENT 1000 #define Y2_SENSE_RESISTOR 91 - #define Y2_MICROSTEPS 16 + #define Y2_MICROSTEPS Y_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z(TMC26X) @@ -2142,19 +2711,55 @@ #if AXIS_DRIVER_TYPE_Z2(TMC26X) #define Z2_MAX_CURRENT 1000 #define Z2_SENSE_RESISTOR 91 - #define Z2_MICROSTEPS 16 + #define Z2_MICROSTEPS Z_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z3(TMC26X) #define Z3_MAX_CURRENT 1000 #define Z3_SENSE_RESISTOR 91 - #define Z3_MICROSTEPS 16 + #define Z3_MICROSTEPS Z_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_Z4(TMC26X) #define Z4_MAX_CURRENT 1000 #define Z4_SENSE_RESISTOR 91 - #define Z4_MICROSTEPS 16 + #define Z4_MICROSTEPS Z_MICROSTEPS + #endif + + #if AXIS_DRIVER_TYPE_I(TMC26X) + #define I_MAX_CURRENT 1000 + #define I_SENSE_RESISTOR 91 + #define I_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_J(TMC26X) + #define J_MAX_CURRENT 1000 + #define J_SENSE_RESISTOR 91 + #define J_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_K(TMC26X) + #define K_MAX_CURRENT 1000 + #define K_SENSE_RESISTOR 91 + #define K_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_U(TMC26X) + #define U_MAX_CURRENT 1000 + #define U_SENSE_RESISTOR 91 + #define U_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_V(TMC26X) + #define V_MAX_CURRENT 1000 + #define V_SENSE_RESISTOR 91 + #define V_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_W(TMC26X) + #define W_MAX_CURRENT 1000 + #define W_SENSE_RESISTOR 91 + #define W_MICROSTEPS 16 #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) @@ -2166,49 +2771,47 @@ #if AXIS_DRIVER_TYPE_E1(TMC26X) #define E1_MAX_CURRENT 1000 #define E1_SENSE_RESISTOR 91 - #define E1_MICROSTEPS 16 + #define E1_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E2(TMC26X) #define E2_MAX_CURRENT 1000 #define E2_SENSE_RESISTOR 91 - #define E2_MICROSTEPS 16 + #define E2_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E3(TMC26X) #define E3_MAX_CURRENT 1000 #define E3_SENSE_RESISTOR 91 - #define E3_MICROSTEPS 16 + #define E3_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E4(TMC26X) #define E4_MAX_CURRENT 1000 #define E4_SENSE_RESISTOR 91 - #define E4_MICROSTEPS 16 + #define E4_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E5(TMC26X) #define E5_MAX_CURRENT 1000 #define E5_SENSE_RESISTOR 91 - #define E5_MICROSTEPS 16 + #define E5_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E6(TMC26X) #define E6_MAX_CURRENT 1000 #define E6_SENSE_RESISTOR 91 - #define E6_MICROSTEPS 16 + #define E6_MICROSTEPS E0_MICROSTEPS #endif #if AXIS_DRIVER_TYPE_E7(TMC26X) #define E7_MAX_CURRENT 1000 #define E7_SENSE_RESISTOR 91 - #define E7_MICROSTEPS 16 + #define E7_MICROSTEPS E0_MICROSTEPS #endif #endif // TMC26X -// @section tmc_smart - /** * To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode * connect your SPI pins to the hardware SPI interface on your board and define @@ -2224,26 +2827,36 @@ * * TMCStepper library is required to use TMC stepper drivers. * https://github.com/teemuatlut/TMCStepper + * @section tmc/config */ #if HAS_TRINAMIC_CONFIG #define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current - #define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256 + + /** + * Interpolate microsteps to 256 + * Override for each driver with _INTERPOLATE settings below + */ + #define INTERPOLATE true #if AXIS_IS_TMC(X) #define X_CURRENT 800 // (mA) RMS current. Multiply by 1.414 for peak current. #define X_CURRENT_HOME X_CURRENT // (mA) RMS current for sensorless homing - #define X_MICROSTEPS 16 // 0..256 + #define X_MICROSTEPS 16 // 0..256 #define X_RSENSE 0.11 - #define X_CHAIN_POS -1 // <=0 : Not chained. 1 : MCU MOSI connected. 2 : Next in chain, ... + #define X_CHAIN_POS -1 // -1..0: Not chained. 1: MCU MOSI connected. 2: Next in chain, ... + //#define X_INTERPOLATE true // Enable to override 'INTERPOLATE' for the X axis + //#define X_HOLD_MULTIPLIER 0.5 // Enable to override 'HOLD_MULTIPLIER' for the X axis #endif #if AXIS_IS_TMC(X2) #define X2_CURRENT 800 #define X2_CURRENT_HOME X2_CURRENT - #define X2_MICROSTEPS 16 + #define X2_MICROSTEPS X_MICROSTEPS #define X2_RSENSE 0.11 #define X2_CHAIN_POS -1 + //#define X2_INTERPOLATE true + //#define X2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y) @@ -2252,14 +2865,18 @@ #define Y_MICROSTEPS 16 #define Y_RSENSE 0.11 #define Y_CHAIN_POS -1 + //#define Y_INTERPOLATE true + //#define Y_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Y2) #define Y2_CURRENT 800 #define Y2_CURRENT_HOME Y2_CURRENT - #define Y2_MICROSTEPS 16 + #define Y2_MICROSTEPS Y_MICROSTEPS #define Y2_RSENSE 0.11 #define Y2_CHAIN_POS -1 + //#define Y2_INTERPOLATE true + //#define Y2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z) @@ -2268,30 +2885,98 @@ #define Z_MICROSTEPS 16 #define Z_RSENSE 0.11 #define Z_CHAIN_POS -1 + //#define Z_INTERPOLATE true + //#define Z_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z2) #define Z2_CURRENT 800 #define Z2_CURRENT_HOME Z2_CURRENT - #define Z2_MICROSTEPS 16 + #define Z2_MICROSTEPS Z_MICROSTEPS #define Z2_RSENSE 0.11 #define Z2_CHAIN_POS -1 + //#define Z2_INTERPOLATE true + //#define Z2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z3) #define Z3_CURRENT 800 #define Z3_CURRENT_HOME Z3_CURRENT - #define Z3_MICROSTEPS 16 + #define Z3_MICROSTEPS Z_MICROSTEPS #define Z3_RSENSE 0.11 #define Z3_CHAIN_POS -1 + //#define Z3_INTERPOLATE true + //#define Z3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(Z4) #define Z4_CURRENT 800 #define Z4_CURRENT_HOME Z4_CURRENT - #define Z4_MICROSTEPS 16 + #define Z4_MICROSTEPS Z_MICROSTEPS #define Z4_RSENSE 0.11 #define Z4_CHAIN_POS -1 + //#define Z4_INTERPOLATE true + //#define Z4_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(I) + #define I_CURRENT 800 + #define I_CURRENT_HOME I_CURRENT + #define I_MICROSTEPS 16 + #define I_RSENSE 0.11 + #define I_CHAIN_POS -1 + //#define I_INTERPOLATE true + //#define I_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(J) + #define J_CURRENT 800 + #define J_CURRENT_HOME J_CURRENT + #define J_MICROSTEPS 16 + #define J_RSENSE 0.11 + #define J_CHAIN_POS -1 + //#define J_INTERPOLATE true + //#define J_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(K) + #define K_CURRENT 800 + #define K_CURRENT_HOME K_CURRENT + #define K_MICROSTEPS 16 + #define K_RSENSE 0.11 + #define K_CHAIN_POS -1 + //#define K_INTERPOLATE true + //#define K_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(U) + #define U_CURRENT 800 + #define U_CURRENT_HOME U_CURRENT + #define U_MICROSTEPS 8 + #define U_RSENSE 0.11 + #define U_CHAIN_POS -1 + //#define U_INTERPOLATE true + //#define U_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(V) + #define V_CURRENT 800 + #define V_CURRENT_HOME V_CURRENT + #define V_MICROSTEPS 8 + #define V_RSENSE 0.11 + #define V_CHAIN_POS -1 + //#define V_INTERPOLATE true + //#define V_HOLD_MULTIPLIER 0.5 + #endif + + #if AXIS_IS_TMC(W) + #define W_CURRENT 800 + #define W_CURRENT_HOME W_CURRENT + #define W_MICROSTEPS 8 + #define W_RSENSE 0.11 + #define W_CHAIN_POS -1 + //#define W_INTERPOLATE true + //#define W_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E0) @@ -2299,57 +2984,75 @@ #define E0_MICROSTEPS 16 #define E0_RSENSE 0.11 #define E0_CHAIN_POS -1 + //#define E0_INTERPOLATE true + //#define E0_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E1) #define E1_CURRENT 800 - #define E1_MICROSTEPS 16 + #define E1_MICROSTEPS E0_MICROSTEPS #define E1_RSENSE 0.11 #define E1_CHAIN_POS -1 + //#define E1_INTERPOLATE true + //#define E1_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E2) #define E2_CURRENT 800 - #define E2_MICROSTEPS 16 + #define E2_MICROSTEPS E0_MICROSTEPS #define E2_RSENSE 0.11 #define E2_CHAIN_POS -1 + //#define E2_INTERPOLATE true + //#define E2_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E3) #define E3_CURRENT 800 - #define E3_MICROSTEPS 16 + #define E3_MICROSTEPS E0_MICROSTEPS #define E3_RSENSE 0.11 #define E3_CHAIN_POS -1 + //#define E3_INTERPOLATE true + //#define E3_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E4) #define E4_CURRENT 800 - #define E4_MICROSTEPS 16 + #define E4_MICROSTEPS E0_MICROSTEPS #define E4_RSENSE 0.11 #define E4_CHAIN_POS -1 + //#define E4_INTERPOLATE true + //#define E4_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E5) #define E5_CURRENT 800 - #define E5_MICROSTEPS 16 + #define E5_MICROSTEPS E0_MICROSTEPS #define E5_RSENSE 0.11 #define E5_CHAIN_POS -1 + //#define E5_INTERPOLATE true + //#define E5_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E6) #define E6_CURRENT 800 - #define E6_MICROSTEPS 16 + #define E6_MICROSTEPS E0_MICROSTEPS #define E6_RSENSE 0.11 #define E6_CHAIN_POS -1 + //#define E6_INTERPOLATE true + //#define E6_HOLD_MULTIPLIER 0.5 #endif #if AXIS_IS_TMC(E7) #define E7_CURRENT 800 - #define E7_MICROSTEPS 16 + #define E7_MICROSTEPS E0_MICROSTEPS #define E7_RSENSE 0.11 #define E7_CHAIN_POS -1 + //#define E7_INTERPOLATE true + //#define E7_HOLD_MULTIPLIER 0.5 #endif + // @section tmc/spi + /** * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. @@ -2361,6 +3064,13 @@ //#define Y2_CS_PIN -1 //#define Z2_CS_PIN -1 //#define Z3_CS_PIN -1 + //#define Z4_CS_PIN -1 + //#define I_CS_PIN -1 + //#define J_CS_PIN -1 + //#define K_CS_PIN -1 + //#define U_CS_PIN -1 + //#define V_CS_PIN -1 + //#define W_CS_PIN -1 //#define E0_CS_PIN -1 //#define E1_CS_PIN -1 //#define E2_CS_PIN -1 @@ -2380,6 +3090,8 @@ //#define TMC_SW_MISO -1 //#define TMC_SW_SCK -1 + // @section tmc/serial + /** * Four TMC2209 drivers can use the same HW/SW serial port with hardware configured addresses. * Set the address using jumpers on pins MS1 and MS2. @@ -2392,22 +3104,30 @@ * Set *_SERIAL_TX_PIN and *_SERIAL_RX_PIN to match for all drivers * on the same serial port, either here or in your board's pins file. */ - #define X_SLAVE_ADDRESS 0 - #define Y_SLAVE_ADDRESS 0 - #define Z_SLAVE_ADDRESS 0 - #define X2_SLAVE_ADDRESS 0 - #define Y2_SLAVE_ADDRESS 0 - #define Z2_SLAVE_ADDRESS 0 - #define Z3_SLAVE_ADDRESS 0 - #define Z4_SLAVE_ADDRESS 0 - #define E0_SLAVE_ADDRESS 0 - #define E1_SLAVE_ADDRESS 0 - #define E2_SLAVE_ADDRESS 0 - #define E3_SLAVE_ADDRESS 0 - #define E4_SLAVE_ADDRESS 0 - #define E5_SLAVE_ADDRESS 0 - #define E6_SLAVE_ADDRESS 0 - #define E7_SLAVE_ADDRESS 0 + //#define X_SLAVE_ADDRESS 0 + //#define Y_SLAVE_ADDRESS 0 + //#define Z_SLAVE_ADDRESS 0 + //#define X2_SLAVE_ADDRESS 0 + //#define Y2_SLAVE_ADDRESS 0 + //#define Z2_SLAVE_ADDRESS 0 + //#define Z3_SLAVE_ADDRESS 0 + //#define Z4_SLAVE_ADDRESS 0 + //#define I_SLAVE_ADDRESS 0 + //#define J_SLAVE_ADDRESS 0 + //#define K_SLAVE_ADDRESS 0 + //#define U_SLAVE_ADDRESS 0 + //#define V_SLAVE_ADDRESS 0 + //#define W_SLAVE_ADDRESS 0 + //#define E0_SLAVE_ADDRESS 0 + //#define E1_SLAVE_ADDRESS 0 + //#define E2_SLAVE_ADDRESS 0 + //#define E3_SLAVE_ADDRESS 0 + //#define E4_SLAVE_ADDRESS 0 + //#define E5_SLAVE_ADDRESS 0 + //#define E6_SLAVE_ADDRESS 0 + //#define E7_SLAVE_ADDRESS 0 + + // @section tmc/smart /** * Software enable @@ -2417,6 +3137,8 @@ */ //#define SOFTWARE_DRIVER_ENABLE + // @section tmc/stealthchop + /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * Use Trinamic's ultra quiet stepping mode. @@ -2424,6 +3146,12 @@ */ #define STEALTHCHOP_XY #define STEALTHCHOP_Z + #define STEALTHCHOP_I + #define STEALTHCHOP_J + #define STEALTHCHOP_K + #define STEALTHCHOP_U + #define STEALTHCHOP_V + #define STEALTHCHOP_W #define STEALTHCHOP_E /** @@ -2435,13 +3163,37 @@ * CHOPPER_DEFAULT_24V * CHOPPER_DEFAULT_36V * CHOPPER_09STEP_24V // 0.9 degree steppers (24V) - * CHOPPER_PRUSAMK3_24V // Imported parameters from the official Pruša firmware for MK3 (24V) + * CHOPPER_PRUSAMK3_24V // Imported parameters from the official Průša firmware for MK3 (24V) * CHOPPER_MARLIN_119 // Old defaults from Marlin v1.1.9 * - * Define you own with + * Define your own with: * { , , hysteresis_start[1..8] } */ - #define CHOPPER_TIMING CHOPPER_DEFAULT_12V + #define CHOPPER_TIMING CHOPPER_DEFAULT_12V // All axes (override below) + //#define CHOPPER_TIMING_X CHOPPER_TIMING // For X Axes (override below) + //#define CHOPPER_TIMING_X2 CHOPPER_TIMING_X + //#define CHOPPER_TIMING_Y CHOPPER_TIMING // For Y Axes (override below) + //#define CHOPPER_TIMING_Y2 CHOPPER_TIMING_Y + //#define CHOPPER_TIMING_Z CHOPPER_TIMING // For Z Axes (override below) + //#define CHOPPER_TIMING_Z2 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_Z3 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_Z4 CHOPPER_TIMING_Z + //#define CHOPPER_TIMING_I CHOPPER_TIMING // For I Axis + //#define CHOPPER_TIMING_J CHOPPER_TIMING // For J Axis + //#define CHOPPER_TIMING_K CHOPPER_TIMING // For K Axis + //#define CHOPPER_TIMING_U CHOPPER_TIMING // For U Axis + //#define CHOPPER_TIMING_V CHOPPER_TIMING // For V Axis + //#define CHOPPER_TIMING_W CHOPPER_TIMING // For W Axis + //#define CHOPPER_TIMING_E CHOPPER_TIMING // For Extruders (override below) + //#define CHOPPER_TIMING_E1 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E2 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E3 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E4 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E5 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E6 CHOPPER_TIMING_E + //#define CHOPPER_TIMING_E7 CHOPPER_TIMING_E + + // @section tmc/status /** * Monitor Trinamic drivers @@ -2462,6 +3214,8 @@ #define STOP_ON_ERROR #endif + // @section tmc/hybrid + /** * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. @@ -2479,6 +3233,12 @@ #define Z2_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3 #define Z4_HYBRID_THRESHOLD 3 + #define I_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] + #define J_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] + #define K_HYBRID_THRESHOLD 3 // [linear=mm/s, rotational=°/s] + #define U_HYBRID_THRESHOLD 3 // [mm/s] + #define V_HYBRID_THRESHOLD 3 + #define W_HYBRID_THRESHOLD 3 #define E0_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30 @@ -2504,7 +3264,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** + * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * @@ -2512,6 +3272,7 @@ * homing and adds a guard period for endstop triggering. * * Comment *_STALL_SENSITIVITY to disable sensorless homing for that axis. + * @section tmc/stallguard */ //#define SENSORLESS_HOMING // StallGuard capable drivers only @@ -2525,10 +3286,18 @@ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define I_STALL_SENSITIVITY 8 + //#define J_STALL_SENSITIVITY 8 + //#define K_STALL_SENSITIVITY 8 + //#define U_STALL_SENSITIVITY 8 + //#define V_STALL_SENSITIVITY 8 + //#define W_STALL_SENSITIVITY 8 //#define SPI_ENDSTOPS // TMC2130 only //#define IMPROVE_HOMING_RELIABILITY #endif + // @section tmc/config + /** * TMC Homing stepper phase. * @@ -2549,7 +3318,7 @@ /** * Enable M122 debugging command for TMC stepper drivers. - * M122 S0/1 will enable continous reporting. + * M122 S0/1 will enable continuous reporting. */ //#define TMC_DEBUG @@ -2568,200 +3337,6 @@ #endif // HAS_TRINAMIC_CONFIG -// @section L64XX - -/** - * L64XX Stepper Driver options - * - * Arduino-L6470 library (0.8.0 or higher) is required. - * https://github.com/ameyer/Arduino-L6470 - * - * Requires the following to be defined in your pins_YOUR_BOARD file - * L6470_CHAIN_SCK_PIN - * L6470_CHAIN_MISO_PIN - * L6470_CHAIN_MOSI_PIN - * L6470_CHAIN_SS_PIN - * ENABLE_RESET_L64XX_CHIPS(Q) where Q is 1 to enable and 0 to reset - */ - -#if HAS_L64XX - - //#define L6470_CHITCHAT // Display additional status info - - #if AXIS_IS_L64XX(X) - #define X_MICROSTEPS 128 // Number of microsteps (VALID: 1, 2, 4, 8, 16, 32, 128) - L6474 max is 16 - #define X_OVERCURRENT 2000 // (mA) Current where the driver detects an over current - // L6470 & L6474 - VALID: 375 x (1 - 16) - 6A max - rounds down - // POWERSTEP01: VALID: 1000 x (1 - 32) - 32A max - rounds down - #define X_STALLCURRENT 1500 // (mA) Current where the driver detects a stall (VALID: 31.25 * (1-128) - 4A max - rounds down) - // L6470 & L6474 - VALID: 31.25 * (1-128) - 4A max - rounds down - // POWERSTEP01: VALID: 200 x (1 - 32) - 6.4A max - rounds down - // L6474 - STALLCURRENT setting is used to set the nominal (TVAL) current - #define X_MAX_VOLTAGE 127 // 0-255, Maximum effective voltage seen by stepper - not used by L6474 - #define X_CHAIN_POS -1 // Position in SPI chain, 0=Not in chain, 1=Nearest MOSI - #define X_SLEW_RATE 1 // 0-3, Slew 0 is slowest, 3 is fastest - #endif - - #if AXIS_IS_L64XX(X2) - #define X2_MICROSTEPS 128 - #define X2_OVERCURRENT 2000 - #define X2_STALLCURRENT 1500 - #define X2_MAX_VOLTAGE 127 - #define X2_CHAIN_POS -1 - #define X2_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Y) - #define Y_MICROSTEPS 128 - #define Y_OVERCURRENT 2000 - #define Y_STALLCURRENT 1500 - #define Y_MAX_VOLTAGE 127 - #define Y_CHAIN_POS -1 - #define Y_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Y2) - #define Y2_MICROSTEPS 128 - #define Y2_OVERCURRENT 2000 - #define Y2_STALLCURRENT 1500 - #define Y2_MAX_VOLTAGE 127 - #define Y2_CHAIN_POS -1 - #define Y2_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Z) - #define Z_MICROSTEPS 128 - #define Z_OVERCURRENT 2000 - #define Z_STALLCURRENT 1500 - #define Z_MAX_VOLTAGE 127 - #define Z_CHAIN_POS -1 - #define Z_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Z2) - #define Z2_MICROSTEPS 128 - #define Z2_OVERCURRENT 2000 - #define Z2_STALLCURRENT 1500 - #define Z2_MAX_VOLTAGE 127 - #define Z2_CHAIN_POS -1 - #define Z2_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Z3) - #define Z3_MICROSTEPS 128 - #define Z3_OVERCURRENT 2000 - #define Z3_STALLCURRENT 1500 - #define Z3_MAX_VOLTAGE 127 - #define Z3_CHAIN_POS -1 - #define Z3_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(Z4) - #define Z4_MICROSTEPS 128 - #define Z4_OVERCURRENT 2000 - #define Z4_STALLCURRENT 1500 - #define Z4_MAX_VOLTAGE 127 - #define Z4_CHAIN_POS -1 - #define Z4_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E0) - #define E0_MICROSTEPS 128 - #define E0_OVERCURRENT 2000 - #define E0_STALLCURRENT 1500 - #define E0_MAX_VOLTAGE 127 - #define E0_CHAIN_POS -1 - #define E0_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E1) - #define E1_MICROSTEPS 128 - #define E1_OVERCURRENT 2000 - #define E1_STALLCURRENT 1500 - #define E1_MAX_VOLTAGE 127 - #define E1_CHAIN_POS -1 - #define E1_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E2) - #define E2_MICROSTEPS 128 - #define E2_OVERCURRENT 2000 - #define E2_STALLCURRENT 1500 - #define E2_MAX_VOLTAGE 127 - #define E2_CHAIN_POS -1 - #define E2_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E3) - #define E3_MICROSTEPS 128 - #define E3_OVERCURRENT 2000 - #define E3_STALLCURRENT 1500 - #define E3_MAX_VOLTAGE 127 - #define E3_CHAIN_POS -1 - #define E3_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E4) - #define E4_MICROSTEPS 128 - #define E4_OVERCURRENT 2000 - #define E4_STALLCURRENT 1500 - #define E4_MAX_VOLTAGE 127 - #define E4_CHAIN_POS -1 - #define E4_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E5) - #define E5_MICROSTEPS 128 - #define E5_OVERCURRENT 2000 - #define E5_STALLCURRENT 1500 - #define E5_MAX_VOLTAGE 127 - #define E5_CHAIN_POS -1 - #define E5_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E6) - #define E6_MICROSTEPS 128 - #define E6_OVERCURRENT 2000 - #define E6_STALLCURRENT 1500 - #define E6_MAX_VOLTAGE 127 - #define E6_CHAIN_POS -1 - #define E6_SLEW_RATE 1 - #endif - - #if AXIS_IS_L64XX(E7) - #define E7_MICROSTEPS 128 - #define E7_OVERCURRENT 2000 - #define E7_STALLCURRENT 1500 - #define E7_MAX_VOLTAGE 127 - #define E7_CHAIN_POS -1 - #define E7_SLEW_RATE 1 - #endif - - /** - * Monitor L6470 drivers for error conditions like over temperature and over current. - * In the case of over temperature Marlin can decrease the drive until the error condition clears. - * Other detected conditions can be used to stop the current print. - * Relevant G-codes: - * M906 - I1/2/3/4/5 Set or get motor drive level using axis codes X, Y, Z, E. Report values if no axis codes given. - * I not present or I0 or I1 - X, Y, Z or E0 - * I2 - X2, Y2, Z2 or E1 - * I3 - Z3 or E3 - * I4 - Z4 or E4 - * I5 - E5 - * M916 - Increase drive level until get thermal warning - * M917 - Find minimum current thresholds - * M918 - Increase speed until max or error - * M122 S0/1 - Report driver parameters - */ - //#define MONITOR_L6470_DRIVER_STATUS - - #if ENABLED(MONITOR_L6470_DRIVER_STATUS) - #define KVAL_HOLD_STEP_DOWN 1 - //#define L6470_STOP_ON_ERROR - #endif - -#endif // HAS_L64XX - // @section i2cbus // @@ -2803,7 +3378,7 @@ #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave #endif -// @section extras +// @section photo /** * Photo G-code @@ -2846,6 +3421,8 @@ #endif #endif +// @section cnc + /** * Spindle & Laser control * @@ -2859,22 +3436,46 @@ * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V * hardware PWM pin for the speed control and a pin for the rotation direction. * - * See https://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + * See https://marlinfw.org/docs/configuration/2.0.9/laser_spindle.html for more config details. */ //#define SPINDLE_FEATURE //#define LASER_FEATURE #if EITHER(SPINDLE_FEATURE, LASER_FEATURE) - #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if the on/off function is active HIGH - #define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power - #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH + + #define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR, ESP32, and LPC) + // ESP32: If SPINDLE_LASER_PWM_PIN is onboard then <=78125Hz. For I2S expander + // the frequency determines the PWM resolution. 2500Hz = 0-100, 977Hz = 0-255, ... + // (250000 / SPINDLE_LASER_FREQUENCY) = max value. + #endif - #define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC) + //#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11 + #if ENABLED(AIR_EVACUATION) + #define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH + //#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin + #endif + + //#define AIR_ASSIST // Air Assist control with G-codes M8-M9 + #if ENABLED(AIR_ASSIST) + #define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin + //#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin + #endif + + //#define SPINDLE_SERVO // A servo converting an angle to spindle power + #ifdef SPINDLE_SERVO + #define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control + #define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle + #endif /** * Speed / Power can be set ('M3 S') and displayed in terms of: * - PWM255 (S0 - S255) * - PERCENT (S0 - S100) * - RPM (S0 - S50000) Best for use with a spindle + * - SERVO (S0 - S180) */ #define CUTTER_POWER_UNIT PWM255 @@ -2905,94 +3506,110 @@ * Speed/Power = (PWMDC / 255 * 100 - SPEED_POWER_INTERCEPT) / SPEED_POWER_SLOPE * PWMDC = (spdpwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) / SPEED_POWER_SLOPE */ - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 5000 // (RPM) - #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM - #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 5000 // (RPM) + #define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM + #define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments) + #endif #else - #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage - #define SPEED_POWER_MIN 0 // (%) 0-100 - #define SPEED_POWER_MAX 100 // (%) 0-100 - #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) + #if ENABLED(SPINDLE_LASER_USE_PWM) + #define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage + #define SPEED_POWER_MIN 0 // (%) 0-100 + #define SPEED_POWER_MAX 100 // (%) 0-100 + #define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments) + #endif - /** - * Enable inline laser power to be handled in the planner / stepper routines. - * Inline power is specified by the I (inline) flag in an M3 command (e.g., M3 S20 I) - * or by the 'S' parameter in G0/G1/G2/G3 moves (see LASER_MOVE_POWER). - * - * This allows the laser to keep in perfect sync with the planner and removes - * the powerup/down delay since lasers require negligible time. - */ - #define LASER_POWER_INLINE + // Define the minimum and maximum test pulse time values for a laser test fire function + #define LASER_TEST_PULSE_MIN 1 // (ms) Used with Laser Control Menu + #define LASER_TEST_PULSE_MAX 999 // (ms) Caution: Menu may not show more than 3 characters - #if ENABLED(LASER_POWER_INLINE) - /** - * Scale the laser's power in proportion to the movement rate. - * - * - Sets the entry power proportional to the entry speed over the nominal speed. - * - Ramps the power up every N steps to approximate the speed trapezoid. - * - Due to the limited power resolution this is only approximate. - */ - #define LASER_POWER_INLINE_TRAPEZOID + #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop - /** - * Continuously calculate the current power (nominal_power * current_rate / nominal_rate). - * Required for accurate power with non-trapezoidal acceleration (e.g., S_CURVE_ACCELERATION). - * This is a costly calculation so this option is discouraged on 8-bit AVR boards. - * - * LASER_POWER_INLINE_TRAPEZOID_CONT_PER defines how many step cycles there are between power updates. If your - * board isn't able to generate steps fast enough (and you are using LASER_POWER_INLINE_TRAPEZOID_CONT), increase this. - * Note that when this is zero it means it occurs every cycle; 1 means a delay wait one cycle then run, etc. - */ - //#define LASER_POWER_INLINE_TRAPEZOID_CONT + /** + * Laser Safety Timeout + * + * The laser should be turned off when there is no movement for a period of time. + * Consider material flammability, cut rate, and G-code order when setting this + * value. Too low and it could turn off during a very slow move; too high and + * the material could ignite. + */ + #define LASER_SAFETY_TIMEOUT_MS 1000 // (ms) - /** - * Stepper iterations between power updates. Increase this value if the board - * can't keep up with the processing demands of LASER_POWER_INLINE_TRAPEZOID_CONT. - * Disable (or set to 0) to recalculate power on every stepper iteration. - */ - //#define LASER_POWER_INLINE_TRAPEZOID_CONT_PER 10 + /** + * Any M3 or G1/2/3/5 command with the 'I' parameter enables continuous inline power mode. + * + * e.g., 'M3 I' enables continuous inline power which is processed by the planner. + * Power is stored in move blocks and applied when blocks are processed by the Stepper ISR. + * + * 'M4 I' sets dynamic mode which uses the current feedrate to calculate a laser power OCR value. + * + * Any move in dynamic mode will use the current feedrate to calculate the laser power. + * Feed rates are set by the F parameter of a move command e.g. G1 X0 Y10 F6000 + * Laser power would be calculated by bit shifting off 8 LSB's. In binary this is div 256. + * The calculation gives us ocr values from 0 to 255, values over F65535 will be set as 255 . + * More refined power control such as compesation for accell/decell will be addressed in future releases. + * + * M5 I clears inline mode and set power to 0, M5 sets the power output to 0 but leaves inline mode on. + */ - /** - * Include laser power in G0/G1/G2/G3/G5 commands with the 'S' parameter - */ - //#define LASER_MOVE_POWER + /** + * Enable M3 commands for laser mode inline power planner syncing. + * This feature enables any M3 S-value to be injected into the block buffers while in + * CUTTER_MODE_CONTINUOUS. The option allows M3 laser power to be commited without waiting + * for a planner syncronization + */ + //#define LASER_POWER_SYNC - #if ENABLED(LASER_MOVE_POWER) - // Turn off the laser on G0 moves with no power parameter. - // If a power parameter is provided, use that instead. - //#define LASER_MOVE_G0_OFF + /** + * Scale the laser's power in proportion to the movement rate. + * + * - Sets the entry power proportional to the entry speed over the nominal speed. + * - Ramps the power up every N steps to approximate the speed trapezoid. + * - Due to the limited power resolution this is only approximate. + */ + //#define LASER_POWER_TRAP + + // + // Laser I2C Ammeter (High precision INA226 low/high side module) + // + //#define I2C_AMMETER + #if ENABLED(I2C_AMMETER) + #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range + #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value + #endif - // Turn off the laser on G28 homing. - //#define LASER_MOVE_G28_OFF + // + // Laser Coolant Flow Meter + // + //#define LASER_COOLANT_FLOW_METER + #if ENABLED(LASER_COOLANT_FLOW_METER) + #define FLOWMETER_PIN 20 // Requires an external interrupt-enabled pin (e.g., RAMPS 2,3,18,19,20,21) + #define FLOWMETER_PPL 5880 // (pulses/liter) Flow meter pulses-per-liter on the input pin + #define FLOWMETER_INTERVAL 1000 // (ms) Flow rate calculation interval in milliseconds + #define FLOWMETER_SAFETY // Prevent running the laser without the minimum flow rate set below + #if ENABLED(FLOWMETER_SAFETY) + #define FLOWMETER_MIN_LITERS_PER_MINUTE 1.5 // (liters/min) Minimum flow required when enabled #endif - - /** - * Inline flag inverted - * - * WARNING: M5 will NOT turn off the laser unless another move - * is done (so G-code files must end with 'M5 I'). - */ - //#define LASER_POWER_INLINE_INVERT - - /** - * Continuously apply inline power. ('M3 S3' == 'G1 S3' == 'M3 S3 I') - * - * The laser might do some weird things, so only enable this - * feature if you understand the implications. - */ - //#define LASER_POWER_INLINE_CONTINUOUS - - #else - - #define SPINDLE_LASER_POWERUP_DELAY 50 // (ms) Delay to allow the spindle/laser to come up to speed/power - #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop - #endif + #endif -#endif +#endif // SPINDLE_FEATURE || LASER_FEATURE + +/** + * Synchronous Laser Control with M106/M107 + * + * Marlin normally applies M106/M107 fan speeds at a time "soon after" processing + * a planner block. This is too inaccurate for a PWM/TTL laser attached to the fan + * header (as with some add-on laser kits). Enable this option to set fan/laser + * speeds with much more exact timing for improved print fidelity. + * + * NOTE: This option sacrifices some cooling fan speed options. + */ +//#define LASER_SYNCHRONOUS_M106_M107 /** * Coolant Control @@ -3009,6 +3626,8 @@ #define COOLANT_FLOOD_INVERT false // Set "true" if the on/off function is reversed #endif +// @section filament width + /** * Filament Width Sensor * @@ -3042,6 +3661,8 @@ //#define FILAMENT_LCD_DISPLAY #endif +// @section power + /** * Power Monitor * Monitor voltage (V) and/or current (A), and -when possible- power (W) @@ -3053,13 +3674,31 @@ */ //#define POWER_MONITOR_CURRENT // Monitor the system current //#define POWER_MONITOR_VOLTAGE // Monitor the system voltage -#if EITHER(POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE) - #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! - #define POWER_MONITOR_CURRENT_OFFSET -1 // Offset value for current sensors with linear function output - #define POWER_MONITOR_VOLTS_PER_VOLT 0.11786 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! + +#if ENABLED(POWER_MONITOR_CURRENT) + #define POWER_MONITOR_VOLTS_PER_AMP 0.05000 // Input voltage to the MCU analog pin per amp - DO NOT apply more than ADC_VREF! + #define POWER_MONITOR_CURRENT_OFFSET 0 // Offset (in amps) applied to the calculated current #define POWER_MONITOR_FIXED_VOLTAGE 13.6 // Voltage for a current sensor with no voltage sensor (for power display) #endif +#if ENABLED(POWER_MONITOR_VOLTAGE) + #define POWER_MONITOR_VOLTS_PER_VOLT 0.077933 // Input voltage to the MCU analog pin per volt - DO NOT apply more than ADC_VREF! + #define POWER_MONITOR_VOLTAGE_OFFSET 0 // Offset (in volts) applied to the calculated voltage +#endif + +// @section safety + +/** + * Stepper Driver Anti-SNAFU Protection + * + * If the SAFE_POWER_PIN is defined for your board, Marlin will check + * that stepper drivers are properly plugged in before applying power. + * Disable protection if your stepper drivers don't support the feature. + */ +//#define DISABLE_DRIVER_SAFE_POWER_PROTECT + +// @section cnc + /** * CNC Coordinate Systems * @@ -3068,10 +3707,26 @@ */ //#define CNC_COORDINATE_SYSTEMS +// @section reporting + +/** + * Auto-report fan speed with M123 S + * Requires fans with tachometer pins + */ +//#define AUTO_REPORT_FANS + /** * Auto-report temperatures with M155 S */ #define AUTO_REPORT_TEMPERATURES +#if ENABLED(AUTO_REPORT_TEMPERATURES) && TEMP_SENSOR_REDUNDANT + //#define AUTO_REPORT_REDUNDANT // Include the "R" sensor in the auto-report +#endif + +/** + * Auto-report position with M154 S + */ +//#define AUTO_REPORT_POSITION /** * Include capabilities in M115 output @@ -3081,6 +3736,8 @@ //#define M115_GEOMETRY_REPORT #endif +// @section security + /** * Expected Printer Check * Add the M16 G-code to compare a string to the MACHINE_NAME. @@ -3088,6 +3745,8 @@ */ //#define EXPECTED_PRINTER_CHECK +// @section volumetrics + /** * Disable all Volumetric extrusion options */ @@ -3116,14 +3775,7 @@ #endif #endif -/** - * Enable this option for a leaner build of Marlin that removes all - * workspace offsets, simplifying coordinate transformations, leveling, etc. - * - * - M206 and M428 are disabled. - * - G92 will revert to its behavior from Marlin 1.0. - */ -//#define NO_WORKSPACE_OFFSETS +// @section reporting // Extra options for the M114 "Current Position" report //#define M114_DETAIL // Use 'M114` for details to check planner calculations @@ -3132,17 +3784,10 @@ //#define REPORT_FAN_CHANGE // Report the new fan speed when changed by M106 (and others) -/** - * Set the number of proportional font spaces required to fill up a typical character space. - * This can help to better align the output of commands like `G29 O` Mesh Output. - * - * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. - * Otherwise, adjust according to your client and font. - */ -#define PROPORTIONAL_FONT_RATIO 1.0 +// @section gcode /** - * Spend 28 bytes of SRAM to optimize the GCode parser + * Spend 28 bytes of SRAM to optimize the G-code parser */ #define FASTER_GCODE_PARSER @@ -3150,10 +3795,23 @@ //#define GCODE_QUOTED_STRINGS // Support for quoted string parameters #endif +// Support for MeatPack G-code compression (https://github.com/scottmudge/OctoPrint-MeatPack) +//#define MEATPACK_ON_SERIAL_PORT_1 +//#define MEATPACK_ON_SERIAL_PORT_2 + //#define GCODE_CASE_INSENSITIVE // Accept G-code sent to the firmware in lowercase //#define REPETIER_GCODE_M360 // Add commands originally from Repetier FW +/** + * Enable this option for a leaner build of Marlin that removes all + * workspace offsets, simplifying coordinate transformations, leveling, etc. + * + * - M206 and M428 are disabled. + * - G92 will revert to its behavior from Marlin 1.0. + */ +//#define NO_WORKSPACE_OFFSETS + /** * CNC G-code options * Support CNC-style G-code dialects used by laser cutters, drawing machine cams, etc. @@ -3169,6 +3827,8 @@ //#define VARIABLE_G0_FEEDRATE // The G0 feedrate is set by F in G0 motion mode #endif +// @section gcode + /** * Startup commands * @@ -3189,31 +3849,109 @@ #endif /** - * User-defined menu items that execute custom GCode + * User-defined menu items to run custom G-code. + * Up to 25 may be defined, but the actual number is LCD-dependent. */ -//#define CUSTOM_USER_MENUS -#if ENABLED(CUSTOM_USER_MENUS) - //#define CUSTOM_USER_MENU_TITLE "Custom Commands" - #define USER_SCRIPT_DONE "M117 User Script Done" - #define USER_SCRIPT_AUDIBLE_FEEDBACK - //#define USER_SCRIPT_RETURN // Return to status screen after a script - #define USER_DESC_1 "Home & UBL Info" - #define USER_GCODE_1 "G28\nG29 W" +// @section custom main menu + +// Custom Menu: Main Menu +//#define CUSTOM_MENU_MAIN +#if ENABLED(CUSTOM_MENU_MAIN) + //#define CUSTOM_MENU_MAIN_TITLE "Custom Commands" + #define CUSTOM_MENU_MAIN_SCRIPT_DONE "M117 User Script Done" + #define CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK + //#define CUSTOM_MENU_MAIN_SCRIPT_RETURN // Return to status screen after a script + #define CUSTOM_MENU_MAIN_ONLY_IDLE // Only show custom menu when the machine is idle + + #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info" + #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W" + //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + + #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL + #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + //#define MAIN_MENU_ITEM_2_CONFIRM + + //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL + //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + //#define MAIN_MENU_ITEM_3_CONFIRM + + //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level" + //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + //#define MAIN_MENU_ITEM_4_CONFIRM + + //#define MAIN_MENU_ITEM_5_DESC "Home & Info" + //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503" + //#define MAIN_MENU_ITEM_5_CONFIRM +#endif + +// @section custom config menu - #define USER_DESC_2 "Preheat for " PREHEAT_1_LABEL - #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) +// Custom Menu: Configuration Menu +//#define CUSTOM_MENU_CONFIG +#if ENABLED(CUSTOM_MENU_CONFIG) + //#define CUSTOM_MENU_CONFIG_TITLE "Custom Commands" + #define CUSTOM_MENU_CONFIG_SCRIPT_DONE "M117 Wireless Script Done" + #define CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK + //#define CUSTOM_MENU_CONFIG_SCRIPT_RETURN // Return to status screen after a script + #define CUSTOM_MENU_CONFIG_ONLY_IDLE // Only show custom menu when the machine is idle - #define USER_DESC_3 "Preheat for " PREHEAT_2_LABEL - #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + #define CONFIG_MENU_ITEM_1_DESC "Wifi ON" + #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678" + //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action - #define USER_DESC_4 "Heat Bed/Home/Level" - #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON" + #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678" + //#define CONFIG_MENU_ITEM_2_CONFIRM - #define USER_DESC_5 "Home & Info" - #define USER_GCODE_5 "G28\nM503" + //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF" + //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678" + //#define CONFIG_MENU_ITEM_3_CONFIRM + + //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????" + //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????" + //#define CONFIG_MENU_ITEM_4_CONFIRM + + //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????" + //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????" + //#define CONFIG_MENU_ITEM_5_CONFIRM +#endif + +// @section custom buttons + +/** + * User-defined buttons to run custom G-code. + * Up to 25 may be defined. + */ +//#define CUSTOM_USER_BUTTONS +#if ENABLED(CUSTOM_USER_BUTTONS) + //#define BUTTON1_PIN -1 + #if PIN_EXISTS(BUTTON1) + #define BUTTON1_HIT_STATE LOW // State of the triggered button. NC=LOW. NO=HIGH. + #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing? + #define BUTTON1_GCODE "G28" + #define BUTTON1_DESC "Homing" // Optional string to set the LCD status + #endif + + //#define BUTTON2_PIN -1 + #if PIN_EXISTS(BUTTON2) + #define BUTTON2_HIT_STATE LOW + #define BUTTON2_WHEN_PRINTING false + #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL + #endif + + //#define BUTTON3_PIN -1 + #if PIN_EXISTS(BUTTON3) + #define BUTTON3_HIT_STATE LOW + #define BUTTON3_WHEN_PRINTING false + #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL + #endif #endif +// @section host + /** * Host Action Commands * @@ -3230,16 +3968,26 @@ */ //#define HOST_ACTION_COMMANDS #if ENABLED(HOST_ACTION_COMMANDS) - //#define HOST_PROMPT_SUPPORT - //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start + //#define HOST_PAUSE_M76 // Tell the host to pause in response to M76 + //#define HOST_PROMPT_SUPPORT // Initiate host prompts to get user feedback + #if ENABLED(HOST_PROMPT_SUPPORT) + //#define HOST_STATUS_NOTIFICATIONS // Send some status messages to the host as notifications + #endif + //#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start + //#define HOST_SHUTDOWN_MENU_ITEM // Add a menu item that tells the host to shut down #endif +// @section extras + /** * Cancel Objects * * Implement M486 to allow Marlin to skip objects */ //#define CANCEL_OBJECTS +#if ENABLED(CANCEL_OBJECTS) + #define CANCEL_OBJECTS_REPORTING // Emit the current object as a status message +#endif /** * I2C position encoders for closed loop control. @@ -3252,6 +4000,7 @@ * Alternative Supplier: https://reliabuild3d.com/ * * Reliabuild encoders have been modified to improve reliability. + * @section i2c encoders */ //#define I2C_POSITION_ENCODERS @@ -3316,13 +4065,14 @@ */ #define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks. - // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. + // Use a rolling average to identify persistent errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE #endif // I2C_POSITION_ENCODERS /** * Analog Joystick(s) + * @section joystick */ //#define JOYSTICK #if ENABLED(JOYSTICK) @@ -3342,11 +4092,43 @@ //#define JOYSTICK_DEBUG #endif +/** + * Mechanical Gantry Calibration + * Modern replacement for the Průša TMC_Z_CALIBRATION. + * Adds capability to work with any adjustable current drivers. + * Implemented as G34 because M915 is deprecated. + * @section calibrate + */ +//#define MECHANICAL_GANTRY_CALIBRATION +#if ENABLED(MECHANICAL_GANTRY_CALIBRATION) + #define GANTRY_CALIBRATION_CURRENT 600 // Default calibration current in ma + #define GANTRY_CALIBRATION_EXTRA_HEIGHT 15 // Extra distance in mm past Z_###_POS to move + #define GANTRY_CALIBRATION_FEEDRATE 500 // Feedrate for correction move + //#define GANTRY_CALIBRATION_TO_MIN // Enable to calibrate Z in the MIN direction + + //#define GANTRY_CALIBRATION_SAFE_POSITION XY_CENTER // Safe position for nozzle + //#define GANTRY_CALIBRATION_XY_PARK_FEEDRATE 3000 // XY Park Feedrate - MMM + //#define GANTRY_CALIBRATION_COMMANDS_PRE "" + #define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position +#endif + +/** + * Instant freeze / unfreeze functionality + * Potentially useful for emergency stop that allows being resumed. + * @section interface + */ +//#define FREEZE_FEATURE +#if ENABLED(FREEZE_FEATURE) + //#define FREEZE_PIN 41 // Override the default (KILL) pin here + #define FREEZE_STATE LOW // State of pin indicating freeze +#endif + /** * MAX7219 Debug Matrix * * Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display. * Requires 3 signal wires. Some useful debug options are included to demonstrate its usage. + * @section debug matrix */ //#define MAX7219_DEBUG #if ENABLED(MAX7219_DEBUG) @@ -3359,7 +4141,8 @@ #define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain. #define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°) // connector at: right=0 bottom=-90 top=90 left=180 - //#define MAX7219_REVERSE_ORDER // The individual LED matrix units may be in reversed order + //#define MAX7219_REVERSE_ORDER // The order of the LED matrix units may be reversed + //#define MAX7219_REVERSE_EACH // The LEDs in each matrix unit row may be reversed //#define MAX7219_SIDE_BY_SIDE // Big chip+matrix boards can be chained side-by-side /** @@ -3367,31 +4150,42 @@ * If you add more debug displays, be careful to avoid conflicts! */ #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning - #define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row - #define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_HEAD 2 // Show the planner queue head position on this and the next LED matrix row + #define MAX7219_DEBUG_PLANNER_TAIL 4 // Show the planner queue tail position on this and the next LED matrix row #define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row // If you experience stuttering, reboots, etc. this option can reveal how // tweaks made to the configuration are affecting the printer in real-time. + #define MAX7219_DEBUG_PROFILE 6 // Display the fraction of CPU time spent in profiled code on this LED matrix + // row. By default idle() is profiled so this shows how "idle" the processor is. + // See class CodeProfiler. #endif /** * NanoDLP Sync support * - * Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp" - * string to enable synchronization with DLP projector exposure. This change will allow to use - * [[WaitForDoneMessage]] instead of populating your gcode with M400 commands + * Support for Synchronized Z moves when used with NanoDLP. G0/G1 axis moves will + * output a "Z_move_comp" string to enable synchronization with DLP projector exposure. + * This feature allows you to use [[WaitForDoneMessage]] instead of M400 commands. + * @section nanodlp */ //#define NANODLP_Z_SYNC #if ENABLED(NANODLP_Z_SYNC) - //#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move. - // Default behavior is limited to Z axis only. + //#define NANODLP_ALL_AXIS // Send a "Z_move_comp" report for any axis move (not just Z). +#endif + +/** + * Ethernet. Use M552 to enable and set the IP address. + * @section network + */ +#if HAS_ETHERNET + #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xF0, 0x0D } // A MAC address unique to your network #endif /** * WiFi Support (Espressif ESP32 WiFi) */ -//#define WIFISUPPORT // Marlin embedded WiFi managenent +//#define WIFISUPPORT // Marlin embedded WiFi management //#define ESP3D_WIFISUPPORT // ESP3D Library WiFi management (https://github.com/luc-github/ESP3DLib) #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT) @@ -3410,17 +4204,29 @@ //#include "Configuration_Secure.h" // External file with WiFi SSID / Password #endif +// @section multi-material + /** - * Pruša Multi-Material Unit v2 + * Průša Multi-Material Unit (MMU) * Enable in Configuration.h + * + * These devices allow a single stepper driver on the board to drive + * multi-material feeders with any number of stepper motors. */ -#if ENABLED(PRUSA_MMU2) - +#if HAS_PRUSA_MMU1 + /** + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + * + * Override the default DIO selector pins here, if needed. + * Some pins files may provide defaults for these pins. + */ + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 inputs + //#define E_MUX2_PIN 44 // Needed for 5 to 8 inputs +#elif HAS_PRUSA_MMU2 // Serial port used for communication with MMU2. - // For AVR enable the UART port used for the MMU. (e.g., internalSerial) - // For 32-bit boards check your HAL for available serial ports. (e.g., Serial2) - #define INTERNAL_SERIAL_PORT 2 - #define MMU2_SERIAL internalSerial + #define MMU2_SERIAL_PORT 2 // Use hardware reset for MMU if a pin is defined for it //#define MMU2_RST_PIN 23 @@ -3433,9 +4239,9 @@ // Add an LCD menu for MMU2 //#define MMU2_MENUS - #if ENABLED(MMU2_MENUS) + #if EITHER(MMU2_MENUS, HAS_PRUSA_MMU2S) // Settings for filament load / unload from the LCD menu. - // This is for Pruša MK3-style extruders. Customize for your hardware. + // This is for Průša MK3-style extruders. Customize for your hardware. #define MMU2_FILAMENTCHANGE_EJECT_FEED 80.0 #define MMU2_LOAD_TO_NOZZLE_SEQUENCE \ { 7.2, 1145 }, \ @@ -3458,29 +4264,12 @@ { -50.0, 2000 } #endif - /** - * MMU Extruder Sensor - * - * Support for a Pruša (or other) IR Sensor to detect filament near the extruder - * and make loading more reliable. Suitable for an extruder equipped with a filament - * sensor less than 38mm from the gears. - * - * During loading the extruder will stop when the sensor is triggered, then do a last - * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. - * If all attempts fail, a filament runout will be triggered. - */ - //#define MMU_EXTRUDER_SENSOR - #if ENABLED(MMU_EXTRUDER_SENSOR) - #define MMU_LOADING_ATTEMPTS_NR 5 //max. number of attempts to load filament if first load fail - #endif - /** * Using a sensor like the MMU2S * This mode requires a MK3S extruder with a sensor at the extruder idler, like the MMU2S. * See https://help.prusa3d.com/en/guide/3b-mk3s-mk2-5s-extruder-upgrade_41560, step 11 */ - //#define PRUSA_MMU2_S_MODE - #if ENABLED(PRUSA_MMU2_S_MODE) + #if HAS_PRUSA_MMU2S #define MMU2_C0_RETRY 5 // Number of retries (total time = timeout*retries) #define MMU2_CAN_LOAD_FEEDRATE 800 // (mm/min) @@ -3496,14 +4285,33 @@ #define MMU2_CAN_LOAD_INCREMENT_SEQUENCE \ { -MMU2_CAN_LOAD_INCREMENT, MMU2_CAN_LOAD_FEEDRATE } + #else + + /** + * MMU1 Extruder Sensor + * + * Support for a Průša (or other) IR Sensor to detect filament near the extruder + * and make loading more reliable. Suitable for an extruder equipped with a filament + * sensor less than 38mm from the gears. + * + * During loading the extruder will stop when the sensor is triggered, then do a last + * move up to the gears. If no filament is detected, the MMU2 can make some more attempts. + * If all attempts fail, a filament runout will be triggered. + */ + //#define MMU_EXTRUDER_SENSOR + #if ENABLED(MMU_EXTRUDER_SENSOR) + #define MMU_LOADING_ATTEMPTS_NR 5 // max. number of attempts to load filament if first load fail + #endif + #endif //#define MMU2_DEBUG // Write debug info to serial output -#endif // PRUSA_MMU2 +#endif // HAS_PRUSA_MMU2 /** * Advanced Print Counter settings + * @section stats */ #if ENABLED(PRINTCOUNTER) #define SERVICE_WARNING_BUZZES 3 @@ -3523,10 +4331,42 @@ // //#define M100_FREE_MEMORY_WATCHER +// +// M42 - Set pin states +// +//#define DIRECT_PIN_CONTROL + // // M43 - display pin status, toggle pins, watch pins, watch endstops & toggle LED, test servo probe // //#define PINS_DEBUGGING +// Enable Tests that will run at startup and produce a report +//#define MARLIN_TEST_BUILD + // Enable Marlin dev mode which adds some special commands -//#define MARLIN_DEV_MODE \ No newline at end of file +//#define MARLIN_DEV_MODE + +#if ENABLED(MARLIN_DEV_MODE) + /** + * D576 - Buffer Monitoring + * To help diagnose print quality issues stemming from empty command buffers. + */ + //#define BUFFER_MONITORING +#endif + +/** + * Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial. + * When running in the debugger it will break for debugging. This is useful to help understand + * a crash from a remote location. Requires ~400 bytes of SRAM and 5Kb of flash. + */ +//#define POSTMORTEM_DEBUGGING + +/** + * Software Reset options + */ +//#define SOFT_RESET_VIA_SERIAL // 'KILL' and '^X' commands will soft-reset the controller +//#define SOFT_RESET_ON_KILL // Use a digital button to soft-reset the controller after KILL + +// Report uncleaned reset reason from register r2 instead of MCUSR. Supported by Optiboot on AVR. +//#define OPTIBOOT_RESET_REASON From d2d9fe5259b22cc17d44eb54b705e0ce6002c2f2 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 16:05:41 +0200 Subject: [PATCH 09/83] - removed some deprecated stuff from the LPC1768 platform that made compilation fail --- .../HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index 5312bc29a8e8..f69941ad81f5 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -63,11 +63,6 @@ #include "../../shared/HAL_SPI.h" #include "../../shared/Delay.h" -void spiBegin(); -void spiInit(uint8_t spiRate, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); -void spiSend(uint8_t b); -void spiSend(const uint8_t *buf, size_t n); - static uint8_t rs_last_state = 255; static void u8g_com_LPC1768_st7920_write_byte_hw_spi(uint8_t rs, uint8_t val) { From 24a92fce44d071e7c657ad287355e5ef081c50a2 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 16:09:24 +0200 Subject: [PATCH 10/83] - fixed a typo in the HAL SPI for DUE --- Marlin/src/HAL/DUE/HAL_SPI.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 3c28879170b6..45c81fa91b87 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -883,7 +883,7 @@ // Default to slowest rate if not specified) // Also sets U8G SPI rate to 4MHz and the SPI mode to 3 - if (spiRate == SPI_RATE_DEFAULT) + if (spiRate == SPI_SPEED_DEFAULT) spiRate = 6; // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz @@ -915,7 +915,7 @@ // TODO? } - void spiBegin() { spiInit(SPI_RATE_DEFAULT); } + void spiBegin() { spiInit(SPI_SPEED_DEFAULT); } static uint8_t spiTransfer(uint8_t data) { WHILE_TX(0); From 63711269e7d46643bd0777bcc7b11b386c73153e Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 16:30:26 +0200 Subject: [PATCH 11/83] - limit the Arduino DUE software SPI layer to just the standard SD card SPI pins (for now?) --- Marlin/src/HAL/DUE/HAL_SPI.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index 45c81fa91b87..efb06aba58f8 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -517,8 +517,8 @@ } _SS_WRITE(HIGH); - WRITE(( hint_mosi != -1 ) ? hint_mosi : SD_MOSI_PIN, HIGH); - WRITE(( hint_sck != -1 ) ? hint_sck : SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, HIGH); + WRITE(SD_SCK_PIN, LOW); } void spiClose() {} From 998a5133c94f51d123c098cbafc7b544720086e0 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 28 Oct 2022 16:38:26 +0200 Subject: [PATCH 12/83] - fixed a missing preprocessor macro in the SD card reliability update (the standard SD card read block retry count) --- Marlin/src/sd/Sd2Card.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 1784b589842a..fc609f11e67a 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -40,6 +40,10 @@ #include "../MarlinCore.h" +#ifndef SD_RETRY_COUNT + #define SD_RETRY_COUNT 3 +#endif + #if ENABLED(SD_CHECK_AND_RETRY) static bool crcSupported = true; From 1d82c373a0bf657f7f09f2a9f7e8f176df24fd34 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 29 Oct 2022 19:28:52 -0500 Subject: [PATCH 13/83] cleanup, refer directly to "SPI" --- Marlin/Configuration_adv.h | 6 +- Marlin/src/HAL/AVR/HAL_SPI.cpp | 31 +- Marlin/src/HAL/DUE/HAL_SPI.cpp | 107 +++--- Marlin/src/HAL/DUE/inc/SanityCheck.h | 2 +- Marlin/src/HAL/ESP32/HAL_SPI.cpp | 6 +- Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 36 +- Marlin/src/HAL/LPC1768/inc/SanityCheck.h | 2 +- Marlin/src/HAL/LPC1768/include/SPI.h | 21 +- Marlin/src/HAL/LPC1768/tft/tft_spi.h | 4 +- Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 10 +- Marlin/src/HAL/STM32/HAL_SPI.cpp | 20 +- Marlin/src/HAL/STM32/MarlinSPI.cpp | 8 +- Marlin/src/HAL/STM32/msc_sd.cpp | 46 +-- Marlin/src/HAL/STM32/sdio.cpp | 18 +- Marlin/src/HAL/STM32/tft/tft_fsmc.h | 4 +- Marlin/src/HAL/STM32/tft/tft_ltdc.h | 4 +- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 335 ++++++------------ Marlin/src/HAL/STM32/tft/tft_spi.h | 24 +- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 186 +++------- Marlin/src/HAL/STM32/tft/xpt2046.h | 4 +- Marlin/src/HAL/STM32F1/HAL_SPI.cpp | 6 +- Marlin/src/HAL/STM32F1/SPI.cpp | 3 +- Marlin/src/HAL/STM32F1/eeprom_wired.cpp | 4 +- Marlin/src/HAL/STM32F1/sdio.cpp | 11 +- Marlin/src/HAL/STM32F1/tft/tft_fsmc.h | 4 +- Marlin/src/HAL/STM32F1/tft/tft_spi.h | 4 +- Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 6 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 6 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 6 +- Marlin/src/HAL/shared/HAL_SPI.h | 4 +- Marlin/src/feature/tmc_util.h | 16 +- Marlin/src/inc/Conditionals_LCD.h | 8 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 5 +- Marlin/src/lcd/tft_io/tft_io.h | 2 +- Marlin/src/module/stepper/trinamic.cpp | 8 +- Marlin/src/module/temperature.cpp | 10 +- Marlin/src/pins/linux/pins_RAMPS_LINUX.h | 6 +- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 6 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 9 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 6 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 6 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 6 +- Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 6 +- .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 6 +- .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 6 +- Marlin/src/pins/lpc1769/pins_FLY_CDY.h | 6 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 6 +- Marlin/src/pins/ramps/pins_RAMPS.h | 6 +- Marlin/src/pins/ramps/pins_RAMPS_S_12.h | 6 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 24 +- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 6 +- Marlin/src/pins/sam/pins_ARCHIM2.h | 6 +- Marlin/src/pins/samd/pins_RAMPS_144.h | 6 +- Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h | 6 +- .../src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h | 24 +- Marlin/src/pins/stm32f1/pins_FLY_MINI.h | 6 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h | 6 +- .../pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h | 6 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 6 +- .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 112 +++--- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 6 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 6 +- Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h | 6 +- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 6 +- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 6 +- .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 6 +- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 6 +- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 6 +- Marlin/src/pins/stm32f4/pins_FLYF407ZG.h | 6 +- Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h | 6 +- Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h | 6 +- .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 9 +- .../src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h | 9 +- .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 6 +- Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h | 6 +- .../src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h | 6 +- .../src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h | 6 +- Marlin/src/pins/stm32f4/pins_RUMBA32_common.h | 6 +- .../pins/stm32h7/pins_BTT_SKR_SE_BX_common.h | 6 +- .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 6 +- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 6 +- 81 files changed, 569 insertions(+), 829 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 9a54b10b82b1..cd66bf919bd8 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3086,9 +3086,9 @@ * but you can override or define them here. */ //#define TMC_USE_SW_SPI - //#define TMC_SW_MOSI -1 - //#define TMC_SW_MISO -1 - //#define TMC_SW_SCK -1 + //#define TMC_SPI_MOSI -1 + //#define TMC_SPI_MISO -1 + //#define TMC_SPI_SCK -1 // @section tmc/serial diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 6d925097f74b..64fade50004a 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -49,6 +49,8 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } +void spiClose() { /* do nothing */ } + #if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ @@ -64,7 +66,7 @@ void spiBegin() { * Initialize hardware SPI * Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6] */ - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore SPI pin hints. // See avr processor documentation @@ -78,17 +80,13 @@ void spiBegin() { ); SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1); - SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X); - } - - void spiClose() { - // nop. + SPSR = spiRate & 1 || spiRate == SPI_SPEED_6 ? 0 : _BV(SPI2X); } /** SPI receive a byte */ uint8_t spiRec() { SPDR = 0xFF; - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } return SPDR; } @@ -97,34 +95,33 @@ void spiBegin() { if (nbyte-- == 0) return; SPDR = 0xFF; for (uint16_t i = 0; i < nbyte; i++) { - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } buf[i] = SPDR; SPDR = 0xFF; } - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } buf[nbyte] = SPDR; } /** SPI send a byte */ void spiSend(uint8_t b) { SPDR = b; - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } } /** SPI send block */ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } SPDR = buf[i]; - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } SPDR = buf[i + 1]; } - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + while (!TEST(SPSR, SPIF)) { /* do nothing */ } } - - /** begin spi transaction */ + /** Begin SPI transaction */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // Based on Arduino SPI library // Clock settings are defined as follows. Note that this shows SPI2X @@ -179,7 +176,6 @@ void spiBegin() { SPSR = clockDiv | 0x01; } - #else // SOFTWARE_SPI || FORCE_SOFT_SPI // ------------------------ @@ -189,8 +185,7 @@ void spiBegin() { // nop to tune soft SPI timing #define nop asm volatile ("\tnop\n") - void spiInit(uint8_t, int, int, int, int) { /* do nothing */ } - void spiClose() { /* do nothing */ } + void spiInit(uint8_t, const int=-1, const int=-1, const int=-1, const int=-1) { /* do nothing */ } // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index efb06aba58f8..21df5d445266 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -493,7 +493,7 @@ * 5 : 250 - 312 kHz * 6 : 125 - 156 kHz */ - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { switch (spiRate) { case 0: spiTransferTx = (pfnSpiTransfer)spiTransferTx0; @@ -521,7 +521,7 @@ WRITE(SD_SCK_PIN, LOW); } - void spiClose() {} + void spiClose() { /* do nothing */ } /** Begin SPI transaction, set clock, bit order, data mode */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { @@ -539,19 +539,21 @@ #define FLUSH_TX() do{ WHILE_RX(1) SPI0->SPI_RDR; }while(0) #if 0 + // ------------------------ + // Hardware SPI + // https://github.com/arduino/ArduinoCore-sam/blob/master/libraries/SPI/src/SPI.h + // ------------------------ + #include + static SPISettings spiConfig; // Generic SPI implementation (test me please) static bool _has_spi_pins = false; static int _spi_pin_cs; // all SPI pins are tied together (CS, MISO, MOSI, SCK) - // ------------------------ - // hardware SPI - // https://github.com/arduino/ArduinoCore-sam/blob/master/libraries/SPI/src/SPI.h - // ------------------------ void spiBegin() {} - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Use datarates Marlin uses uint32_t clock; switch (spiRate) { @@ -566,87 +568,79 @@ } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); // We ignore all pins other than chip-select because they have to be tied together anyway. - if (hint_cs != -1) - { - sdSPI.begin(hint_cs); + if (hint_cs != -1) { + SPI.begin(hint_cs); _spi_pin_cs = hint_cs; _has_spi_pins = true; } - else - { - sdSPI.begin(); + else { + SPI.begin(); _has_spi_pins = false; } } void spiClose() { if (_has_spi_pins) - sdSPI.end(_spi_pin_cs); + SPI.end(_spi_pin_cs); else - sdSPI.end(); + SPI.end(); _has_spi_pins = false; _spi_pin_cs = -1; } uint8_t spiRec() { if (_has_spi_pins) - sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + SPI.beginTransaction(_spi_pin_cs, spiConfig); else - sdSPI.beginTransaction(spiConfig); - uint8_t returnByte = sdSPI.transfer(0xFF); + SPI.beginTransaction(spiConfig); + uint8_t returnByte = SPI.transfer(0xFF); if (_has_spi_pins) - sdSPI.endTransaction(_spi_pin_cs); + SPI.endTransaction(_spi_pin_cs); else - sdSPI.endTransaction(); + SPI.endTransaction(); return returnByte; } void spiRead(uint8_t *buf, uint16_t nbyte) { if (nbyte == 0) return; memset(buf, 0xFF, nbyte); - if (_has_spi_pins == false) - { - sdSPI.beginTransaction(spiConfig); - sdSPI.transfer(buf, nbyte); + if (_has_spi_pins == false) { + SPI.beginTransaction(spiConfig); + SPI.transfer(buf, nbyte); } - else - { - sdSPI.beginTransaction(_spi_pin_cs, spiConfig); - sdSPI.transfer(_spi_pin_cs, buf, nbyte); + else { + SPI.beginTransaction(_spi_pin_cs, spiConfig); + SPI.transfer(_spi_pin_cs, buf, nbyte); } // There is no pin-specific endTransaction method. - sdSPI.endTransaction(); + SPI.endTransaction(); } void spiSend(uint8_t b) { - if (_has_spi_pins) - { - sdSPI.beginTransaction(_spi_pin_cs, spiConfig); - sdSPI.transfer(_spi_pin_cs, b); + if (_has_spi_pins) { + SPI.beginTransaction(_spi_pin_cs, spiConfig); + SPI.transfer(_spi_pin_cs, b); } - else - { - sdSPI.beginTransaction(spiConfig); - sdSPI.transfer(b); + else { + SPI.beginTransaction(spiConfig); + SPI.transfer(b); } - sdSPI.endTransaction(); + SPI.endTransaction(); } // SD-card specific. void spiSendBlock(uint8_t token, const uint8_t *buf) { - if (_has_spi_pins) - { - sdSPI.beginTransaction(_spi_pin_cs, spiConfig); - sdSPI.transfer(_spi_pin_cs, token); - sdSPI.transfer(_spi_pin_cs, (uint8_t*)buf, 512); + if (_has_spi_pins) { + SPI.beginTransaction(_spi_pin_cs, spiConfig); + SPI.transfer(_spi_pin_cs, token); + SPI.transfer(_spi_pin_cs, (uint8_t*)buf, 512); } - else - { - sdSPI.beginTransaction(spiConfig); - sdSPI.transfer(token); - sdSPI.transfer(buf, 512); + else { + SPI.beginTransaction(spiConfig); + SPI.transfer(token); + SPI.transfer(buf, 512); } - sdSPI.endTransaction(); + SPI.endTransaction(); } #endif @@ -660,14 +654,14 @@ // ------------------------ static bool spiInitialized = false; - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // I guess ignore the hinted pins? if (spiInitialized) return; // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 }; - if (spiRate > 6) spiRate = 1; + if (spiRate > SPI_SPEED_6) spiRate = SPI_HALF_SPEED; // Set SPI mode 1, clock, select not active after transfer, with delay between transfers SPI_ConfigureNPCS(SPI0, SPI_CHAN_DAC, @@ -878,17 +872,16 @@ * display to use software SPI. */ - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // We ignore the hinted pins? Why don't we use the standard, already implemented SPI library? // Default to slowest rate if not specified) // Also sets U8G SPI rate to 4MHz and the SPI mode to 3 - if (spiRate == SPI_SPEED_DEFAULT) - spiRate = 6; + if (spiRate == SPI_SPEED_DEFAULT) spiRate = SPI_SPEED_6; // 8.4 MHz, 4 MHz, 2 MHz, 1 MHz, 0.5 MHz, 0.329 MHz, 0.329 MHz constexpr int spiDivider[] = { 10, 21, 42, 84, 168, 255, 255 }; - if (spiRate > 6) spiRate = 1; + if (spiRate > SPI_SPEED_6) spiRate = SPI_HALF_SPEED; // Enable PIOA and SPI0 REG_PMC_PCER0 = (1UL << ID_PIOA) | (1UL << ID_SPI0); @@ -911,9 +904,7 @@ SPI0->SPI_CSR[0] = SPI_CSR_SCBR(spiDivider[1]) | SPI_CSR_CSAAT | SPI_MODE_3_DUE_HW; // U8G default to 4MHz } - void spiClose() { - // TODO? - } + void spiClose() { /* do nothing */ } void spiBegin() { spiInit(SPI_SPEED_DEFAULT); } diff --git a/Marlin/src/HAL/DUE/inc/SanityCheck.h b/Marlin/src/HAL/DUE/inc/SanityCheck.h index 1de13600e7f9..996404a7d04c 100644 --- a/Marlin/src/HAL/DUE/inc/SanityCheck.h +++ b/Marlin/src/HAL/DUE/inc/SanityCheck.h @@ -64,7 +64,7 @@ * Usually the hardware SPI pins are only available to the LCD. This makes the DUE hard SPI used at the same time * as the TMC2130 soft SPI the most common setup. */ -#define _IS_HW_SPI(P) (defined(TMC_SW_##P) && (TMC_SPI_##P == SD_MOSI_PIN || TMC_SPI_##P == SD_MISO_PIN || TMC_SPI_##P == SD_SCK_PIN)) +#define _IS_HW_SPI(P) (defined(TMC_SPI_##P) && (TMC_SPI_##P == SD_MOSI_PIN || TMC_SPI_##P == SD_MISO_PIN || TMC_SPI_##P == SD_SCK_PIN)) #if ENABLED(SDSUPPORT) && HAS_DRIVER(TMC2130) #if ENABLED(TMC_USE_SW_SPI) diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index daeb6676b28e..96bca5e7a645 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -58,7 +58,7 @@ void spiBegin() { #endif } -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { uint32_t clock; switch (spiRate) { @@ -77,9 +77,7 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi SPI.begin(hint_sck, hint_miso, hint_mosi, hint_cs); } -void spiClose() { - SPI.end(); -} +void spiClose() { SPI.end(); } uint8_t spiRec() { SPI.beginTransaction(spiConfig); diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 800e23847dd9..debf11ed0e5e 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -76,16 +76,14 @@ swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); } - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - SPI_speed = - swSpiInit(spiRate, - ( hint_sck != -1 ) ? hint_sck : SD_SCK_PIN, - ( hint_mosi != -1 ) ? hint_mosi : SD_MOSI_PIN - ); + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { + SPI_speed = swSpiInit(spiRate, + hint_sck < 0 ? SD_SCK_PIN : hint_sck, + hint_mosi < 0 ? SD_MOSI_PIN : hint_mosi + ); } - void spiClose() { - } + void spiClose() { /* do nothing */ } uint8_t spiRec() { return spiTransfer(0xFF); } @@ -117,20 +115,17 @@ void spiBegin() {} // Set up SCK, MOSI & MISO pins for SSP0 - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - if (spiRate == SPI_SPEED_DEFAULT) - spiRate = INIT_SPI_SPEED; + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { + if (spiRate == SPI_SPEED_DEFAULT) spiRate = INIT_SPI_SPEED; // We basically ignore all pins other than MISO because we assume that all // belong to the same hardware SPI capable pin "module". int used_miso_pin = ( hint_miso != -1 ) ? hint_miso : SD_MISO_PIN; -#ifdef BOARD_SPI1_MISO_PIN - if (used_miso_pin == BOARD_SPI1_MISO_PIN) - SPI.setModule(1); -#endif -#ifdef BOARD_SPI2_MISO_PIN - if (used_miso_pin == BOARD_SPI2_MISO_PIN) - SPI.setModule(2); -#endif + #ifdef BOARD_SPI1_MISO_PIN + if (used_miso_pin == BOARD_SPI1_MISO_PIN) SPI.setModule(1); + #endif + #ifdef BOARD_SPI2_MISO_PIN + if (used_miso_pin == BOARD_SPI2_MISO_PIN) SPI.setModule(2); + #endif SPI.setDataSize(DATA_SIZE_8BIT); SPI.setDataMode(SPI_MODE0); @@ -219,7 +214,8 @@ SPIClass::SPIClass(uint8_t device) { GPDMA_Init(); } -SPIClass::SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel) { +SPIClass::SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel/*=-1*/) { + UNUSED(miso); UNUSED(sclk); UNUSED(ssel); #if BOARD_NR_SPI >= 1 if (mosi == BOARD_SPI1_MOSI_PIN) SPIClass(1); #endif diff --git a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h index 453b5631d5cc..b9a336066818 100644 --- a/Marlin/src/HAL/LPC1768/inc/SanityCheck.h +++ b/Marlin/src/HAL/LPC1768/inc/SanityCheck.h @@ -111,7 +111,7 @@ static_assert(DISABLED(BAUD_RATE_GCODE), "BAUD_RATE_GCODE is not yet supported o #define IS_RX1(P) (P == P0_16) #define _IS_TX1_1 IS_TX1 #define _IS_RX1_1 IS_RX1 - #if IS_TX1(TMC_SW_SCK) + #if IS_TX1(TMC_SPI_SCK) #error "Serial port pins (1) conflict with other pins!" #elif HAS_ROTARY_ENCODER #if IS_TX1(BTN_EN2) || IS_RX1(BTN_EN1) diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index 24f4759315bd..a319f86dd24c 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -78,15 +78,16 @@ class SPISettings { //uint32_t spiRate() const { return spi_speed; } static uint32_t spiRate2Clock(uint32_t spiRate) { - uint32_t Marlin_speed[7]; // CPSR is always 2 - Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED - Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED - Marlin_speed[2] = 2083333; //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED - Marlin_speed[3] = 1000000; //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED - Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 - Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 - Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h - return Marlin_speed[spiRate > 6 ? 6 : spiRate]; + constexpr uint32_t Marlin_speed[] = { // CPSR is always 2 + SPI_CLOCK_DIV2, //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED + SPI_CLOCK_DIV4, //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED + SPI_CLOCK_DIV8, //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED + SPI_CLOCK_DIV16, //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED + SPI_CLOCK_DIV32, //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 + SPI_CLOCK_DIV64, //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 + SPI_CLOCK_DIV128 //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h + }; + return Marlin_speed[spiRate > SPI_SPEED_6 ? SPI_SPEED_6 : spiRate]; } private: @@ -129,7 +130,7 @@ class SPIClass { /** * Init using pins */ - SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)-1); + SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel=pin_t(-1)); /** * Select and configure the current selected SPI device to use diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.h b/Marlin/src/HAL/LPC1768/tft/tft_spi.h index 4753fdbae9a0..a9b0c3d534e0 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.h +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.h @@ -63,9 +63,9 @@ class TFT_SPI { static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + // static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; //LPC dma can only write 0xFFF bytes at once. #define MAX_DMA_SIZE (0xFFF - 1) while (Count > 0) { diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index c374bc824608..2642740b7a1e 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -65,10 +65,10 @@ void spiBegin() { } - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore all pin hints. - if (spiRate == SPI_SPEED_DEFAULT) - spiRate = SPI_HALF_SPEED; + if (spiRate == SPI_SPEED_DEFAULT) spiRate = SPI_HALF_SPEED; + // Use datarates Marlin uses uint32_t clock; switch (spiRate) { @@ -85,9 +85,7 @@ sdSPI.begin(); } - void spiClose() { - sdSPI.end(); - } + void spiClose() { sdSPI.end(); } /** * @brief Receives a single byte from the SPI port. diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index aac889a7e57d..b833eca5b54f 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -46,7 +46,7 @@ static SPISettings spiConfig; #include "../shared/Delay.h" - void spiBegin(void) { + void spiBegin() { #if PIN_EXISTS(SD_SS) OUT_WRITE(SD_SS_PIN, HIGH); #endif @@ -67,7 +67,7 @@ static SPISettings spiConfig; void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); } void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); } - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Use datarates Marlin uses switch (spiRate) { case SPI_FULL_SPEED: delaySPIFunc = &delaySPI_125; break; // desired: 8,000,000 actual: ~1.1M @@ -86,9 +86,7 @@ static SPISettings spiConfig; SPI.begin(); } - void spiClose() { - SPI.end(); - } + void spiClose() { SPI.end(); } // Begin SPI transaction, set clock, bit order, data mode void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } @@ -161,9 +159,9 @@ static SPISettings spiConfig; } // Configure SPI for specified SPI speed - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore chip-select because the software manages it already. - + // Use datarates Marlin uses uint32_t clock; switch (spiRate) { @@ -185,13 +183,11 @@ static SPISettings spiConfig; SPI.beginTransaction(spiConfig); } - void spiClose() { - // Terminates SPI activity. - SPI.end(); - } + // Terminate SPI activity + void spiClose() { SPI.end(); } /** - * @brief Receives a single byte from the SPI port. + * @brief Receive a single byte from the SPI port. * * @return Byte received * diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index 0c9e107b2d22..432e7f20b505 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -42,14 +42,12 @@ void MarlinSPI::setClockDivider(uint8_t _div) { _clockDivider = _div; } -void MarlinSPI::begin(void) { - //TODO: only call spi_init if any parameter changed!! +void MarlinSPI::begin() { + // TODO: only call spi_init if any parameter changed!! spi_init(&_spi, _speed, _dataMode, _bitOrder, _dataSize); } -void MarlinSPI::end(void) { - spi_deinit(&_spi); -} +void MarlinSPI::end() { spi_deinit(&_spi); } void MarlinSPI::setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc) { _dmaHandle.Init.Direction = direction; diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index b6e2ec6dee1e..a8d964d76cbf 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -66,28 +66,18 @@ class Sd2CardUSBMscHandler : public USBMscHandler { } // multi block optimization - uint32_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; - - RETRY_MULTI: - uint32 i = blkLen; + bool done = false, success = true; uint8_t *cBuf = pBuf; sd2card->writeStart(blkAddr); - while (i--) { + while (blkLen--) { hal.watchdog_refresh(); - if (sd2card->writeData(cBuf) == false) - { - sd2card->writeStop(); - if (--multi_retry_cnt == 0) - goto FAIL; - multi_retry_cnt--; - goto RETRY_MULTI: - } + uint8_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; + while (sd2card->writeData(cBuf) == false && multi_retry_cnt) --multi_retry_cnt; + sd2card->writeStop(); + if (multi_retry_cnt <= 0) return false; cBuf += BLOCK_SIZE; } - sd2card->writeStop(); return true; - FAIL: - return false; } bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { @@ -99,28 +89,16 @@ class Sd2CardUSBMscHandler : public USBMscHandler { } // multi block optimization - uint32_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; - - RETRY_MULTI: - uint32 i = blkLen; - uint8_t *cBuf = pBuf; sd2card->readStart(blkAddr); - while (i--) { + while (blkLen--) { hal.watchdog_refresh(); - if (sd2card->readData(cBuf) == false) - { - sd2card->readStop(); - if (--multi_retry_cnt == 0) - goto FAIL; - multi_retry_cnt--; - goto RETRY_MULTI: - } - cBuf += BLOCK_SIZE; + uint8_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; + while (sd2card->readData(pBuf) == false && multi_retry_cnt) --multi_retry_cnt; + sd2card->readStop(); + if (multi_retry_cnt <= 0) return false; + pBuf += BLOCK_SIZE; } - sd2card->readStop(); return true; - FAIL: - return false; } bool IsReady() { diff --git a/Marlin/src/HAL/STM32/sdio.cpp b/Marlin/src/HAL/STM32/sdio.cpp index 04793c184de9..60dbe7e8c93d 100644 --- a/Marlin/src/HAL/STM32/sdio.cpp +++ b/Marlin/src/HAL/STM32/sdio.cpp @@ -397,12 +397,11 @@ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { #else uint8_t retries = SDIO_READ_RETRIES; - while (retries--) - { + while (retries--) { if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) return true; -#ifdef SD_RETRY_DO_DELAY - delay(SD_RETRY_DELAY_MS); -#endif + #if SD_RETRY_DELAY_MS + delay(SD_RETRY_DELAY_MS); + #endif } return false; @@ -439,12 +438,11 @@ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { #else uint8_t retries = SDIO_READ_RETRIES; - while (retries--) - { + while (retries--) { if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) return true; -#ifdef SD_RETRY_DO_DELAY - delay(SD_RETRY_DELAY_MS); -#endif + #if SD_RETRY_DELAY_MS + delay(SD_RETRY_DELAY_MS); + #endif } return false; diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index 2200abaa10e8..3456ea5dba7f 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -74,9 +74,9 @@ class TFT_FSMC { static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); } 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, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h index 7b63d6929b31..8eaf880f4602 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.h +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -64,9 +64,9 @@ class TFT_LTDC { 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, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_PINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index ba9016cfc18a..956985012588 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -36,46 +36,21 @@ DMA_HandleTypeDef TFT_SPI::DMAtx; uint8_t TFT_SPI::clkdiv_write; #if PIN_EXISTS(TFT_MISO) -uint8_t TFT_SPI::clkdiv_read; + uint8_t TFT_SPI::clkdiv_read; #endif bool TFT_SPI::active_transfer; bool TFT_SPI::active_dma; -uint8_t TFT_SPI::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) -{ - if ( speed >= (spibasefreq / 2) ) - { - return SPI_BAUDRATEPRESCALER_2; - } - else if ( speed >= (spibasefreq / 4) ) - { - return SPI_BAUDRATEPRESCALER_4; - } - else if ( speed >= (spibasefreq / 8) ) - { - return SPI_BAUDRATEPRESCALER_8; - } - else if ( speed >= (spibasefreq / 16) ) - { - return SPI_BAUDRATEPRESCALER_16; - } - else if ( speed >= (spibasefreq / 32) ) - { - return SPI_BAUDRATEPRESCALER_32; - } - else if ( speed >= (spibasefreq / 64) ) - { - return SPI_BAUDRATEPRESCALER_64; - } - else if ( speed >= (spibasefreq / 128) ) - { - return SPI_BAUDRATEPRESCALER_128; - } - else - { - return SPI_BAUDRATEPRESCALER_256; - } +uint8_t TFT_SPI::_GetClockDivider(uint32_t spibasefreq, uint32_t speed) { + if (speed >= (spibasefreq / 2)) return SPI_BAUDRATEPRESCALER_2; + if (speed >= (spibasefreq / 4)) return SPI_BAUDRATEPRESCALER_4; + if (speed >= (spibasefreq / 8)) return SPI_BAUDRATEPRESCALER_8; + if (speed >= (spibasefreq / 16)) return SPI_BAUDRATEPRESCALER_16; + if (speed >= (spibasefreq / 32)) return SPI_BAUDRATEPRESCALER_32; + if (speed >= (spibasefreq / 64)) return SPI_BAUDRATEPRESCALER_64; + if (speed >= (spibasefreq / 128)) return SPI_BAUDRATEPRESCALER_128; + return SPI_BAUDRATEPRESCALER_256; } extern "C" { @@ -99,62 +74,52 @@ void TFT_SPI::Init() { // SPI can have different baudrates depending on read or write functionality. -#if PIN_EXISTS(TFT_MISO) - // static clkdiv_read variable. - bool has_clkdiv_read = false; -#endif + #if PIN_EXISTS(TFT_MISO) + // static clkdiv_read variable. + bool has_clkdiv_read = false; + #endif // static clkdiv_write variable. bool has_clkdiv_write = false; -#if (PIN_EXISTS(TFT_MISO) && defined(TFT_BAUDRATE_READ)) || defined(TFT_BAURDATE_WRITE) + #if (PIN_EXISTS(TFT_MISO) && defined(TFT_BAUDRATE_READ)) || defined(TFT_BAUDRATE_WRITE) spi_t tmp_spi; tmp_spi.pin_sclk = digitalPinToPinName(TFT_SCK_PIN); uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); -#if PIN_EXISTS(TFT_MISO) && TFT_BAUDRATE_READ - clkdiv_read = _GetClockDivider(spibasefreq, TFT_BAUDRATE_READ); - has_clkdiv_read = true; -#endif + #if PIN_EXISTS(TFT_MISO) && TFT_BAUDRATE_READ + clkdiv_read = _GetClockDivider(spibasefreq, TFT_BAUDRATE_READ); + has_clkdiv_read = true; + #endif -#ifdef TFT_BAUDRATE_WRITE - clkdiv_write = _GetClockDivider(spibasefreq, TFT_BAUDRATE_WRITE); - has_clkdiv_write = true; -#endif + #ifdef TFT_BAUDRATE_WRITE + clkdiv_write = _GetClockDivider(spibasefreq, TFT_BAUDRATE_WRITE); + has_clkdiv_write = true; + #endif -#endif + #endif - if ( !has_clkdiv_write ) - { -#ifdef SPI1_BASE - if (spiInstance == SPI1) - { - clkdiv_write = SPI_BAUDRATEPRESCALER_4; - has_clkdiv_write = true; - } -#endif + if (!has_clkdiv_write) { + #ifdef SPI1_BASE + if (spiInstance == SPI1) { + clkdiv_write = SPI_BAUDRATEPRESCALER_4; + has_clkdiv_write = true; + } + #endif - if ( !has_clkdiv_write ) - { - clkdiv_write = SPI_BAUDRATEPRESCALER_2; - } + if (!has_clkdiv_write) clkdiv_write = SPI_BAUDRATEPRESCALER_2; } -#if PIN_EXISTS(TFT_MISO) - if ( !has_clkdiv_read ) - { - clkdiv_read = clkdiv_write; - } -#endif + #if PIN_EXISTS(TFT_MISO) + if (!has_clkdiv_read) clkdiv_read = clkdiv_write; + #endif SPIx.Instance = spiInstance; SPIx.State = HAL_SPI_STATE_RESET; SPIx.Init.NSS = SPI_NSS_SOFT; SPIx.Init.Mode = SPI_MODE_MASTER; SPIx.Init.Direction = (TFT_MISO_PIN != NC && TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; - //SPIx.Init.BaudRatePrescaler = clkdiv; SPIx.Init.CLKPhase = SPI_PHASE_1EDGE; SPIx.Init.CLKPolarity = SPI_POLARITY_LOW; - //SPIx.Init.DataSize = SPI_DATASIZE_8BIT; SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB; SPIx.Init.TIMode = SPI_TIMODE_DISABLE; SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; @@ -175,19 +140,12 @@ void TFT_SPI::Init() { } // Call before any HAL initialization (DMA or SPI). -void TFT_SPI::HALPrepare(eSPIMode spiMode) -{ +void TFT_SPI::HAL_SPI_Prepare(eSPIMode spiMode) { uint8_t clkdiv = 1; -#if PIN_EXISTS(TFT_MISO) - if (spiMode == eSPIMode::READ) - { - clkdiv = clkdiv_read; - } -#endif - if (spiMode == eSPIMode::WRITE) - { - clkdiv = clkdiv_write; - } + #if PIN_EXISTS(TFT_MISO) + if (spiMode == eSPIMode::READ) clkdiv = clkdiv_read; + #endif + if (spiMode == eSPIMode::WRITE) clkdiv = clkdiv_write; SPIx.Init.BaudRatePrescaler = clkdiv; @@ -200,138 +158,84 @@ void TFT_SPI::HALPrepare(eSPIMode spiMode) pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_CLK_ENABLE(); - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Channel3; - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Stream3; - DMAtx.Init.Channel = DMA_CHANNEL_3; - #endif - } + #ifdef STM32F1xx + #define _DMATX_PREPARE(N1,N4,S,C1,C4) \ + __HAL_RCC_DMA##N1##_CLK_ENABLE(); \ + DMAtx.Instance = DMA##N1##_Channel##C1; + #elif defined(STM32F4xx) + #define _DMATX_PREPARE(N1,N4,S,C1,C4) \ + __HAL_RCC_DMA##N4##_CLK_ENABLE(); \ + DMAtx.Instance = DMA##N4##_Stream##S; \ + DMAtx.Init.Channel = DMA_CHANNEL_##C4; + #else + #define _DMATX_PREPARE(...) NOOP #endif + #define SPIX_PREPARE(I,N1,N4,S,C1,C4) \ + if (SPIx.Instance == SPI##I) { \ + __HAL_RCC_SPI##I##_CLK_ENABLE(); \ + __HAL_RCC_SPI##I##_FORCE_RESET(); \ + __HAL_RCC_SPI##I##_RELEASE_RESET(); \ + _DMATX_PREPARE(N1,N4,S,C1,C4); \ + } + #ifdef SPI1_BASE + SPIX_PREPARE(1, 1, 2, 3, 3, 3); + #endif #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_CLK_ENABLE(); - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Channel5; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Stream4; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } + SPIX_PREPARE(2, 1, 1, 4, 5, 0); #endif - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_CLK_ENABLE(); - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Channel2; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Stream5; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } + SPIX_PREPARE(3, 2, 1, 5, 2, 0); #endif - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_CLK_ENABLE(); - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Channel4; - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Stream5; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } + SPIX_PREPARE(4, 2, 2, 5, 4, 0); #endif } -void TFT_SPI::HALDismantle(void) -{ - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - __HAL_RCC_SPI1_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_DISABLE(); - #endif - } +void TFT_SPI::HAL_SPI_Dismantle() { + #ifdef STM32F1xx + #define _DMATX_DISMANTLE(N1,N4) \ + __HAL_RCC_DMA##N1##_CLK_DISABLE(); \ + #elif defined(STM32F4xx) + #define _DMATX_DISMANTLE(N1,N4) \ + __HAL_RCC_DMA##N4##_CLK_DISABLE(); \ + #else + #define _DMATX_DISMANTLE(...) NOOP #endif + #define SPIX_DISMANTLE(I,N1,N4) \ + if (SPIx.Instance == SPI##I) { \ + __HAL_RCC_SPI##I##_FORCE_RESET(); \ + __HAL_RCC_SPI##I##_RELEASE_RESET(); \ + __HAL_RCC_SPI##I##_CLK_DISABLE(); \ + _DMATX_DISMANTLE(N1,N4); \ + } + #ifdef SPI1_BASE + SPIX_DISMANTLE(1, 1, 2); + #endif #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - __HAL_RCC_SPI2_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_DISABLE(); - #endif - } + SPIX_DISMANTLE(2, 1, 1); #endif - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - __HAL_RCC_SPI3_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_DISABLE(); - #endif - } + SPIX_DISMANTLE(3, 2, 1); #endif - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - __HAL_RCC_SPI4_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_DISABLE(); - #endif + SPIX_DISMANTLE(4, 2, 2); #endif } void TFT_SPI::DataTransferBegin(uint16_t DataSize, eSPIMode spiMode) { - HALPrepare(spiMode); + HAL_SPI_Prepare(spiMode); SPIx.Init.DataSize = ( DataSize == DATASIZE_8BIT ) ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT; HAL_SPI_Init(&SPIx); WRITE(TFT_CS_PIN, LOW); active_transfer = true; } -void TFT_SPI::DataTransferEnd(void) -{ +void TFT_SPI::DataTransferEnd() { // TODO: apply strong integrity to the active_transfer variable! HAL_SPI_DeInit(&SPIx); - HALDismantle(); + HAL_SPI_Dismantle(); WRITE(TFT_CS_PIN, HIGH); active_transfer = false; } @@ -378,45 +282,40 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) { __HAL_SPI_DISABLE(&SPIx); DataTransferEnd(); #endif - return Data >> 7; } bool TFT_SPI::isBusy() { - if (active_dma) - { + if (active_dma) { #ifdef STM32F1xx volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; #elif defined(STM32F4xx) volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; #endif - #if 0 - if (dmaEnabled) { - if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) + #if 0 + if (dmaEnabled) { + if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) + Abort(); + } + else Abort(); - } - else - Abort(); - #endif + #endif return dmaEnabled; } - else - { + else { #if 0 - Abort(); + Abort(); #endif return false; } } void TFT_SPI::Abort() { - if (active_transfer) - { + if (active_transfer) { // Wait for any running spi while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { } while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) { } - if (active_dma) - { + if (active_dma) { // First, abort any running dma HAL_DMA_Abort(&DMAtx); HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); @@ -430,10 +329,10 @@ void TFT_SPI::Abort() { } void TFT_SPI::Transmit(uint16_t Data) { -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif + #if PIN_EXISTS(TFT_MISO) + if (TFT_MISO_PIN == TFT_MOSI_PIN) + SPI_1LINE_TX(&SPIx); + #endif __HAL_SPI_ENABLE(&SPIx); @@ -442,10 +341,10 @@ void TFT_SPI::Transmit(uint16_t Data) { while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN != TFT_MOSI_PIN) - __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read -#endif + #if PIN_EXISTS(TFT_MISO) + if (TFT_MISO_PIN != TFT_MOSI_PIN) + __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read + #endif } void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { @@ -453,10 +352,10 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun // Wait last dma finish, to start another while (isBusy()) { /* nada */ } -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif + #if PIN_EXISTS(TFT_MISO) + if (TFT_MISO_PIN == TFT_MOSI_PIN) + SPI_1LINE_TX(&SPIx); + #endif DataTransferBegin(); @@ -479,10 +378,10 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun void TFT_SPI::TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif + #if PIN_EXISTS(TFT_MISO) + if (TFT_MISO_PIN == TFT_MOSI_PIN) + SPI_1LINE_TX(&SPIx); + #endif DataTransferBegin(); diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index ce853c968880..fac69ae4f541 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -42,11 +42,7 @@ class TFT_SPI { - enum class eSPIMode - { - READ, - WRITE - }; + enum class eSPIMode { READ, WRITE }; private: static SPI_HandleTypeDef SPIx; @@ -59,14 +55,14 @@ class TFT_SPI { static void TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); #endif - static void HALPrepare(eSPIMode spiMode); - static void HALDismantle(void); + static void HAL_SPI_Prepare(eSPIMode spiMode); + static void HAL_SPI_Dismantle(); - static uint8_t _GetClockDivider( uint32_t spibasefreq, uint32_t speed ); + static uint8_t _GetClockDivider(uint32_t spibasefreq, uint32_t speed); -#if PIN_EXISTS(TFT_MISO) - static uint8_t clkdiv_read; -#endif + #if PIN_EXISTS(TFT_MISO) + static uint8_t clkdiv_read; + #endif static uint8_t clkdiv_write; static bool active_transfer; @@ -80,7 +76,7 @@ class TFT_SPI { static bool isBusy(); static void Abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT, eSPIMode spiMode = eSPIMode::WRITE); + static void DataTransferBegin(uint16_t DataWidth=DATASIZE_16BIT, eSPIMode spiMode=eSPIMode::WRITE); static void DataTransferEnd(); static void DataTransferAbort(); @@ -93,9 +89,9 @@ class TFT_SPI { static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { TransmitDMA_IT(DMA_MINC_ENABLE, Data, Count); } #endif - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index f4edb3af2942..306c47d73936 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -35,40 +35,15 @@ uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } SPI_HandleTypeDef XPT2046::SPIx; -uint8_t XPT2046::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) -{ - if ( speed >= (spibasefreq / 2) ) - { - return SPI_BAUDRATEPRESCALER_2; - } - else if ( speed >= (spibasefreq / 4) ) - { - return SPI_BAUDRATEPRESCALER_4; - } - else if ( speed >= (spibasefreq / 8) ) - { - return SPI_BAUDRATEPRESCALER_8; - } - else if ( speed >= (spibasefreq / 16) ) - { - return SPI_BAUDRATEPRESCALER_16; - } - else if ( speed >= (spibasefreq / 32) ) - { - return SPI_BAUDRATEPRESCALER_32; - } - else if ( speed >= (spibasefreq / 64) ) - { - return SPI_BAUDRATEPRESCALER_64; - } - else if ( speed >= (spibasefreq / 128) ) - { - return SPI_BAUDRATEPRESCALER_128; - } - else - { - return SPI_BAUDRATEPRESCALER_256; - } +uint8_t XPT2046::_GetClockDivider(uint32_t spibasefreq, uint32_t speed) { + if (speed >= (spibasefreq / 2)) return SPI_BAUDRATEPRESCALER_2; + if (speed >= (spibasefreq / 4)) return SPI_BAUDRATEPRESCALER_4; + if (speed >= (spibasefreq / 8)) return SPI_BAUDRATEPRESCALER_8; + if (speed >= (spibasefreq / 16)) return SPI_BAUDRATEPRESCALER_16; + if (speed >= (spibasefreq / 32)) return SPI_BAUDRATEPRESCALER_32; + if (speed >= (spibasefreq / 64)) return SPI_BAUDRATEPRESCALER_64; + if (speed >= (spibasefreq / 128)) return SPI_BAUDRATEPRESCALER_128; + return SPI_BAUDRATEPRESCALER_256; } extern "C" { @@ -93,27 +68,21 @@ void XPT2046::Init() { if (spiInstance) { uint8_t clkdiv; -#ifdef TOUCH_BAUDRATE - spi_t tmp_spi; - tmp_spi.pin_sclk = digitalPinToPinName(TOUCH_SCK_PIN); - uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); - - clkdiv = _GetClockDivider(spibasefreq, TOUCH_BAUDRATE); -#else - bool has_clkdiv = false; - - #ifdef SPI1_BASE - if (spiInstance == SPI1) - { - clkdiv = SPI_BAUDRATEPRESCALER_16; - has_clkdiv = true; - } + #ifdef TOUCH_BAUDRATE + spi_t tmp_spi; + tmp_spi.pin_sclk = digitalPinToPinName(TOUCH_SCK_PIN); + uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); + clkdiv = _GetClockDivider(spibasefreq, TOUCH_BAUDRATE); + #else + bool has_clkdiv = false; + #ifdef SPI1_BASE + if (spiInstance == SPI1) { + clkdiv = SPI_BAUDRATEPRESCALER_16; + has_clkdiv = true; + } + #endif + if (!has_clkdiv) clkdiv = SPI_BAUDRATEPRESCALER_8; #endif - if ( !has_clkdiv ) - { - clkdiv = SPI_BAUDRATEPRESCALER_8; - } -#endif SPIx.State = HAL_SPI_STATE_RESET; SPIx.Init.NSS = SPI_NSS_SOFT; @@ -137,126 +106,85 @@ void XPT2046::Init() { getRawData(XPT2046_Z1); } -void XPT2046::HALPrepare(void) -{ +void XPT2046::HAL_SPI_Prepare() { pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI); pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO); pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TOUCH_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TOUCH_SCK_PIN)), GPIO_PULLDOWN); - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_CLK_ENABLE(); - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); + #define SPIX_PREPARE(I) \ + if (SPIx.Instance == SPI##I) { \ + __HAL_RCC_SPI##I##_CLK_ENABLE(); \ + __HAL_RCC_SPI##I##_FORCE_RESET(); \ + __HAL_RCC_SPI##I##_RELEASE_RESET(); \ } + #ifdef SPI1_BASE + SPIX_PREPARE(1); #endif #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_CLK_ENABLE(); - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - } + SPIX_PREPARE(2); #endif #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_CLK_ENABLE(); - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - } + SPIX_PREPARE(3); #endif #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_CLK_ENABLE(); - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - } + SPIX_PREPARE(4); #endif #ifdef SPI5_BASE - if (SPIx.Instance == SPI5) { - __HAL_RCC_SPI5_CLK_ENABLE(); - __HAL_RCC_SPI5_FORCE_RESET(); - __HAL_RCC_SPI5_RELEASE_RESET(); - } + SPIX_PREPARE(5); #endif #ifdef SPI6_BASE - if (SPIx.Instance == SPI6) { - __HAL_RCC_SPI6_CLK_ENABLE(); - __HAL_RCC_SPI6_FORCE_RESET(); - __HAL_RCC_SPI6_RELEASE_RESET(); - } + SPIX_PREPARE(6); #endif } -void XPT2046::HALDismantle(void) -{ - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - __HAL_RCC_SPI1_CLK_DISABLE(); +void XPT2046::HAL_SPI_Dismantle() { + #define SPIX_DISMANTLE(I) \ + if (SPIx.Instance == SPI##I) { \ + __HAL_RCC_SPI##I##_FORCE_RESET(); \ + __HAL_RCC_SPI##I##_RELEASE_RESET(); \ + __HAL_RCC_SPI##I##_CLK_DISABLE(); \ } + #ifdef SPI1_BASE + SPIX_DISMANTLE(1); #endif #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - __HAL_RCC_SPI2_CLK_DISABLE(); - } + SPIX_DISMANTLE(2); #endif #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - __HAL_RCC_SPI3_CLK_DISABLE(); - } + SPIX_DISMANTLE(3); #endif #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - __HAL_RCC_SPI4_CLK_DISABLE(); - } + SPIX_DISMANTLE(4); #endif #ifdef SPI5_BASE - if (SPIx.Instance == SPI5) { - __HAL_RCC_SPI5_FORCE_RESET(); - __HAL_RCC_SPI5_RELEASE_RESET(); - __HAL_RCC_SPI5_CLK_DISABLE(); - } + SPIX_DISMANTLE(5); #endif #ifdef SPI6_BASE - if (SPIx.Instance == SPI6) { - __HAL_RCC_SPI6_FORCE_RESET(); - __HAL_RCC_SPI6_RELEASE_RESET(); - __HAL_RCC_SPI6_CLK_DISABLE(); - } + SPIX_DISMANTLE(6); #endif } -void XPT2046::DataTransferBegin(void) - { - if (SPIx.Instance) - { - HALPrepare(); +void XPT2046::DataTransferBegin() { + if (SPIx.Instance) { + HAL_SPI_Prepare(); HAL_SPI_Init(&SPIx); } WRITE(TOUCH_CS_PIN, LOW); } -void XPT2046::DataTransferEnd(void) -{ +void XPT2046::DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); - if (SPIx.Instance) - { + if (SPIx.Instance) { HAL_SPI_DeInit(&SPIx); - HALDismantle(); + HAL_SPI_Dismantle(); } } bool XPT2046::isTouched() { - return isBusy() ? false : ( + if (isBusy()) return false; + return ( #if PIN_EXISTS(TOUCH_INT) READ(TOUCH_INT_PIN) != HIGH #else diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 87f09063f683..413e2cc6f63c 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -77,8 +77,8 @@ class XPT2046 { static uint16_t SoftwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); } - static void HALPrepare(void); - static void HALDismantle(void); + static void HAL_SPI_Prepare(); + static void HAL_SPI_Dismantle(); public: static void Init(); diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index a2dc7486d2d9..4865685fd7e2 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -74,7 +74,7 @@ void spiBegin() { * * @details */ -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // TODO: maybe use the more generic STM32 SPI stuff instead, ignore the pins here. /** * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz @@ -103,9 +103,7 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi SPI.setDataMode(SPI_MODE0); } -void spiClose() { - SPI.end(); -} +void spiClose() { SPI.end(); } /** * @brief Receive a single byte from the SPI port. diff --git a/Marlin/src/HAL/STM32F1/SPI.cpp b/Marlin/src/HAL/STM32F1/SPI.cpp index 1ce2c7d3fd5d..902c9511a726 100644 --- a/Marlin/src/HAL/STM32F1/SPI.cpp +++ b/Marlin/src/HAL/STM32F1/SPI.cpp @@ -155,7 +155,8 @@ SPIClass::SPIClass(uint32_t spi_num) { _currentSetting->state = SPI_STATE_IDLE; } -SPIClass::SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel) : SPIClass(1) { +SPIClass::SPIClass(int8_t mosi, int8_t miso, int8_t sclk, int8_t ssel/*=-1*/) : SPIClass(1) { + UNUSED(miso); UNUSED(sclk); UNUSED(ssel); #if BOARD_NR_SPI >= 1 if (mosi == BOARD_SPI1_MOSI_PIN) setModule(1); #endif diff --git a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp index 4dc5fa931ae6..1a9d4ed9cd45 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_wired.cpp @@ -39,9 +39,7 @@ size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_finish() { -#if ENABLED(SPI_EEPROM) - spiClose(); -#endif + TERN_(SPI_EEPROM, spiClose()); return true; } diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 515cfadefa81..b00be302179d 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -136,13 +136,12 @@ bool SDIO_ReadBlock_DMA(uint32_t blockAddress, uint8_t *data) { } bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) { - uint32_t retries = SDIO_READ_RETRIES; - while (retries--) - { + uint8_t retries = SDIO_READ_RETRIES; + while (retries--) { if (SDIO_ReadBlock_DMA(blockAddress, data)) return true; -#ifdef SD_RETRY_DO_DELAY - delay(SD_RETRY_DELAY_MS); -#endif + #if SD_RETRY_DELAY_MS + delay(SD_RETRY_DELAY_MS); + #endif } return false; } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h index d9ee1f4c7767..89b5bdf9dd20 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h @@ -60,9 +60,9 @@ class TFT_FSMC { static void WriteReg(uint16_t Reg); static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; while (Count > 0) { TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.h b/Marlin/src/HAL/STM32F1/tft/tft_spi.h index da9a8e0c223e..1b13d06bb3f3 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.h @@ -61,9 +61,9 @@ class TFT_SPI { static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; + uint16_t Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index cb4dd4d0d16e..6bf5eaff6708 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -46,7 +46,7 @@ void spiBegin() { } // Configure SPI for specified SPI speed -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the pin hints, there is nothing we can do (see arduino core). // Use data rates Marlin uses uint32_t clock; @@ -63,9 +63,7 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi SPI.begin(); } -void spiClose() { - SPI.end(); -} +void spiClose() { SPI.end(); } // SPI receive a byte uint8_t spiRec() { diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 0d165749ef73..7f4fe93ac3e1 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -44,7 +44,7 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the SPI pin hints. // Use Marlin data-rates @@ -63,9 +63,7 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi SPI.begin(); } -void spiClose() { - SPI.end(); -} +void spiClose() { SPI.end(); } uint8_t spiRec() { SPI.beginTransaction(spiConfig); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 1adf8a04a9dc..f3686a4d0450 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -59,7 +59,7 @@ void spiBegin() { //SET_OUTPUT(SD_MOSI_PIN); } -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the SPI pin hints. // Use Marlin data-rates @@ -78,9 +78,7 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi SPI.begin(); } -void spiClose() { - SPI.end(); -} +void spiClose() { SPI.end(); } uint8_t spiRec() { SPI.beginTransaction(spiConfig); diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 60c188b7900d..de9b3c50dc5d 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -53,7 +53,7 @@ #define SPI_SIXTEENTH_SPEED 4 // Set SCK rate to 1/16 of max rate #define SPI_SPEED_5 5 // Set SCK rate to 1/32 of max rate #define SPI_SPEED_6 6 // Set SCK rate to 1/64 of max rate -#define SPI_SPEED_DEFAULT 255 // Let the framework decide (usually recommended value) +#define SPI_SPEED_DEFAULT 255 // Let the framework decide (usually recommended value) // // Standard SPI functions @@ -63,7 +63,7 @@ void spiBegin(); // Configure SPI for specified SPI speed -void spiInit(uint8_t spiRate, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); +void spiInit(uint8_t spiRate, const int hint_sck=-1, const int hint_miso=-1, const int hint_mosi=-1, const int hint_cs=-1); // Terminates SPI connection. void spiClose(); diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index a96f3100ca20..4a95aec79057 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -91,11 +91,11 @@ class TMCMarlin : public TMC, public TMCStorage { TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t axis_chain_index) : TMC(cs_pin, RS, axis_chain_index) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const bool isSoftSPI=false) : + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, isSoftSPI) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index, bool softSPI) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index, softSPI) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index, const bool isSoftSPI=false) : + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index, isSoftSPI) {} uint16_t rms_current() { return TMC::rms_current(); } void rms_current(uint16_t mA) { @@ -290,11 +290,11 @@ class TMCMarlin : public TMC266 TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t) : TMC2660Stepper(cs_pin, RS) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : - TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const bool isSoftSPI=false) : + TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, isSoftSPI) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t, bool softSPI) : - TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t, const bool isSoftSPI=false) : + TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, isSoftSPI) {} uint16_t rms_current() { return TMC2660Stepper::rms_current(); } void rms_current(const uint16_t mA) { diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index ebab8e9497e3..996034497fef 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -1483,9 +1483,6 @@ #define TFT_INTERFACE_SPI #define TFT_BAUDRATE_READ 8000000 // Hz #define TFT_BAUDRATE_WRITE 32000000 // Hz - #if defined(MKS_TS35_V2_0) && defined(TOUCH_SCREEN) - #define TFT_TOUCH_DEVICE_XPT2046 - #endif #elif EITHER(LERDGE_TFT35, ANET_ET5_TFT35) // ST7796 #define TFT_DEFAULT_ORIENTATION TFT_EXCHANGE_XY #define TFT_RES_480x320 @@ -1621,12 +1618,11 @@ #if TOUCH_IDLE_SLEEP_MINS #define HAS_TOUCH_SLEEP 1 #endif - #if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046) - #define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 - #endif #if ENABLED(TFT_TOUCH_DEVICE_GT911) // GT911 Capacitive touch screen such as BIQU_BX_TFT70 #undef TOUCH_SCREEN_CALIBRATION #undef TOUCH_CALIBRATION_AUTO_SAVE + #else + #define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8 #endif #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && ENABLED(TFT_INTERFACE_SPI) #define TOUCH_BAUDRATE 2500000 // Hz diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index a2af15397015..21990e2b94c8 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -383,9 +383,8 @@ void MarlinUI::init_lcd() { } else PanelDetected = 0; -#if ENABLED(TFTGLCD_PANEL_SPI) - spiClose(); -#endif + + TERN_(TFTGLCD_PANEL_SPI, spiClose()); safe_delay(100); } diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 50b921cd2a93..1f387272335c 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -126,7 +126,7 @@ class TFT_IO { inline static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { io.WriteSequenceIT(Data, Count); }; #endif - // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + // static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } inline static void WriteMultiple(uint16_t Color, uint32_t Count) { io.WriteMultiple(Color, Count); }; protected: diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 2face373166e..e790fc322581 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -47,13 +47,11 @@ enum StealthIndex : uint8_t { // SWHW = SW/SH UART selection #if ENABLED(TMC_USE_SW_SPI) #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, true) +#elif defined(TMC_SPI_MISO) && defined(TMC_SPI_MOSI) && defined(TMC_SPI_SCK) + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, false) #else -#if !defined(TMC_SPI_MISO) || !defined(TMC_SPI_MOSI) || !defined(TMC_SPI_SCK) - // define in case the pins are unknown/not-definable/fixed. + // Define when the pins are unknown/not-definable/fixed. #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) -#else - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, false) -#endif #endif #if ENABLED(TMC_SERIAL_MULTIPLEXER) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 2ad0f0e0821d..1a6f0bdbebe2 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3114,7 +3114,7 @@ void Temperature::disable_all_heaters() { #if !HAS_MAXTC_SW_SPI // Initialize SPI using the default Hardware SPI bus. - // FIXME: spiBegin, spiRec and spiInit doesn't work when soft spi is used. + // FIXME: spiBegin, spiRec and spiInit doesn't work when Soft SPI is used. spiBegin(); spiInit(MAX_TC_SPEED_BITS); #endif @@ -3128,10 +3128,7 @@ void Temperature::disable_all_heaters() { if (i > 0) max_tc_temp <<= 8; // shift left if not the last byte } - #if !HAS_MAXTC_SW_SPI - // Need to terminate our work. - spiClose(); - #endif + IF_DISABLED(HAS_MAXTC_SW_SPI, spiClose()); // Terminate our work MAXTC_CS_WRITE(HIGH); // Disable MAXTC #else @@ -3224,15 +3221,12 @@ void Temperature::update_raw_temperatures() { #if HAS_TEMP_ADC_0 && !TEMP_SENSOR_IS_MAX_TC(0) temp_hotend[0].update(); #endif - #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_IS_MAX_TC(1) temp_hotend[1].update(); #endif - #if HAS_TEMP_ADC_2 && !TEMP_SENSOR_IS_MAX_TC(2) temp_hotend[2].update(); #endif - #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_IS_MAX_TC(REDUNDANT) temp_redundant.update(); #endif diff --git a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h index 5a43ee85ac28..3e8814c3ee9d 100644 --- a/Marlin/src/pins/linux/pins_RAMPS_LINUX.h +++ b/Marlin/src/pins/linux/pins_RAMPS_LINUX.h @@ -250,13 +250,13 @@ * Default pins for TMC SPI */ #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 66 + #define TMC_SPI_MOSI 66 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO 44 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 64 + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index 783a207b083d..bde6a1c5fc7b 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -80,13 +80,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P0_18 // ETH + #define TMC_SPI_MOSI P0_18 // ETH #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_17 // ETH + #define TMC_SPI_MISO P0_17 // ETH #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_15 // ETH + #define TMC_SPI_SCK P0_15 // ETH #endif // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 2006900bae5b..6e069e9786d7 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -56,7 +56,6 @@ #define E0_DIR_PIN P2_13 #define E0_ENABLE_PIN P2_12 - /** ------ ------ * 1.30 | 1 2 | 2.11 0.17 | 1 2 | 0.15 * 0.18 | 3 4 | 0.16 3.26 | 3 4 | 1.23 @@ -165,12 +164,12 @@ // When using any TMC SPI-based drivers, software SPI is used // because pins may be shared with the display or SD card. //#define TMC_USE_SW_SPI - #define TMC_SPI_MOSI EXP2_06_PIN - #define TMC_SPI_MISO EXP2_01_PIN + #define TMC_SPI_MOSI EXP2_06_PIN + #define TMC_SPI_MISO EXP2_01_PIN // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) - #define TMC_SPI_SCK EXP2_02_PIN + #define TMC_SPI_SCK EXP2_02_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. - //#define TMC_SW_SCK P2_06 + //#define TMC_SPI_SCK P2_06 #if ENABLED(SOFTWARE_DRIVER_ENABLE) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 85d7d0f16ecb..0195febf0e51 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -140,13 +140,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P4_28 + #define TMC_SPI_MOSI P4_28 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_05 + #define TMC_SPI_MISO P0_05 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_04 + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 644ca80651c5..7c357c36ba9a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -197,13 +197,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P1_17 + #define TMC_SPI_MOSI P1_17 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_05 + #define TMC_SPI_MISO P0_05 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_04 + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index b365e7c9583c..b54c240701d8 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -135,13 +135,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P4_28 + #define TMC_SPI_MOSI P4_28 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_05 + #define TMC_SPI_MISO P0_05 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_04 + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 4952a07c3b1e..1ccb3451e3e4 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -100,13 +100,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P1_00 // ETH + #define TMC_SPI_MOSI P1_00 // ETH #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P1_08 // ETH + #define TMC_SPI_MISO P1_08 // ETH #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P1_09 // ETH + #define TMC_SPI_SCK P1_09 // ETH #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index f9755f8677a5..f9f2345d9c21 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -71,13 +71,13 @@ // Default pins for TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 3997cccec2d3..3702acec73f8 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -88,13 +88,13 @@ // Default pins for TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 + #define TMC_SPI_MOSI P1_16 // Ethernet Expansion - Pin 5 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 + #define TMC_SPI_MISO P1_17 // Ethernet Expansion - Pin 6 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 + #define TMC_SPI_SCK P1_08 // Ethernet Expansion - Pin 7 #endif // diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index f0d904811dd9..21f262ad4195 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -95,13 +95,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P0_20 + #define TMC_SPI_MOSI P0_20 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_19 + #define TMC_SPI_MISO P0_19 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_21 + #define TMC_SPI_SCK P0_21 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 358a1d87b1f6..47ff4406a0bb 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -149,13 +149,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI P1_16 + #define TMC_SPI_MOSI P1_16 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO P0_05 + #define TMC_SPI_MISO P0_05 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK P0_04 + #define TMC_SPI_SCK P0_04 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index b9dbd2a531a5..56685cfe642d 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -314,13 +314,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 66 + #define TMC_SPI_MOSI 66 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO 44 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 64 + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index 2d28ec87552d..93916db3e988 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -219,13 +219,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 51 + #define TMC_SPI_MOSI 51 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 50 + #define TMC_SPI_MISO 50 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 53 + #define TMC_SPI_SCK 53 #endif // diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 779a21ebd7f9..ea670be0d91e 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -150,15 +150,15 @@ // // Default pins for TMC SPI // -// #ifndef TMC_SPI_MOSI -// #define TMC_SPI_MOSI 66 -// #endif -// #ifndef TMC_SPI_MISO -// #define TMC_SPI_MISO 44 -// #endif -// #ifndef TMC_SPI_SCK -// #define TMC_SPI_SCK 64 -// #endif +//#ifndef TMC_SPI_MOSI +// #define TMC_SPI_MOSI 66 +//#endif +//#ifndef TMC_SPI_MISO +// #define TMC_SPI_MISO 44 +//#endif +//#ifndef TMC_SPI_SCK +// #define TMC_SPI_SCK 64 +//#endif // // Temperature Sensors @@ -177,9 +177,9 @@ // SPI for MAX Thermocouple //#if DISABLED(SDSUPPORT) -// #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card +// #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card //#else -// #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) //#endif // @@ -211,7 +211,7 @@ #define LED_PIN 13 //#ifndef FILWIDTH_PIN -// #define FILWIDTH_PIN 5 // Analog Input +// #define FILWIDTH_PIN 5 // Analog Input //#endif // DIO 4 (Servos plug) for the runout sensor. diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 0ddb1f69a431..f15d4d7e3f0f 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -183,13 +183,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 66 + #define TMC_SPI_MOSI 66 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO 44 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 64 + #define TMC_SPI_SCK 64 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 4c0330e51285..503b29f15b9e 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -149,13 +149,13 @@ // Required for the Archim2 board. // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 28 // PD3 + #define TMC_SPI_MOSI 28 // PD3 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 26 // PD1 + #define TMC_SPI_MISO 26 // PD1 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 27 // PD2 + #define TMC_SPI_SCK 27 // PD2 #endif // diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index e70c69ef82e9..725240de7f5f 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -167,13 +167,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 58 // Mega/Due:66 - AGCM4:58 + #define TMC_SPI_MOSI 58 // Mega/Due:66 - AGCM4:58 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO 44 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 56 // Mega/Due:64 - AGCM4:56 + #define TMC_SPI_SCK 56 // Mega/Due:64 - AGCM4:56 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 3845645abb68..d53bc6bfffd5 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -97,13 +97,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB5 + #define TMC_SPI_MOSI PB5 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB4 + #define TMC_SPI_MISO PB4 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB3 + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index ce1d0d66d72d..d88812ac4628 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -70,30 +70,30 @@ // Shared with EXP2 #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB3 + #define TMC_SPI_SCK PB3 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB4 + #define TMC_SPI_MISO PB4 #endif #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB5 + #define TMC_SPI_MOSI PB5 #endif #if HAS_TMC_UART // Shared with EXP1 - #define X_SERIAL_TX_PIN PC10 - #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN + #define X_SERIAL_TX_PIN PC10 + #define X_SERIAL_RX_PIN X_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PC11 - #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN + #define Y_SERIAL_TX_PIN PC11 + #define Y_SERIAL_RX_PIN Y_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PC12 - #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN + #define Z_SERIAL_TX_PIN PC12 + #define Z_SERIAL_RX_PIN Z_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PC14 - #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN + #define E0_SERIAL_TX_PIN PC14 + #define E0_SERIAL_RX_PIN E0_SERIAL_TX_PIN // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 + #define TMC_BAUD_RATE 19200 #endif // diff --git a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h index 665ca0402536..dd8ef9656150 100644 --- a/Marlin/src/pins/stm32f1/pins_FLY_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_FLY_MINI.h @@ -84,13 +84,13 @@ #endif #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI EXP2_06_PIN + #define TMC_SPI_MOSI EXP2_06_PIN #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO EXP2_01_PIN + #define TMC_SPI_MISO EXP2_01_PIN #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK EXP2_02_PIN + #define TMC_SPI_SCK EXP2_02_PIN #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index c158e619d08e..6d8889733215 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -53,13 +53,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB15 + #define TMC_SPI_MOSI PB15 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB14 + #define TMC_SPI_MISO PB14 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB13 + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h index 29118ae53f8f..89fda7ab6799 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -54,13 +54,13 @@ // Software and hardware actually, they are connected to SPI2 bus. // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB15 + #define TMC_SPI_MOSI PB15 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB14 + #define TMC_SPI_MISO PB14 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB13 + #define TMC_SPI_SCK PB13 #endif #include "pins_MKS_ROBIN_E3_V1_1_common.h" // ... MKS_ROBIN_E3_common diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 8d48bcca4764..7994089619f8 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -115,13 +115,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PD14 + #define TMC_SPI_MOSI PD14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PD1 + #define TMC_SPI_MISO PD1 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PD0 + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index 22f64520b753..e1a68b32ee67 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -54,25 +54,23 @@ // Limit Switches // #ifndef NO_STOP_PINS -#if !defined(X_STOP_PIN) -#define X_STOP_PIN PA12 -#endif -#if !defined(Y_STOP_PIN) -#define Y_STOP_PIN PA11 -#endif -#if !defined(Z_STOP_PIN) -#define Z_STOP_PIN PC6 -#endif + #ifndef X_STOP_PIN + #define X_STOP_PIN PA12 + #endif + #ifndef Y_STOP_PIN + #define Y_STOP_PIN PA11 + #endif + #ifndef Z_STOP_PIN + #define Z_STOP_PIN PC6 + #endif #endif // // Z Probe // -#if HAS_BED_PROBE -#ifndef Z_MIN_PROBE_PIN +#if HAS_BED_PROBE && !defined(Z_MIN_PROBE_PIN) #define Z_MIN_PROBE_PIN PB1 #endif -#endif // // Steppers @@ -191,74 +189,64 @@ #define BEEPER_PIN EXP1_01_PIN - // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) - #if ENABLED(MKS_MINI_12864) - - #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN + #if EITHER(MKS_MINI_12864, FYSETC_MINI_12864_2_1) + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN - #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN -1 - #define DOGLCD_A0 EXP1_07_PIN - #define DOGLCD_CS EXP1_06_PIN #define DOGLCD_SCK EXP2_02_PIN #define DOGLCD_MOSI EXP2_06_PIN - - #elif ENABLED(FYSETC_MINI_12864_2_1) - - #define BTN_ENC EXP1_02_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN - - #define LCD_PINS_DC EXP1_04_PIN - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 LCD_PINS_DC + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN #define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_05_PIN - #define NEOPIXEL_PIN EXP1_06_PIN - #define DOGLCD_MOSI EXP2_06_PIN - #define DOGLCD_SCK EXP2_02_PIN - #define FORCE_SOFT_SPI - #define SOFTWARE_SPI - //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + + #if ENABLED(MKS_MINI_12864) + #define LCD_RESET_PIN -1 + #define DOGLCD_A0 EXP1_07_PIN + #define DOGLCD_CS EXP1_06_PIN + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define DOGLCD_A0 LCD_PINS_DC + #define DOGLCD_CS EXP1_03_PIN + #define LCD_PINS_DC EXP1_04_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #define FORCE_SOFT_SPI + #define SOFTWARE_SPI + //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 + #endif #elif ENABLED(MKS_TS35_V2_0) // OPTIONAL CONTROLS BESIDE THE TOUCH SCREEN // (the TS35-R V2.0 model does not have them) - #define BTN_ENC EXP1_02_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN // DISPLAY PINS. - #define TFT_A0_PIN EXP1_08_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TFT_RESET_PIN EXP1_04_PIN + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN // SPI BUS PINS. - #define TFT_SCK_PIN EXP2_02_PIN - #define TFT_MISO_PIN -1 // has to be custom soldered to work! - #define TFT_MOSI_PIN EXP2_06_PIN - #define TOUCH_SCK_PIN TFT_SCK_PIN - #define TOUCH_MISO_PIN EXP2_01_PIN - #define TOUCH_MOSI_PIN TFT_MOSI_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN -1 // Must be custom soldered to work! + #define TFT_MOSI_PIN EXP2_06_PIN + #define TOUCH_SCK_PIN TFT_SCK_PIN + #define TOUCH_MISO_PIN EXP2_01_PIN + #define TOUCH_MOSI_PIN TFT_MOSI_PIN // SPI BUS CHIP-SELECT PINS. - #define TFT_CS_PIN EXP1_07_PIN - #define TOUCH_CS_PIN EXP1_05_PIN + #define TFT_CS_PIN EXP1_07_PIN + #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_INT_PIN EXP1_06_PIN // Disable any LCD related PINs config - #define LCD_PINS_ENABLE -1 - #define LCD_PINS_RS -1 + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 - #ifndef TFT_BUFFERSIZE + #ifndef TFT_BUFFER_SIZE #define TFT_BUFFER_SIZE 1200 #endif #ifndef TFT_QUEUE_SIZE @@ -317,4 +305,4 @@ #define SD_SCK_PIN EXP2_02_PIN #define SD_MISO_PIN EXP2_01_PIN #define SD_MOSI_PIN EXP2_06_PIN -#define SD_SS_PIN EXP2_04_PIN \ No newline at end of file +#define SD_SS_PIN EXP2_04_PIN diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 712b7773ab8a..bfa6f451202b 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -125,13 +125,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PD14 + #define TMC_SPI_MOSI PD14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PD1 + #define TMC_SPI_MISO PD1 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PD0 + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index b5341082f4ea..7373d0d7b5bb 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -108,13 +108,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB15 + #define TMC_SPI_MOSI PB15 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB14 + #define TMC_SPI_MISO PB14 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB13 + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h index d03e38f05151..56200d50968b 100644 --- a/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h +++ b/Marlin/src/pins/stm32f1/pins_PANDA_PI_V29.h @@ -91,13 +91,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB5 + #define TMC_SPI_MOSI PB5 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB4 + #define TMC_SPI_MISO PB4 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB3 + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 5cdf4d00d27c..d31885e73d62 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -111,13 +111,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB15 + #define TMC_SPI_MOSI PB15 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB14 + #define TMC_SPI_MISO PB14 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB13 + #define TMC_SPI_SCK PB13 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index d1ac2557bde8..3f9e4896030b 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -205,13 +205,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PG15 + #define TMC_SPI_MOSI PG15 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB6 + #define TMC_SPI_MISO PB6 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB3 + #define TMC_SPI_SCK PB3 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index e001c2c0413a..122bc7965286 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -263,13 +263,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PA7 + #define TMC_SPI_MOSI PA7 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PA6 + #define TMC_SPI_MISO PA6 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PA5 + #define TMC_SPI_SCK PA5 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 8265f170861e..a6bff004507c 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -175,13 +175,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PC12 + #define TMC_SPI_MOSI PC12 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PC11 + #define TMC_SPI_MISO PC11 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PC10 + #define TMC_SPI_SCK PC10 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 52ab56e5c48f..76d06380b454 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -275,13 +275,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MOSI PE14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PA14 + #define TMC_SPI_MISO PA14 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PE15 + #define TMC_SPI_SCK PE15 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h index f0c9d0c16a95..8d31130d89cb 100644 --- a/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h +++ b/Marlin/src/pins/stm32f4/pins_FLYF407ZG.h @@ -238,13 +238,13 @@ // Trinamic SPI // #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK EXP2_02_PIN + #define TMC_SPI_SCK EXP2_02_PIN #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO EXP2_01_PIN + #define TMC_SPI_MISO EXP2_01_PIN #endif #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI EXP2_06_PIN + #define TMC_SPI_MOSI EXP2_06_PIN #endif // diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h index f42672c96cec..a6035c2c6f01 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_S6_V2_0.h @@ -57,13 +57,13 @@ // #define TMC_USE_SW_SPI #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MOSI PE14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PE13 + #define TMC_SPI_MISO PE13 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PE12 + #define TMC_SPI_SCK PE12 #endif #include "pins_FYSETC_S6.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h index 7c702106cdfe..368f464f86ca 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER.h @@ -105,13 +105,13 @@ // #define TMC_USE_SW_SPI #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MOSI PE14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PE13 + #define TMC_SPI_MISO PE13 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PE12 + #define TMC_SPI_SCK PE12 #endif #if HOTENDS > 3 || E_STEPPERS > 3 diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 416fece66aad..117a5707ee8a 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -135,13 +135,16 @@ #define TMC_USE_SW_SPI #endif #if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 - #define TMC_SPI_MOSI PE14 + #undef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 #endif #if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 - #define TMC_SPI_MISO PE13 + #undef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 #endif #if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 - #define TMC_SPI_SCK PE12 + #undef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 6029f1c91b33..96e19c987f78 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -58,13 +58,16 @@ #define TMC_USE_SW_SPI #endif #if !defined(TMC_SPI_MOSI) || TMC_SPI_MOSI == -1 - #define TMC_SPI_MOSI PD14 + #undef TMC_SPI_MOSI + #define TMC_SPI_MOSI PD14 #endif #if !defined(TMC_SPI_MISO) || TMC_SPI_MISO == -1 - #define TMC_SPI_MISO PD1 + #undef TMC_SPI_MISO + #define TMC_SPI_MISO PD1 #endif #if !defined(TMC_SPI_SCK) || TMC_SPI_SCK == -1 - #define TMC_SPI_SCK PD0 + #undef TMC_SPI_SCK + #define TMC_SPI_SCK PD0 #endif #include "pins_MKS_ROBIN_NANO_V3_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index cac9c22fe5b5..f427e90f5943 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -116,13 +116,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PD14 + #define TMC_SPI_MOSI PD14 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PD1 + #define TMC_SPI_MISO PD1 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PD0 + #define TMC_SPI_SCK PD0 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h index 26510508a90c..6ff99b984e23 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h @@ -200,9 +200,9 @@ // #if HAS_TMC_SPI #define TMC_USE_SW_SPI - #define TMC_SPI_MOSI PE14 - #define TMC_SPI_MISO PE13 - #define TMC_SPI_SCK PE12 + #define TMC_SPI_MOSI PE14 + #define TMC_SPI_MISO PE13 + #define TMC_SPI_SCK PE12 #endif // diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h index 7d598fc2ab99..cf4720a20c6b 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV3.h @@ -171,9 +171,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SPI_MISO MISO_PIN -#define TMC_SPI_MOSI MOSI_PIN -#define TMC_SPI_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h index 386da6ec1492..c8da0af8949c 100644 --- a/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h +++ b/Marlin/src/pins/stm32f4/pins_OPULO_LUMEN_REV4.h @@ -168,9 +168,9 @@ #define MOSI_PIN PB5 #define SCK_PIN PB3 -#define TMC_SPI_MISO MISO_PIN -#define TMC_SPI_MOSI MOSI_PIN -#define TMC_SPI_SCK SCK_PIN +#define TMC_SPI_MISO MISO_PIN +#define TMC_SPI_MOSI MOSI_PIN +#define TMC_SPI_SCK SCK_PIN // // I2C diff --git a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h index 5c50e51a2631..264bb91af436 100644 --- a/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h +++ b/Marlin/src/pins/stm32f4/pins_RUMBA32_common.h @@ -92,13 +92,13 @@ #define E2_CS_PIN PD1 #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PA7 + #define TMC_SPI_MOSI PA7 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PA6 + #define TMC_SPI_MISO PA6 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PA5 + #define TMC_SPI_SCK PA5 #endif // diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h index 918f159522ca..c3236de5aa37 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h @@ -96,13 +96,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PC6 + #define TMC_SPI_MOSI PC6 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PG3 + #define TMC_SPI_MISO PG3 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PC7 + #define TMC_SPI_SCK PC7 #endif #if HAS_TMC_UART diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index d6cb4fef2e72..d8e41b9e5712 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -265,13 +265,13 @@ // SPI pins for TMC2130 stepper drivers // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PE13 + #define TMC_SPI_MOSI PE13 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PE15 + #define TMC_SPI_MISO PE15 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PE14 + #define TMC_SPI_SCK PE14 #endif #if HAS_TMC_UART diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 1f2ecf10f2d8..f5e725b6a3fe 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -130,12 +130,12 @@ bool MAX3421e::start() { const uint8_t revision = regRd(rREVISION); if (revision == 0x00 || revision == 0xFF) { SERIAL_ECHOLNPGM("Revision register appears incorrect on MAX3421e initialization. Got ", revision); - goto fail; + return false; } if (!reset()) { SERIAL_ECHOLNPGM("OSCOKIRQ hasn't asserted in time"); - goto fail; + return false; } // Delay a minimum of 1 second to ensure any capacitors are drained. @@ -159,8 +159,6 @@ bool MAX3421e::start() { regWr(rPINCTL, bmFDUPSPI | bmINTLEVEL); return true; -fail: - return false; } // Probe bus to determine device presence and speed. Switch host to this speed. From e5ce7956074aed2e3b9c5b89b7dfa4d7e8eefea5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Oct 2022 13:31:37 -0500 Subject: [PATCH 14/83] Keep 'static' for DMA --- Marlin/src/HAL/LPC1768/tft/tft_spi.h | 4 ++-- Marlin/src/HAL/STM32/tft/tft_fsmc.h | 4 ++-- Marlin/src/HAL/STM32/tft/tft_ltdc.h | 4 ++-- Marlin/src/HAL/STM32/tft/tft_spi.h | 4 ++-- Marlin/src/HAL/STM32F1/tft/tft_fsmc.h | 4 ++-- Marlin/src/HAL/STM32F1/tft/tft_spi.h | 4 ++-- Marlin/src/lcd/tft_io/tft_io.h | 2 +- 7 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.h b/Marlin/src/HAL/LPC1768/tft/tft_spi.h index a9b0c3d534e0..4753fdbae9a0 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.h +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.h @@ -63,9 +63,9 @@ class TFT_SPI { static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - // static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; //LPC dma can only write 0xFFF bytes at once. #define MAX_DMA_SIZE (0xFFF - 1) while (Count > 0) { diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index 3456ea5dba7f..2200abaa10e8 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -74,9 +74,9 @@ class TFT_FSMC { static void WriteReg(uint16_t Reg) { LCD->REG = tft_data_t(Reg); __DSB(); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_PINC_DISABLE, &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) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h index 8eaf880f4602..7b63d6929b31 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.h +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -64,9 +64,9 @@ class TFT_LTDC { 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) { uint16_t Data = Color; TransmitDMA(DMA_PINC_DISABLE, &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) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/STM32/tft/tft_spi.h index fac69ae4f541..2d43e46f0a06 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32/tft/tft_spi.h @@ -89,9 +89,9 @@ class TFT_SPI { static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { TransmitDMA_IT(DMA_MINC_ENABLE, Data, Count); } #endif - static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h index 89b5bdf9dd20..d9ee1f4c7767 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_fsmc.h @@ -60,9 +60,9 @@ class TFT_FSMC { static void WriteReg(uint16_t Reg); static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; while (Count > 0) { TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.h b/Marlin/src/HAL/STM32F1/tft/tft_spi.h index 1b13d06bb3f3..da9a8e0c223e 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.h +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.h @@ -61,9 +61,9 @@ class TFT_SPI { static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } static void WriteMultiple(uint16_t Color, uint32_t Count) { - uint16_t Data = Color; + static uint16_t Data; Data = Color; while (Count > 0) { TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 1f387272335c..50b921cd2a93 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -126,7 +126,7 @@ class TFT_IO { inline static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { io.WriteSequenceIT(Data, Count); }; #endif - // static void WriteMultiple(uint16_t Color, uint16_t Count) { uint16_t Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } inline static void WriteMultiple(uint16_t Color, uint32_t Count) { io.WriteMultiple(Color, Count); }; protected: From 9f2193d71d31ca825ab6d04e8f8639dbdf3220ab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Oct 2022 13:50:29 -0500 Subject: [PATCH 15/83] Fix macros --- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 956985012588..c83cb1c3ca30 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -194,11 +194,9 @@ void TFT_SPI::HAL_SPI_Prepare(eSPIMode spiMode) { void TFT_SPI::HAL_SPI_Dismantle() { #ifdef STM32F1xx - #define _DMATX_DISMANTLE(N1,N4) \ - __HAL_RCC_DMA##N1##_CLK_DISABLE(); \ + #define _DMATX_DISMANTLE(N1,N4) __HAL_RCC_DMA##N1##_CLK_DISABLE() #elif defined(STM32F4xx) - #define _DMATX_DISMANTLE(N1,N4) \ - __HAL_RCC_DMA##N4##_CLK_DISABLE(); \ + #define _DMATX_DISMANTLE(N1,N4) __HAL_RCC_DMA##N4##_CLK_DISABLE() #else #define _DMATX_DISMANTLE(...) NOOP #endif From 94a9bca76c6d7edf19acd9cefb9e042f9822a69b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Oct 2022 13:50:48 -0500 Subject: [PATCH 16/83] Try success flag --- Marlin/src/HAL/STM32/msc_sd.cpp | 24 +++++++++++------------- 1 file changed, 11 insertions(+), 13 deletions(-) diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index a8d964d76cbf..2f10b27769ce 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -65,19 +65,17 @@ class Sd2CardUSBMscHandler : public USBMscHandler { return sd2card->writeBlock(blkAddr, pBuf); } - // multi block optimization - bool done = false, success = true; - uint8_t *cBuf = pBuf; + bool success = true; sd2card->writeStart(blkAddr); while (blkLen--) { hal.watchdog_refresh(); uint8_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; - while (sd2card->writeData(cBuf) == false && multi_retry_cnt) --multi_retry_cnt; - sd2card->writeStop(); - if (multi_retry_cnt <= 0) return false; - cBuf += BLOCK_SIZE; + while (!(success = sd2card->writeData(pBuf)) && multi_retry_cnt--) { /* retry... */ } + if (!success) break; + pBuf += BLOCK_SIZE; } - return true; + sd2card->writeStop(); + return success; } bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) { @@ -88,17 +86,17 @@ class Sd2CardUSBMscHandler : public USBMscHandler { return sd2card->readBlock(blkAddr, pBuf); } - // multi block optimization + bool success = true; sd2card->readStart(blkAddr); while (blkLen--) { hal.watchdog_refresh(); uint8_t multi_retry_cnt = SD_MULTIBLOCK_READ_RETRY_CNT; - while (sd2card->readData(pBuf) == false && multi_retry_cnt) --multi_retry_cnt; - sd2card->readStop(); - if (multi_retry_cnt <= 0) return false; + while (!(success = sd2card->readData(pBuf)) && multi_retry_cnt--) { /* retry... */ } + if (!success) break; pBuf += BLOCK_SIZE; } - return true; + sd2card->readStop(); + return success; } bool IsReady() { From 979abe2b0062ab060261e250b5b2139331b769cd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Oct 2022 15:39:15 -0500 Subject: [PATCH 17/83] 8 bit rate enum --- Marlin/src/HAL/LPC1768/include/SPI.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h index a319f86dd24c..0076c84b7b80 100644 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ b/Marlin/src/HAL/LPC1768/include/SPI.h @@ -62,7 +62,7 @@ class SPISettings { public: - SPISettings(uint32_t spiRate, int inBitOrder, int inDataMode) { + SPISettings(uint8_t spiRate, int inBitOrder, int inDataMode) { init_AlwaysInline(spiRate2Clock(spiRate), inBitOrder, inDataMode, DATA_SIZE_8BIT); } SPISettings(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) { @@ -77,7 +77,7 @@ class SPISettings { //uint32_t spiRate() const { return spi_speed; } - static uint32_t spiRate2Clock(uint32_t spiRate) { + static uint32_t spiRate2Clock(uint8_t spiRate) { constexpr uint32_t Marlin_speed[] = { // CPSR is always 2 SPI_CLOCK_DIV2, //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED SPI_CLOCK_DIV4, //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED From b8345f82ca202609589fd3c06cfb52b90ca282c1 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 24 Nov 2022 13:21:47 +0100 Subject: [PATCH 18/83] - added global HAL SPI layer with STM32, ESP32 and LPC176x/LPC175x unique (reference) implementations This is the big HAL SPI update you have been waiting for! It fixes the SPI bus sharing problem for good, laying a strong foundation for the Marlin FW SPI into the future. All brought to you by Martin Turski, company owner of EirDev. CHANGELOG: * added ESP32 unique HAL SPI * added LPC1768 unique HAL SPI (needs testing because I got a broken board) * tft_spi.cpp is now a generic class (SPI ccreen support for virtually every SPI capable controller board) * xpt2046.cpp is not a generic class (generic touch screen support comes closer!) * further global SPI refactoring, removing use of the generic Arduino SPIClass in favor of the new & better HAL SPI interface * removed obsolete code (MarlinSPI) * added HAL NVIC (ARM) for proofed interrupt management (shared between STM32 and LPC1768) * removed some arbitrary Marlin FW limits related to shared SPI bus (may not have caught all thus I need the support for the Marlin FW community for testing) * made drawing to the screen asynchronous for color UI (if it is supported by enabling USE_SPI_DMA_TC, only on supported boards!) * merged ARM exception handling code with the new HAL NVIC code * added some ARM exception management helpers (BEEP_ON_SYSTEM_EXCEPTION) * added HALSPI_DO_ERRORBEEPS, HALSPI_DO_LOOPBEEPS, HALSPI_ESP32_STATIC_DMADESCS, HALSPI_DMA_ALWAYS, HALSPI_DEBUG, HALSPI_DISABLE_DMA, HALSPI_LOOPBEEP_TIMEOUT, HALSPI_DMA_THRESHOLD configuration preprocessor definitions for HAL SPI * added HAL_SPI_SUPPORTS_ASYNC option: if defined then the SPI async interface (spiWriteAsync, spiWriteAsync16, spiAsyncAbort, spiAsyncJoin, spiAsyncIsRunning) is available * improved SD_WRITE_TIMEOUT, SD_ERASE_TIMEOUT, SD_INIT_TIMEOUT, SD_READ_TIMEOUT SD-card timeout variables: they can now be disabled to allow for no-timeout at SD card operations (use with caution!) * added SD_DISABLE_TIMEOUTS preprocessor option: if defined in your configuration then the default SD card timeout variables are not applied, if previous config of them is missing HAL SPI has been thoroughly tested on the STM32 and ESP32 implementations! The generic SPI has been working fine on the LPC1768 (needs further testing, I will get a fully working board soon). Have fun! --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 216 +- Marlin/src/HAL/AVR/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/DUE/HAL_SPI.cpp | 434 ++- .../dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp | 5 +- Marlin/src/HAL/DUE/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/ESP32/HAL_SPI.cpp | 118 - Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 2587 +++++++++++++++++ Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp | 277 ++ .../{AVR/MarlinSPI.h => ESP32/HAL_SPI_SW.cpp} | 20 +- Marlin/src/HAL/ESP32/MarlinSPI.h | 26 - Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp | 3 +- Marlin/src/HAL/LINUX/MarlinSPI.h | 26 - Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/LINUX/spi_pins.h | 2 +- Marlin/src/HAL/LPC1768/HAL.h | 8 + Marlin/src/HAL/LPC1768/HAL_SPI.cpp | 423 --- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 2569 ++++++++++++++++ Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp | 212 ++ Marlin/src/HAL/LPC1768/MarlinSPI.h | 45 - Marlin/src/HAL/LPC1768/include/SPI.h | 182 -- Marlin/src/HAL/LPC1768/main.cpp | 4 + Marlin/src/HAL/LPC1768/spi_pins.h | 7 - Marlin/src/HAL/LPC1768/tft/tft_spi.cpp | 130 - Marlin/src/HAL/LPC1768/tft/tft_spi.h | 77 - Marlin/src/HAL/LPC1768/tft/xpt2046.h | 83 - .../u8g/u8g_com_HAL_LPC1768_hw_spi.cpp | 3 +- .../u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 5 +- Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h | 26 - Marlin/src/HAL/NATIVE_SIM/spi_pins.h | 2 +- Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h | 7 +- Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h | 10 - Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 88 +- Marlin/src/HAL/SAMD51/MarlinSPI.h | 26 - Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/STM32/HAL.cpp | 4 + Marlin/src/HAL/STM32/HAL_SPI_HW.cpp | 1303 +++++++++ Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp | 202 ++ .../HAL/STM32/{HAL_SPI.cpp => HAL_SPI_SW.cpp} | 215 +- Marlin/src/HAL/STM32/MarlinSPI.cpp | 178 -- Marlin/src/HAL/STM32/MarlinSPI.h | 107 - Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 2 +- Marlin/src/HAL/STM32/tft/tft_fsmc.h | 6 +- Marlin/src/HAL/STM32/tft/tft_ltdc.h | 8 +- Marlin/src/HAL/STM32/tft/tft_spi.cpp | 506 ---- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 332 --- Marlin/src/HAL/STM32F1/HAL_SPI.cpp | 176 -- Marlin/src/HAL/STM32F1/MarlinSPI.h | 45 - Marlin/src/HAL/STM32F1/tft/tft_spi.cpp | 129 - Marlin/src/HAL/STM32F1/tft/tft_spi.h | 72 - Marlin/src/HAL/STM32F1/tft/xpt2046.cpp | 144 - Marlin/src/HAL/STM32F1/tft/xpt2046.h | 83 - Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 94 +- Marlin/src/HAL/TEENSY31_32/MarlinSPI.h | 26 - .../HAL/TEENSY31_32/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 94 +- Marlin/src/HAL/TEENSY35_36/MarlinSPI.h | 26 - .../HAL/TEENSY35_36/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 93 +- Marlin/src/HAL/TEENSY40_41/MarlinSPI.h | 26 - .../HAL/TEENSY40_41/inc/Conditionals_LCD.h | 4 +- Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp | 177 ++ .../MarlinSPI.h => shared/ARM/HAL_NVIC.h} | 20 +- Marlin/src/HAL/shared/HAL_SPI.h | 84 +- Marlin/src/HAL/shared/SPI/bufmgmt.h | 65 + .../shared/cpu_exception/exception_arm.cpp | 192 +- Marlin/src/HAL/shared/tft/tft_spi.cpp | 155 + .../src/HAL/{STM32 => shared}/tft/tft_spi.h | 58 +- .../HAL/{LPC1768 => shared}/tft/xpt2046.cpp | 117 +- .../src/HAL/{STM32 => shared}/tft/xpt2046.h | 18 - Marlin/src/MarlinCore.cpp | 2 + Marlin/src/feature/dac/dac_dac084s085.cpp | 4 +- Marlin/src/feature/tmc_util.h | 14 +- Marlin/src/gcode/control/M993_M994.cpp | 2 + Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 67 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h | 3 + .../dogm/u8g_dev_tft_upscale_from_128x64.cpp | 16 +- .../ftdi_eve_lib/basic/spi.cpp | 13 +- .../ftdi_eve_lib/basic/spi.h | 17 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 4 + Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp | 2 - Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 12 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 10 + .../extui/mks_ui/tft_lvgl_configuration.cpp | 28 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/lcd/menu/menu_x_twist.cpp | 2 +- Marlin/src/lcd/tft/canvas.cpp | 6 +- Marlin/src/lcd/tft/tft.h | 10 +- Marlin/src/lcd/tft/touch.cpp | 52 +- Marlin/src/lcd/tft/touch.h | 10 +- Marlin/src/lcd/tft/ui_1024x600.cpp | 52 +- Marlin/src/lcd/tft/ui_320x240.cpp | 48 +- Marlin/src/lcd/tft/ui_480x320.cpp | 54 +- Marlin/src/lcd/tft/ui_common.cpp | 8 +- Marlin/src/lcd/tft_io/tft_io.cpp | 76 +- Marlin/src/lcd/tft_io/tft_io.h | 22 +- Marlin/src/lcd/touch/touch_buttons.cpp | 2 +- Marlin/src/libs/MAX31865.cpp | 23 +- Marlin/src/libs/MAX31865.h | 3 - Marlin/src/libs/W25Qxx.cpp | 26 +- Marlin/src/libs/W25Qxx.h | 5 +- Marlin/src/module/stepper.cpp | 12 +- Marlin/src/module/stepper/TMC26X.h | 1 - Marlin/src/module/stepper/trinamic.cpp | 41 +- Marlin/src/module/temperature.cpp | 3 +- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 92 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 2 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 3 - Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 74 +- Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 3 + Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 2 +- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 6 +- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 6 +- Marlin/src/pins/pinsDebug_list.h | 9 + .../pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h | 3 - Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h | 2 - Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 9 +- .../src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h | 9 +- .../pins/stm32f1/pins_MKS_ROBIN_NANO_common.h | 3 - Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h | 2 - .../pins/stm32f4/pins_MKS_MONSTER8_common.h | 3 - .../stm32f4/pins_MKS_ROBIN_NANO_V3_common.h | 3 - .../src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h | 3 - Marlin/src/sd/Sd2Card.cpp | 103 +- Marlin/src/sd/Sd2Card.h | 23 +- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 4 - ini/features.ini | 5 +- ini/lpc176x.ini | 2 +- ini/stm32-common.ini | 2 +- 129 files changed, 9558 insertions(+), 3877 deletions(-) delete mode 100644 Marlin/src/HAL/ESP32/HAL_SPI.cpp create mode 100644 Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp create mode 100644 Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp rename Marlin/src/HAL/{AVR/MarlinSPI.h => ESP32/HAL_SPI_SW.cpp} (67%) delete mode 100644 Marlin/src/HAL/ESP32/MarlinSPI.h delete mode 100644 Marlin/src/HAL/LINUX/MarlinSPI.h delete mode 100644 Marlin/src/HAL/LPC1768/HAL_SPI.cpp create mode 100644 Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp create mode 100644 Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp delete mode 100644 Marlin/src/HAL/LPC1768/MarlinSPI.h delete mode 100644 Marlin/src/HAL/LPC1768/include/SPI.h delete mode 100644 Marlin/src/HAL/LPC1768/tft/tft_spi.cpp delete mode 100644 Marlin/src/HAL/LPC1768/tft/tft_spi.h delete mode 100644 Marlin/src/HAL/LPC1768/tft/xpt2046.h delete mode 100644 Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h delete mode 100644 Marlin/src/HAL/SAMD51/MarlinSPI.h create mode 100644 Marlin/src/HAL/STM32/HAL_SPI_HW.cpp create mode 100644 Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp rename Marlin/src/HAL/STM32/{HAL_SPI.cpp => HAL_SPI_SW.cpp} (57%) delete mode 100644 Marlin/src/HAL/STM32/MarlinSPI.cpp delete mode 100644 Marlin/src/HAL/STM32/MarlinSPI.h delete mode 100644 Marlin/src/HAL/STM32/tft/tft_spi.cpp delete mode 100644 Marlin/src/HAL/STM32/tft/xpt2046.cpp delete mode 100644 Marlin/src/HAL/STM32F1/HAL_SPI.cpp delete mode 100644 Marlin/src/HAL/STM32F1/MarlinSPI.h delete mode 100644 Marlin/src/HAL/STM32F1/tft/tft_spi.cpp delete mode 100644 Marlin/src/HAL/STM32F1/tft/tft_spi.h delete mode 100644 Marlin/src/HAL/STM32F1/tft/xpt2046.cpp delete mode 100644 Marlin/src/HAL/STM32F1/tft/xpt2046.h delete mode 100644 Marlin/src/HAL/TEENSY31_32/MarlinSPI.h delete mode 100644 Marlin/src/HAL/TEENSY35_36/MarlinSPI.h delete mode 100644 Marlin/src/HAL/TEENSY40_41/MarlinSPI.h create mode 100644 Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp rename Marlin/src/HAL/{DUE/MarlinSPI.h => shared/ARM/HAL_NVIC.h} (57%) create mode 100644 Marlin/src/HAL/shared/SPI/bufmgmt.h create mode 100644 Marlin/src/HAL/shared/tft/tft_spi.cpp rename Marlin/src/HAL/{STM32 => shared}/tft/tft_spi.h (50%) rename Marlin/src/HAL/{LPC1768 => shared}/tft/xpt2046.cpp (50%) rename Marlin/src/HAL/{STM32 => shared}/tft/xpt2046.h (77%) diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index 6d925097f74b..e59316219787 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -77,29 +77,94 @@ void spiBegin() { , PRSPI ); + // DORD is set to 0 -> MSB transfer, else LSB + SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1); SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X); } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint8_t spiRate; + if (maxClockFreq >= 20000000) { + spiRate = SPI_FULL_SPEED; + } + else if (maxClockFreq >= 5000000) { + spiRate = SPI_HALF_SPEED; + } + else if (maxClockFreq >= 2500000) { + spiRate = SPI_QUARTER_SPEED; + } + else if (maxClockFreq >= 1250000) { + spiRate = SPI_EIGHTH_SPEED; + } + else if (maxClockFreq >= 625000) { + spiRate = SPI_SPEED_5; + } + else if (maxClockFreq >= 300000) { + spiRate = SPI_SPEED_6; + } + else + spiRate = SPI_SPEED_6; + + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); + } + void spiClose() { // nop. } + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + SPCR &= ~_BV(DORD); + } + else if (bitOrder == SPI_BITORDER_LSB) { + SPCR |= _BV(DORD); + } + } + + void spiSetClockMode(int clockMode) { + // TODO. + if (clockMode != SPI_CLKMODE_0) { + for (;;) {} + } + } + /** SPI receive a byte */ - uint8_t spiRec() { - SPDR = 0xFF; + uint8_t spiRec(uint8_t txval) { + SPDR = txval; while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } return SPDR; } + uint16_t spiRec16(uint16_t txval) { + bool msb = ( TEST(SPCR, DORD) == false ); + uint8_t tx_first, tx_second; + if (msb) { + tx_first = ( txval >> 8 ); + tx_second = ( txval & 0xFF ); + } + else { + tx_first = ( txval & 0xFF ); + tx_second = ( txval >> 8 ); + } + SPDR = tx_first; + while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + uint16_t val = ( msb ? ( (uint16_t)SPDR << 8 ) : ( SPDR ) ); + SPDR = tx_second; + while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + val |= ( msb ? ( SPDR ) : ( (uint16_t)SPDR << 8 ) ); + return val; + } + /** SPI read data */ - void spiRead(uint8_t *buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { if (nbyte-- == 0) return; - SPDR = 0xFF; + SPDR = txval; for (uint16_t i = 0; i < nbyte; i++) { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } buf[i] = SPDR; - SPDR = 0xFF; + SPDR = txval; } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } buf[nbyte] = SPDR; @@ -111,6 +176,14 @@ void spiBegin() { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } + void spiSend16(uint16_t v) { + bool msb = ( TEST(SPCR, DORD) == false ); + SPDR = ( msb ? ( v >> 8 ) : ( v & 0xFF ) ); + while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + SPDR = ( msb ? ( v & 0xFF ) : ( v >> 8 ) ); + while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } + } + /** SPI send block */ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = token; @@ -123,8 +196,28 @@ void spiBegin() { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } + void spiWrite(const uint8_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } - /** begin spi transaction */ + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } + +#if 0 + /** begin spi transaction (TODO: merge ideas into spiInitEx) */ void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { // Based on Arduino SPI library // Clock settings are defined as follows. Note that this shows SPI2X @@ -178,6 +271,7 @@ void spiBegin() { (dataMode << CPHA) | ((clockDiv >> 1) << SPR0); SPSR = clockDiv | 0x01; } +#endif #else // SOFTWARE_SPI || FORCE_SOFT_SPI @@ -189,29 +283,79 @@ void spiBegin() { // nop to tune soft SPI timing #define nop asm volatile ("\tnop\n") + static int _spi_bit_order = SPI_BITORDER_DEFAULT; + void spiInit(uint8_t, int, int, int, int) { /* do nothing */ } + void spiInitEx(uint32_t, int, int, int, int) { /* do nothing */ } void spiClose() { /* do nothing */ } - // Begin SPI transaction, set clock, bit order, data mode - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } + void spiSetBitOrder(int bitOrder) { + _spi_bit_order = bitOrder; + } + + void spiSetClockMode(int clockMode) { + // TODO. + if (clockMode != SPI_CLKMODE_0) { + for (;;) {} + } + } // Soft SPI receive byte - uint8_t spiRec() { + uint8_t spiRec(uint8_t txval) { + if (txval != 0xFF) { + // TODO. + for (;;) {} + } uint8_t data = 0; // no interrupts during byte receive - about 8µs cli(); // output pin high - like sending 0xFF WRITE(SD_MOSI_PIN, HIGH); + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + LOOP_L_N(i, 8) { WRITE(SD_SCK_PIN, HIGH); nop; // adjust so SCK is nice nop; - data <<= 1; + if (READ(SD_MISO_PIN)) + { + int bitidx = ( msb ? 7-i : i ); + data |= ( 1 << bitidx ); + } + + WRITE(SD_SCK_PIN, LOW); + } - if (READ(SD_MISO_PIN)) data |= 1; + sei(); + return data; + } + + uint16_t spiRec16(uint16_t txval) { + if (txval != 0xFFFF) { + // TODO. + for (;;) {} + } + uint16_t data = 0; + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + // no interrupts during byte receive - about 8µs + cli(); + // output pin high - like sending 0xFF + WRITE(SD_MOSI_PIN, HIGH); + + LOOP_L_N(i, 16) { + WRITE(SD_SCK_PIN, HIGH); + + nop; // adjust so SCK is nice + nop; + + if (READ(SD_MISO_PIN)) + { + int bitidx = ( msb ? 15-i : i ); + data |= ( 1 << bitidx ); + } WRITE(SD_SCK_PIN, LOW); } @@ -221,19 +365,41 @@ void spiBegin() { } // Soft SPI read data - void spiRead(uint8_t *buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { for (uint16_t i = 0; i < nbyte; i++) - buf[i] = spiRec(); + buf[i] = spiRec(txval); } // Soft SPI send byte void spiSend(uint8_t data) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); // no interrupts during byte send - about 8µs cli(); LOOP_L_N(i, 8) { + int bitidx = ( msb ? 7-i : i ); + WRITE(SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, ( data & ( 1 << bitidx )) != 0); + WRITE(SD_SCK_PIN, HIGH); + } + + nop; // hold SCK high for a few ns + nop; + nop; + nop; + + WRITE(SD_SCK_PIN, LOW); + + sei(); + } + + void spiSend16(uint16_t v) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + // no interrupts during byte send - about 8µs + cli(); + LOOP_L_N(i, 16) { + int bitidx = ( msb ? 15-i : i ); WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, data & 0x80); - data <<= 1; + WRITE(SD_MOSI_PIN, ( data & ( 1 << bitidx )) != 0); WRITE(SD_SCK_PIN, HIGH); } @@ -254,6 +420,26 @@ void spiBegin() { spiSend(buf[i]); } + void spiWrite(const uint8_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } + #endif // SOFTWARE_SPI || FORCE_SOFT_SPI #endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h index a611ccd7c4a9..c747509990de 100644 --- a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/AVR." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/AVR." #endif diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index efb06aba58f8..ff557b4de242 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -263,6 +263,7 @@ * Note: The cast is unnecessary, but without it, this file triggers a GCC 4.8.3-2014 bug. * Later GCC versions do not have this problem, but at this time (May 2018) Arduino still * uses that buggy and obsolete GCC version!! + * They are implemented to handle MSB transfers. */ static pfnSpiTransfer spiTransferRx = (pfnSpiTransfer)spiTransferX; static pfnSpiTransfer spiTransferTx = (pfnSpiTransfer)spiTransferX; @@ -423,15 +424,39 @@ ); } + static inline uint8_t _flip_bits_8(uint8_t v) { + uint8_t result = 0; + for (int n = 0; n < 8; n++) + { + result <<= 1; + bool bitval = ( v & ( 1 << n ) ) != 0; + result |= bitval; + } + return result; + } + + static inline uint8_t _spiTransferRx_ordered(uint8_t txval) + { + return ( _spi_bit_order == SPI_BITORDER_MSB ? spiTransferRx(txval) : _flip_bits_8(spiTransferRx(_flip_bits_8(txval))) ); + } + + static inline void _spiTransferTx_ordered(uint8_t b) { + if ( _spi_bit_order == SPI_BITORDER_LSB ) + { + b = _flip_bits_8(b); + } + (void)spiTransferTx(b); + } + static void spiTxBlockX(const uint8_t *buf, uint32_t todo) { do { - (void)spiTransferTx(*buf++); + _spiTransferTx_ordered(*buf++); } while (--todo); } static void spiRxBlockX(uint8_t *buf, uint32_t todo) { do { - *buf++ = spiTransferRx(0xFF); + *buf++ = _spiTransferRx_ordered(); } while (--todo); } @@ -439,6 +464,8 @@ static pfnSpiTxBlock spiTxBlock = (pfnSpiTxBlock)spiTxBlockX; static pfnSpiRxBlock spiRxBlock = (pfnSpiRxBlock)spiRxBlockX; + static int _spi_bit_order = SPI_BITORDER_DEFAULT; + #if MB(ALLIGATOR) #define _SS_WRITE(S) WRITE(SD_SS_PIN, S) #else @@ -453,16 +480,50 @@ SET_OUTPUT(SD_MOSI_PIN); } - uint8_t spiRec() { + void spiSetBitOrder(int bitOrder) { + _spi_bit_order = bitOrder; + } + + void spiSetClockMode(int clockMode) { + if (clockMode != SPI_CLKMODE_0) { + // TODO. + for (;;) {} + } + } + + uint8_t spiRec(uint8_t txval) { _SS_WRITE(LOW); WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 - uint8_t b = spiTransferRx(0xFF); + uint8_t b = _spiTransferRx_ordered(txval); _SS_WRITE(HIGH); return b; } - void spiRead(uint8_t *buf, uint16_t nbyte) { + uint16_t spiRec16(uint16_t txval) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + uint8_t tx_first, tx_second; + if (msb) { + tx_first = ( txval >> 8 ); + tx_second = ( txval & 0xFF ); + } + else { + tx_first = ( txval & 0xFF ); + tx_second = ( txval >> 8 ); + } + _SS_WRITE(LOW); + WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 + uint16_t v = ( msb ? ( (uint16_t)_spiTransferRx_ordered(tx_first) << 8 ) : _spiTransferRx_ordered(tx_first) ); + v |= ( msb ? _spiTransferRx_ordered(tx_second) : ( (uint16_t)_spiTransferRx_ordered(tx_second) << 8 ) ); + _SS_WRITE(HIGH); + return v; + } + + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { if (nbyte) { + if (txval != 0xFF) { + // TODO. + for (;;) {} + } _SS_WRITE(LOW); WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 spiRxBlock(buf, nbyte); @@ -472,17 +533,58 @@ void spiSend(uint8_t b) { _SS_WRITE(LOW); - (void)spiTransferTx(b); + _spiTransferTx_ordered(b); + _SS_WRITE(HIGH); + } + + static void _spiSend16Internal(uint16_t v, bool msb) { + _spiTransferTx_ordered(msb ? ( v >> 8 ) : ( v & 0xFF )); + _spiTransferTx_ordered(msb ? ( v & 0xFF ) : ( v >> 8 )); + } + + void spiSend16(uint16_t v) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + _SS_WRITE(LOW); + _spiSend16Internal(v); _SS_WRITE(HIGH); } void spiSendBlock(uint8_t token, const uint8_t *buf) { _SS_WRITE(LOW); - (void)spiTransferTx(token); + _spiTransferTx_ordered(token); spiTxBlock(buf, 512); _SS_WRITE(HIGH); } + void spiWrite(const uint8_t *buf, uint16_t cnt) { + _SS_WRITE(LOW); + spiTxBlock(buf, cnt); + _SS_WRITE(HIGH); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + _SS_WRITE(LOW); + for (uint16_t n = 0; n < cnt; n++) + _spiSend16Internal(buf[n], msb); + _SS_WRITE(HIGH); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + _SS_WRITE(LOW); + for (uint16_t n = 0; n < repcnt; n++) + _spiTransferTx_ordered(val); + _SS_WRITE(HIGH); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + _SS_WRITE(LOW); + for (uint16_t n = 0; n < repcnt; n++) + _spiSend16Internal(val, msb); + _SS_WRITE(HIGH); + } + /** * spiRate should be * 0 : 8 - 10 MHz @@ -494,6 +596,8 @@ * 6 : 125 - 156 kHz */ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore pin hints... TODO? + switch (spiRate) { case 0: spiTransferTx = (pfnSpiTransfer)spiTransferTx0; @@ -521,13 +625,35 @@ WRITE(SD_SCK_PIN, LOW); } - void spiClose() {} - - /** Begin SPI transaction, set clock, bit order, data mode */ - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - // TODO: to be implemented + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint8_t spiRate; + if (maxClockFreq >= 20000000) { + spiRate = SPI_FULL_SPEED; + } + else if (maxClockFreq >= 5000000) { + spiRate = SPI_HALF_SPEED; + } + else if (maxClockFreq >= 2500000) { + spiRate = SPI_QUARTER_SPEED; + } + else if (maxClockFreq >= 1250000) { + spiRate = SPI_EIGHTH_SPEED; + } + else if (maxClockFreq >= 625000) { + spiRate = SPI_SPEED_5; + } + else if (maxClockFreq >= 300000) { + spiRate = SPI_SPEED_6; + } + else + spiRate = SPI_SPEED_6; + + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); } + void spiClose() {} + #pragma GCC reset_options #else // !SOFTWARE_SPI @@ -545,25 +671,20 @@ static bool _has_spi_pins = false; static int _spi_pin_cs; // all SPI pins are tied together (CS, MISO, MOSI, SCK) + static uint32_t _spi_clock; + static int _spi_bitOrder; + static int _spi_clockMode; + // ------------------------ // hardware SPI // https://github.com/arduino/ArduinoCore-sam/blob/master/libraries/SPI/src/SPI.h // ------------------------ void spiBegin() {} - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - // Use datarates Marlin uses - uint32_t clock; - switch (spiRate) { - case SPI_FULL_SPEED: clock = 8000000; break; - case SPI_HALF_SPEED: clock = 4000000; break; - case SPI_QUARTER_SPEED: clock = 2000000; break; - case SPI_EIGHTH_SPEED: clock = 1000000; break; - case SPI_SIXTEENTH_SPEED: clock = 500000; break; - case SPI_SPEED_5: clock = 250000; break; - case SPI_SPEED_6: clock = 125000; break; - default: clock = 4000000; break; // Default from the SPI library - } + void spiInitEx(uint32_t clock, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + _spi_clock = clock; + _spi_bitOrder = MSBFIRST; + _spi_clockMode = SPI_MODE0; spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); // We ignore all pins other than chip-select because they have to be tied together anyway. if (hint_cs != -1) @@ -579,6 +700,22 @@ } } + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 8000000; break; + case SPI_HALF_SPEED: clock = 4000000; break; + case SPI_QUARTER_SPEED: clock = 2000000; break; + case SPI_EIGHTH_SPEED: clock = 1000000; break; + case SPI_SIXTEENTH_SPEED: clock = 500000; break; + case SPI_SPEED_5: clock = 250000; break; + case SPI_SPEED_6: clock = 125000; break; + default: clock = 4000000; break; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + void spiClose() { if (_has_spi_pins) sdSPI.end(_spi_pin_cs); @@ -588,12 +725,31 @@ _spi_pin_cs = -1; } - uint8_t spiRec() { + void spiSetBitOrder(int bitOrder) { + _spi_bitOrder = (bitOrder == SPI_BITORDER_MSB) ? (MSBFIRST) : (LSBFIRST); + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); + } + + void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + _spi_clockMode = SPI_MODE0; + else if (clockMode == SPI_CLKMODE_1) + _spi_clockMode = SPI_MODE1; + else if (clockMode == SPI_CLKMODE_2) + _spi_clockMode = SPI_MODE2; + else if (clockMode == SPI_CLKMODE_3) + _spi_clockMode = SPI_MODE3; + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); + } + + uint8_t spiRec(uint8_t txval) { if (_has_spi_pins) sdSPI.beginTransaction(_spi_pin_cs, spiConfig); else sdSPI.beginTransaction(spiConfig); - uint8_t returnByte = sdSPI.transfer(0xFF); + uint8_t returnByte = sdSPI.transfer(txval); if (_has_spi_pins) sdSPI.endTransaction(_spi_pin_cs); else @@ -601,9 +757,22 @@ return returnByte; } - void spiRead(uint8_t *buf, uint16_t nbyte) { + uint16_t spiRec16(uint16_t txval) { + if (_has_spi_pins) + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + else + sdSPI.beginTransaction(spiConfig); + uint16_t returnVal = sdSPI.transfer16(txval); + if (_has_spi_pins) + sdSPI.endTransaction(_spi_pin_cs); + else + sdSPI.endTransaction(); + return returnVal; + } + + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { if (nbyte == 0) return; - memset(buf, 0xFF, nbyte); + memset(buf, txval, nbyte); if (_has_spi_pins == false) { sdSPI.beginTransaction(spiConfig); @@ -632,6 +801,20 @@ sdSPI.endTransaction(); } + void spiSend16(uint16_t v) { + if (_has_spi_pins) + { + sdSPI.beginTransaction(_spi_pin_cs, spiConfig); + sdSPI.transfer16(_spi_pin_cs, v); + } + else + { + sdSPI.beginTransaction(spiConfig); + sdSPI.transfer16(v); + } + sdSPI.endTransaction(); + } + // SD-card specific. void spiSendBlock(uint8_t token, const uint8_t *buf) { if (_has_spi_pins) @@ -648,6 +831,27 @@ } sdSPI.endTransaction(); } + + void spiWrite(const uint8_t *buf, uint16_t cnt) { + // TODO: really has to be improved. + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } #endif #if MB(ALLIGATOR) @@ -657,6 +861,8 @@ // ------------------------ // hardware SPI + // https://github.com/arduino/ArduinoCore-sam/blob/master/system/libsam/source/spi.c + // https://www.gadgetronicx.com/spi-protocol-tutorial-arm/ // ------------------------ static bool spiInitialized = false; @@ -682,10 +888,39 @@ SPI_ConfigureNPCS(SPI0, SPI_CHAN, SPI_CSR_NCPHA | SPI_CSR_CSAAT | SPI_CSR_SCBR(spiDivider[spiRate]) | SPI_CSR_DLYBCT(1)); + + SPI0->SPI_CR &= ~( 1 << 5 ); // MSB config SPI_Enable(SPI0); spiInitialized = true; } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint8_t spiRate; + if (maxClockFreq >= 20000000) { + spiRate = SPI_FULL_SPEED; + } + else if (maxClockFreq >= 5000000) { + spiRate = SPI_HALF_SPEED; + } + else if (maxClockFreq >= 2500000) { + spiRate = SPI_QUARTER_SPEED; + } + else if (maxClockFreq >= 1250000) { + spiRate = SPI_EIGHTH_SPEED; + } + else if (maxClockFreq >= 625000) { + spiRate = SPI_SPEED_5; + } + else if (maxClockFreq >= 300000) { + spiRate = SPI_SPEED_6; + } + else + spiRate = SPI_SPEED_6; + + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); + } + void spiClose() { spiInitialized = false; SPI_Disable(SPI0); @@ -737,10 +972,26 @@ spiInit(1); } + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + SPI0->SPI_CR &= ~( 1 << 5 ); // 6th bit. + } + else if (bitOrder == SPI_BITORDER_LSB) { + SPI0->SPI_CR |= ( 1 << 5 ); + } + } + + void spiSetClockMode(int clockMode) { + if (clockMode != SPI_CLKMODE_0) { + // TODO. + for (;;) {} + } + } + // Read single byte from SPI - uint8_t spiRec() { + uint8_t spiRec(uint8_t txval) { // write dummy byte with address and end transmission flag - SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER; + SPI0->SPI_TDR = txval | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER; WHILE_TX(0); WHILE_RX(0); @@ -749,6 +1000,37 @@ return SPI0->SPI_RDR; } + uint16_t spiRec16(uint16_t txval) { + bool msb = ( ( SPI0->SPI_CR & ( 1 << 5 ) ) == 0 ); + + uint8_t tx_first, tx_second; + if (msb) { + tx_first = ( txval >> 8 ); + tx_second = ( txval & 0xFF ); + } + else { + tx_first = ( txval & 0xFF ); + tx_second = ( txval >> 8 ); + } + + SPI0->SPI_TDR = tx_first | SPI_PCS(SPI_CHAN); + + WHILE_TX(0); + WHILE_RX(0); + + uint16_t v = ( msb ? ( (uint16_t)(SPI0->SPI_RDR&0xFF) << 8 ) : (SPI0->SPI_RDR&0xFF) ); + + SPI0->SPI_TDR = tx_second | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER; + + WHILE_TX(0); + WHILE_RX(0); + + v |= ( msb ? (SPI0->SPI_RDR&0xFF) : ( (uint16_t)(SPI0->SPI_RDR&0xFF) << 8 ) ); + + return v; + } + +#if 0 uint8_t spiRec(uint32_t chan) { WHILE_TX(0); @@ -760,14 +1042,15 @@ return SPI0->SPI_RDR; } +#endif // Read from SPI into buffer - void spiRead(uint8_t *buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { if (!nbyte) return; --nbyte; for (int i = 0; i < nbyte; i++) { //WHILE_TX(0); - SPI0->SPI_TDR = 0x000000FF | SPI_PCS(SPI_CHAN); + SPI0->SPI_TDR = txval | SPI_PCS(SPI_CHAN); WHILE_RX(0); buf[i] = SPI0->SPI_RDR; //DELAY_US(1U); @@ -785,10 +1068,22 @@ //DELAY_US(1U); } - void spiSend(const uint8_t *buf, size_t nbyte) { + void spiSend16(uint16_t v) { + bool msb = ( ( SPI0->SPI_CR & ( 1 << 5 ) ) == 0 ); + SPI0->SPI_TDR = (uint32_t)( msb ? (v&0xFF) : (v>>8) ) | SPI_PCS(SPI_CHAN); + WHILE_TX(0); + WHILE_RX(0); + SPI0->SPI_RDR; + SPI0->SPI_TDR = (uint32_t)( msb ? (v>>8) : (v&0xFF) ) | SPI_PCS(SPI_CHAN) | SPI_TDR_LASTXFER; + WHILE_TX(0); + WHILE_RX(0); + SPI0->SPI_RDR; + } + + void spiWrite(const uint8_t *buf, uint16_t nbyte) { if (!nbyte) return; --nbyte; - for (size_t i = 0; i < nbyte; i++) { + for (uint16_t i = 0; i < nbyte; i++) { SPI0->SPI_TDR = (uint32_t)buf[i] | SPI_PCS(SPI_CHAN); WHILE_TX(0); WHILE_RX(0); @@ -798,6 +1093,22 @@ spiSend(buf[nbyte]); } + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } + +#if 0 void spiSend(uint32_t chan, byte b) { WHILE_TX(0); // write byte with address and end transmission flag @@ -817,6 +1128,7 @@ } spiSend(chan, buf[nbyte]); } +#endif // Write from buffer to SPI void spiSendBlock(uint8_t token, const uint8_t *buf) { @@ -834,11 +1146,6 @@ spiSend(buf[511]); } - /** Begin SPI transaction, set clock, bit order, data mode */ - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - // TODO: to be implemented - } - #else // U8G compatible hardware SPI #define SPI_MODE_0_DUE_HW 2 // DUE CPHA control bit is inverted @@ -912,11 +1219,21 @@ } void spiClose() { - // TODO? + // Disable the SPI. + SPI0->SPI_CR = SPI_CR_SPIDIS; } void spiBegin() { spiInit(SPI_SPEED_DEFAULT); } + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + SPI0->SPI_CR &= ~( 1 << 5 ); + } + else if (bitOrder == SPI_BITORDER_LSB) { + SPI0->SPI_CR |= ( 1 << 5 ); + } + } + static uint8_t spiTransfer(uint8_t data) { WHILE_TX(0); SPI0->SPI_TDR = (uint32_t)data | 0x00070000UL; // Add TMC2130 PCS bits to every byte (use SPI0->SPI_CSR[3]) @@ -925,14 +1242,45 @@ return SPI0->SPI_RDR; } - uint8_t spiRec() { return (uint8_t)spiTransfer(0xFF); } + uint8_t spiRec() { + return (uint8_t)spiTransfer(0xFF); + } + + uint16_t spiRec16() { + bool msb = ( ( SPI0->SPI_CR & ( 1 << 5 ) ) == 0 ); + if ( msb ) + { + return ( (uint16_t)spiRec() << 8 ) | ( (uint16_t)spiRec() ); + } + else + { + return ( (uint16_t)spiRec() ) | ( (uint16_t)spiRec() << 8 ); + } + } void spiRead(uint8_t *buf, uint16_t nbyte) { for (int i = 0; i < nbyte; i++) buf[i] = spiTransfer(0xFF); } - void spiSend(uint8_t data) { spiTransfer(data); } + void spiSend(uint8_t data) + { + spiTransfer(data); + } + + void spiSend16(uint16_t data) + { + bool msb = ( ( SPI0->SPI_CR & ( 1 << 5 ) ) == 0 ); + if (msb) { + spiSend(data >> 8); + spiSend(data & 0xFF); + + } + else { + spiSend(data & 0xFF); + spiSend(data >> 8); + } + } void spiSend(const uint8_t *buf, size_t nbyte) { for (uint16_t i = 0; i < nbyte; i++) diff --git a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp index 42d0d85c25e2..ab95c0a1ffef 100644 --- a/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp +++ b/Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp @@ -97,10 +97,7 @@ uint8_t u8g_com_HAL_DUE_shared_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_va u8g_Delay(5); - spiBegin(); - // the Arduino Core SPI library of the DUE only cares about the chip-select pin. - // TODO: can we hint all the pins? - spiInit(LCD_SPI_SPEED, -1, -1, -1, U8G_PI_CS); + spiInit(LCD_SPI_SPEED, U8G_PI_SCK, -1, U8G_PI_MOSI, U8G_PI_CS); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h index 58674144470c..8e964debea84 100644 --- a/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/DUE/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/DUE." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/DUE." #endif diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp deleted file mode 100644 index daeb6676b28e..000000000000 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ /dev/null @@ -1,118 +0,0 @@ -/** - * 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 - * Copyright (c) 2017 Victor Perez - * - * 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 . - * - */ -#ifdef ARDUINO_ARCH_ESP32 - -#include "../../inc/MarlinConfig.h" - -#include "../shared/HAL_SPI.h" - -#include -#include - -// ------------------------ -// Public Variables -// ------------------------ - -static SPISettings spiConfig; - -// ------------------------ -// Public functions -// ------------------------ - -#if ENABLED(SOFTWARE_SPI) - - // ------------------------ - // Software SPI - // ------------------------ - #error "Software SPI not supported for ESP32. Use Hardware SPI." - -#else - -// ------------------------ -// Hardware SPI -// ------------------------ - -void spiBegin() { - #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); - #endif -} - -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - uint32_t clock; - - switch (spiRate) { - case SPI_FULL_SPEED: clock = 16000000; break; - case SPI_HALF_SPEED: clock = 8000000; break; - case SPI_QUARTER_SPEED: clock = 4000000; break; - case SPI_EIGHTH_SPEED: clock = 2000000; break; - case SPI_SIXTEENTH_SPEED: clock = 1000000; break; - case SPI_SPEED_5: clock = 500000; break; - case SPI_SPEED_6: clock = 250000; break; - default: clock = 1000000; // Default from the SPI library - } - - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - // https://github.com/espressif/arduino-esp32/blob/master/libraries/SPI/src/SPI.cpp SPIClass::begin method. - SPI.begin(hint_sck, hint_miso, hint_mosi, hint_cs); -} - -void spiClose() { - SPI.end(); -} - -uint8_t spiRec() { - SPI.beginTransaction(spiConfig); - uint8_t returnByte = SPI.transfer(0xFF); - SPI.endTransaction(); - return returnByte; -} - -void spiRead(uint8_t *buf, uint16_t nbyte) { - SPI.beginTransaction(spiConfig); - SPI.transferBytes(0, buf, nbyte); - SPI.endTransaction(); -} - -void spiSend(uint8_t b) { - SPI.beginTransaction(spiConfig); - SPI.transfer(b); - SPI.endTransaction(); -} - -void spiSendBlock(uint8_t token, const uint8_t *buf) { - SPI.beginTransaction(spiConfig); - SPI.transfer(token); - SPI.writeBytes(const_cast(buf), 512); - SPI.endTransaction(); -} - -void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - spiConfig = SPISettings(spiClock, bitOrder, dataMode); - - SPI.beginTransaction(spiConfig); -} - -#endif // !SOFTWARE_SPI - -#endif // ARDUINO_ARCH_ESP32 diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp new file mode 100644 index 000000000000..84b558117028 --- /dev/null +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -0,0 +1,2587 @@ +/** + * 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 + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ + +/* + HAL SPI implementation by Martin Turski, company owner of EirDev + Inclusion date: 24th of November, 2022 + Contact mail: turningtides@outlook.de + --- + + Contact Martin if there is any grave SPI design or functionality issue. + Include a link to the Marlin FW GitHub issue post. Otherwise the mail + may be ignored. This implementation has been created specifically for the + Marlin FW. It was made with performance and simplicity-of-maintenance in + mind, while keeping all the SPI requirements in check. + + Original pull request: https://github.com/MarlinFirmware/Marlin/pull/24911 +*/ + +#ifdef ARDUINO_ARCH_ESP32 + +#include "../../inc/MarlinConfig.h" + +#include "../shared/HAL_SPI.h" +#include "../shared/SPI/bufmgmt.h" + +#if !ENABLED(SOFTWARE_SPI) && !ENABLED(HALSPI_HW_GENERIC) + +#include "FreeRTOS.h" +//#include "semphr.h" + +// ------------------------ +// Hardware SPI +// tested using MKS TinyBee V1.0 (ESP32-WROOM-32U) +// ------------------------ + +static void _spi_on_error(uint32_t code = 0) { + for (;;) { +#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay((code > 0) ? 800 : 150); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(250); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code - 1) + delay(250); + } + delay(3000); +#endif + } +} + +static void _spi_infobeep(uint32_t code) { +#if PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(300); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); +#endif +} + +// ESP32 TRM DATE: 14th of November, 2022 + +template +inline numberType _MIN(numberType a, numberType b) { + return ( a < b ? a : b ); +} + +namespace MarlinESP32 { + +struct spi_cmd_reg_t { + uint32_t reserved1 : 18; + uint32_t SPI_USR : 1; + uint32_t reserved2 : 13; +}; +static_assert(sizeof(spi_cmd_reg_t) == 4, "invalid size for ESP32 spi_cmd_reg_t"); + +struct spi_ctrl_reg_t { + uint32_t reserved1 : 13; + uint32_t SPI_FASTRD_MODE : 1; + uint32_t SPI_FREAD_DUAL : 1; + uint32_t reserved2 : 5; + uint32_t SPI_FREAD_QUAD : 1; + uint32_t SPI_WP : 1; + uint32_t reserved3 : 1; + uint32_t SPI_FREAD_DIO : 1; + uint32_t SPI_FREAD_QIO : 1; + uint32_t SPI_RD_BIT_ORDER : 1; + uint32_t SPI_WR_BIT_ORDER : 1; + uint32_t reserved4 : 5; +}; +static_assert(sizeof(spi_ctrl_reg_t) == 4, "invalid size for ESP32 spi_ctrl_reg_t"); + +struct spi_ctrl2_reg_t { + uint32_t SPI_SETUP_TIME : 4; + uint32_t SPI_HOLD_TIME : 4; + uint32_t reserved1 : 4; + uint32_t SPI_CK_OUT_HIGH_MODE : 4; + uint32_t SPI_MISO_DELAY_MODE : 2; + uint32_t SPI_MISO_DELAY_NUM : 3; + uint32_t SPI_MOSI_DELAY_MODE : 2; + uint32_t SPI_MOSI_DELAY_NUM : 3; + uint32_t SPI_CS_DELAY_MODE : 2; + uint32_t SPI_CS_DELAY_NUM : 4; +}; +static_assert(sizeof(spi_ctrl2_reg_t) == 4, "invalid size for ESP32 spi_ctrl2_reg_t"); + +struct spi_clock_reg_t { + uint32_t SPI_CLKCNT_L : 6; + uint32_t SPI_CLKCNT_H : 6; + uint32_t SPI_CLKCNT_N : 6; + uint32_t SPI_CLKDIV_PRE : 13; + uint32_t SPI_CLK_EQU_SYSCLK : 1; +}; +static_assert(sizeof(spi_clock_reg_t) == 4, "invalid size for ESP32 spi_clock_reg_t"); + +struct spi_user_reg_t { + uint32_t SPI_DOUTDIN : 1; + uint32_t reserved1 : 3; + uint32_t SPI_CS_HOLD : 1; + uint32_t SPI_CS_SETUP : 1; + uint32_t SPI_CK_I_EDGE : 1; + uint32_t SPI_CK_OUT_EDGE : 1; + uint32_t reserved2 : 2; + uint32_t SPI_RD_BYTE_ORDER : 1; + uint32_t SPI_WR_BYTE_ORDER : 1; + uint32_t SPI_FWRITE_DUAL : 1; + uint32_t SPI_FWRITE_QUAD : 1; + uint32_t SPI_FWRITE_DIO : 1; + uint32_t SPI_FWRITE_QIO : 1; + uint32_t SPI_SIO : 1; + uint32_t reserved3 : 7; + uint32_t SPI_USR_MISO_HIGHPART : 1; + uint32_t SPI_USR_MOSI_HIGHPART : 1; + uint32_t SPI_USR_DUMMY_IDLE : 1; + uint32_t SPI_USR_MOSI : 1; + uint32_t SPI_USR_MISO : 1; + uint32_t SPI_USR_DUMMY : 1; + uint32_t SPI_USR_ADDR : 1; + uint32_t SPI_USR_COMMAND : 1; +}; +static_assert(sizeof(spi_user_reg_t) == 4, "invalid size for ESP32 spi_user_reg_t"); + +struct spi_user1_reg_t { + uint32_t SPI_USR_DUMMY_CYCLELEN : 8; + uint32_t reserved1 : 18; + uint32_t SPI_USR_ADDR_BITLEN : 6; +}; +static_assert(sizeof(spi_user1_reg_t) == 4, "invalid size for ESP32 spi_user1_reg_t"); + +struct spi_user2_reg_t { + uint32_t SPI_USR_COMMAND_VALUE : 16; + uint32_t reserved1 : 12; + uint32_t SPI_USR_COMMAND_BITLEN : 4; +}; +static_assert(sizeof(spi_user2_reg_t) == 4, "invalid size for ESP32 spi_user2_reg_t"); + +struct spi_mosi_dlen_reg_t { + uint32_t SPI_USR_MOSI_DBITLEN : 24; + uint32_t reserved1 : 8; +}; +static_assert(sizeof(spi_mosi_dlen_reg_t) == 4, "invalid size for ESP32 spi_mosi_dlen_reg_t"); + +struct spi_miso_dlen_reg_t { + uint32_t SPI_USR_MISO_DBITLEN : 24; + uint32_t reserved1 : 8; +}; +static_assert(sizeof(spi_miso_dlen_reg_t) == 4, "invalid size for ESP32 spi_miso_dlen_reg_t"); + +struct spi_pin_reg_t { + uint32_t SPI_CS0_DIS : 1; + uint32_t SPI_CS1_DIS : 1; + uint32_t SPI_CS2_DIS : 1; + uint32_t reserved1 : 2; + uint32_t SPI_CK_DIS : 1; + uint32_t SPI_MASTER_CS_POL : 3; + uint32_t reserved2 : 2; + uint32_t SPI_MASTER_CK_SEL : 3; + uint32_t reserved3 : 15; + uint32_t SPI_CK_IDLE_EDGE : 1; + uint32_t SPI_CS_KEEP_ACTIVE : 1; + uint32_t reserved4 : 1; +}; +static_assert(sizeof(spi_pin_reg_t) == 4, "invalid size for ESP32 spi_pin_reg_t"); + +struct spi_slave_reg_t { + uint32_t SPI_SLV_RD_BUF_DONE : 1; + uint32_t SPI_SLV_WR_BUF_DONE : 1; + uint32_t SPI_SLV_RD_STA_DONE : 1; + uint32_t SPI_SLV_WR_STA_DONE : 1; + uint32_t SPI_TRANS_DONE : 1; + uint32_t SPI_SLV_RD_BUF_INTEN : 1; + uint32_t SPI_SLV_WR_BUF_INTEN : 1; + uint32_t SPI_SLV_RD_STA_INTEN : 1; + uint32_t SPI_SLV_WR_STA_INTEN : 1; + uint32_t SPI_TRANS_INTEN : 1; + uint32_t SPI_CS_I_MODE : 2; + uint32_t reserved1 : 5; + uint32_t SPI_SLV_LAST_COMMAND : 3; + uint32_t SPI_SLV_LAST_STATE : 3; // read-only + uint32_t SPI_TRANS_CNT : 4; // read-only + uint32_t SPI_SLV_CMD_DEFINE : 1; + uint32_t SPI_SLV_WR_RD_STA_EN : 1; + uint32_t SPI_SLV_WR_RD_BUF_EN : 1; + uint32_t SPI_SLAVE_MODE : 1; + uint32_t SPI_SYNC_RESET : 1; +}; +static_assert(sizeof(spi_slave_reg_t) == 4, "invalid size for ESP32 spi_slave_reg_t"); + +struct spi_slave1_reg_t { + uint32_t SPI_SLV_RDBUF_DUMMY_EN : 1; + uint32_t SPI_SLV_WRBUF_DUMMY_EN : 1; + uint32_t SPI_SLV_RDSTA_DUMMY_EN : 1; + uint32_t SPI_SLV_WRSTA_DUMMY_EN : 1; + uint32_t SPI_SLV_WR_ADDR_BITLEN : 6; + uint32_t SPI_SLV_RD_ADDR_BITLEN : 6; + uint32_t reserved1 : 9; + uint32_t SPI_SLV_STATUS_READBACK : 1; + uint32_t SPI_SLV_STATUS_FAST_EN : 1; + uint32_t SPI_SLV_STATUS_BITLEN : 5; +}; +static_assert(sizeof(spi_slave1_reg_t) == 4, "invalid size for ESP32 spi_slave1_reg_t"); + +struct spi_slave2_reg_t { + uint32_t SPI_SLV_RDSTA_DUMMY_CYCLELEN : 8; + uint32_t SPI_SLV_WRSTA_DUMMY_CYCLELEN : 8; + uint32_t SPI_SLV_RDBUF_DUMMY_CYCLELEN : 8; + uint32_t SPI_SLV_WRBUF_DUMMY_CYCLELEN : 8; +}; +static_assert(sizeof(spi_slave2_reg_t) == 4, "invalid size for ESP32 spi_slave2_reg_t"); + +struct spi_slave3_reg_t { + uint32_t SPI_SLV_RDBUF_CMD_VALUE : 8; + uint32_t SPI_SLV_WRBUF_CMD_VALUE : 8; + uint32_t SPI_SLV_RDSTA_CMD_VALUE : 8; + uint32_t SPI_SLV_WRSTA_CMD_VALUE : 8; +}; +static_assert(sizeof(spi_slave3_reg_t) == 4, "invalid size for ESP32 spi_slave3_reg_t"); + +struct spi_slv_wrbuf_dlen_reg_t { + uint32_t SPI_SLV_WRBUF_DBITLEN : 24; + uint32_t reserved1 : 8; +}; +static_assert(sizeof(spi_slv_wrbuf_dlen_reg_t) == 4, "invalid size for ESP32 spi_slv_wrbuf_dlen_reg_t"); + +struct spi_slv_rdbuf_dlen_reg_t { + uint32_t SPI_SLV_RDBUF_DBITLEN : 24; + uint32_t reserved1 : 8; +}; +static_assert(sizeof(spi_slv_rdbuf_dlen_reg_t) == 4, "invalid size for ESP32 spi_slv_rdbuf_dlen_reg_t"); + +struct spi_slv_rd_bit_reg_t { + uint32_t SPI_SLV_RDATA_BIT : 24; + uint32_t reserved1 : 8; +}; +static_assert(sizeof(spi_slv_rd_bit_reg_t) == 4, "invalid size for ESP32 spi_slv_rd_bit_reg_t"); + +struct spi_ext2_reg_t { + uint32_t SPI_ST : 3; // read-only + uint32_t reserved1 : 29; +}; +static_assert(sizeof(spi_ext2_reg_t) == 4, "invalid size for ESP32 spi_ext2_reg_t"); + +struct spi_dma_conf_reg_t { + uint32_t reserved1 : 2; + uint32_t SPI_IN_RST : 1; + uint32_t SPI_OUT_RST : 1; + uint32_t SPI_AHBM_FIFO_RST : 1; + uint32_t SPI_AHBM_RST : 1; + uint32_t reserved2 : 3; + uint32_t SPI_OUT_EOF_MODE : 1; + uint32_t SPI_OUTDSCR_BURST_EN : 1; + uint32_t SPI_INDSCR_BURST_EN : 1; + uint32_t SPI_OUT_DATA_BURST_EN : 1; + uint32_t reserved3 : 1; + uint32_t SPI_DMA_RX_STOP : 1; + uint32_t SPI_DMA_TX_STOP : 1; + uint32_t SPI_DMA_CONTINUE : 1; + uint32_t reserved4 : 15; +}; +static_assert(sizeof(spi_dma_conf_reg_t) == 4, "invalid size for ESP32 spi_dma_conf_reg_t"); + +struct spi_dma_out_link_reg_t { + uint32_t SPI_OUTLINK_ADDR : 20; // ESP32 base address: 0x3FF00000 + uint32_t reserved1 : 8; + uint32_t SPI_OUTLINK_STOP : 1; + uint32_t SPI_OUTLINK_START : 1; + uint32_t SPI_OUTLINK_RESTART : 1; + uint32_t reserved2 : 1; +}; +static_assert(sizeof(spi_dma_out_link_reg_t) == 4, "invalid size for ESP32 spi_dma_out_link_reg_t"); + +struct spi_dma_in_link_reg_t { + uint32_t SPI_INLINK_ADDR : 20; // ESP32 base address: 0x3FF00000 + uint32_t SPI_INLINK_AUTO_RET : 1; + uint32_t reserved1 : 7; + uint32_t SPI_INLINK_STOP : 1; + uint32_t SPI_INLINK_START : 1; + uint32_t SPI_INLINK_RESTART : 1; + uint32_t reserved2 : 1; +}; +static_assert(sizeof(spi_dma_in_link_reg_t) == 4, "invalid size for ESP32 spi_dma_in_link_reg_t"); + +struct spi_dma_status_reg_t { + uint32_t SPI_DMA_TX_EN : 1; // read-only + uint32_t SPI_DMA_RX_EN : 1; // read-only + uint32_t reserved1 : 30; +}; +static_assert(sizeof(spi_dma_status_reg_t) == 4, "invalid size for ESP32 spi_dma_status_reg_t"); + +struct spi_dma_int_ena_reg_t { + uint32_t SPI_INLINK_DSCR_EMPTY_INT_ENA : 1; + uint32_t SPI_OUTLINK_DSCR_ERROR_INT_ENA : 1; + uint32_t SPI_INLINK_DSCR_ERROR_INT_ENA : 1; + uint32_t SPI_IN_DONE_INT_ENA : 1; + uint32_t SPI_IN_ERR_EOF_INT_ENA : 1; + uint32_t SPI_IN_SUC_EOF_INT_ENA : 1; + uint32_t SPI_OUT_DONE_INT_ENA : 1; + uint32_t SPI_OUT_EOF_INT_ENA : 1; + uint32_t SPI_OUT_TOTAL_EOF_INT_ENA : 1; + uint32_t reserved1 : 23; +}; +static_assert(sizeof(spi_dma_int_ena_reg_t) == 4, "invalid size for ESP32 spi_dma_int_ena_reg_t"); + +struct spi_dma_int_raw_reg_t { + uint32_t SPI_INLINK_DSCR_EMPTY_INT_RAW : 1; // read-only + uint32_t SPI_OUTLINK_DSCR_ERROR_INT_RAW : 1; // read-only + uint32_t SPI_INLINK_DSCR_ERROR_INT_RAW : 1; // read-only + uint32_t SPI_IN_DONE_INT_RAW : 1; // read-only + uint32_t SPI_IN_ERR_EOF_INT_RAW : 1; // read-only + uint32_t SPI_IN_SUC_EOF_INT_RAW : 1; // read-only + uint32_t SPI_OUT_DONE_INT_RAW : 1; // read-only + uint32_t SPI_OUT_EOF_INT_RAW : 1; // read-only + uint32_t SPI_OUT_TOTAL_EOF_INT_RAW : 1; // read-only + uint32_t reserved1 : 23; +}; +static_assert(sizeof(spi_dma_int_raw_reg_t) == 4, "invalid size for ESP32 spi_dma_int_raw_reg_t"); + +struct spi_dma_int_st_reg_t { + uint32_t SPI_INLINK_DSCR_EMPTY_INT_ST : 1; // read-only + uint32_t SPI_OUTLINK_DSCR_ERROR_INT_ST : 1; // read-only + uint32_t SPI_INLINK_DSCR_ERROR_INT_ST : 1; // read-only + uint32_t SPI_IN_DONE_INT_ST : 1; // read-only + uint32_t SPI_IN_ERR_EOF_INT_ST : 1; // read-only + uint32_t SPI_IN_SUC_EOF_INT_ST : 1; // read-only + uint32_t SPI_OUT_DONE_INT_ST : 1; // read-only + uint32_t SPI_OUT_EOF_INT_ST : 1; // read-only + uint32_t SPI_OUT_TOTAL_EOF_INT_ST : 1; // read-only + uint32_t reserved1 : 23; +}; +static_assert(sizeof(spi_dma_int_st_reg_t) == 4, "invalid size for ESP32 spi_dma_int_st_reg_t"); + +struct spi_dma_int_clr_reg_t { + uint32_t SPI_INLINK_DSCR_EMPTY_INT_CLR : 1; + uint32_t SPI_OUTLINK_DSCR_ERROR_INT_CLR : 1; + uint32_t SPI_INLINK_DSCR_ERROR_INT_CLR : 1; + uint32_t SPI_IN_DONE_INT_CLR : 1; + uint32_t SPI_IN_ERR_EOF_INT_CLR : 1; + uint32_t SPI_IN_SUC_EOF_INT_CLR : 1; + uint32_t SPI_OUT_DONE_INT_CLR : 1; + uint32_t SPI_OUT_EOF_INT_CLR : 1; + uint32_t SPI_OUT_TOTAL_EOF_INT_CLR : 1; + uint32_t reserved1 : 23; +}; +static_assert(sizeof(spi_dma_int_clr_reg_t) == 4, "invalid size for ESP32 spi_dma_int_clr_reg_t"); + +struct spi_dma_rstatus_reg_t { + uint32_t TX_DES_ADDRESS : 20; // read-only, ESP32 base address: 0x3FF00000 + uint32_t reserved1 : 10; + uint32_t TX_FIFO_FULL : 1; // read-only + uint32_t TX_FIFO_EMPTY : 1; // read-only +}; +static_assert(sizeof(spi_dma_rstatus_reg_t) == 4, "invalid size for ESP32 spi_dma_rstatus_reg_t"); + +struct spi_dma_tstatus_reg_t { + uint32_t RX_DES_ADDRESS : 20; // read-only, ESP32 base address: 0x3FF00000 + uint32_t reserved1 : 10; + uint32_t RX_FIFO_FULL : 1; // read-only + uint32_t RX_FIFO_EMPTY : 1; // read-only +}; +static_assert(sizeof(spi_dma_tstatus_reg_t) == 4, "invalid size for ESP32 spi_dma_tstatus_reg_t"); + +struct spi_dev_t { + volatile spi_cmd_reg_t SPI_CMD_REG; + volatile uint32_t SPI_ADDR_REG; + volatile spi_ctrl_reg_t SPI_CTRL_REG; + volatile uint32_t SPI_CTRL1_REG; + volatile uint32_t SPI_RD_STATUS_REG; + volatile spi_ctrl2_reg_t SPI_CTRL2_REG; + volatile spi_clock_reg_t SPI_CLOCK_REG; + volatile spi_user_reg_t SPI_USER_REG; + volatile spi_user1_reg_t SPI_USER1_REG; + volatile spi_user2_reg_t SPI_USER2_REG; + volatile spi_mosi_dlen_reg_t SPI_MOSI_DLEN_REG; + volatile spi_miso_dlen_reg_t SPI_MISO_DLEN_REG; + volatile uint32_t SPI_SLV_WR_STATUS_REG; + volatile spi_pin_reg_t SPI_PIN_REG; + volatile spi_slave_reg_t SPI_SLAVE_REG; + volatile spi_slave1_reg_t SPI_SLAVE1_REG; + volatile spi_slave2_reg_t SPI_SLAVE2_REG; + volatile spi_slave3_reg_t SPI_SLAVE3_REG; + volatile spi_slv_wrbuf_dlen_reg_t SPI_SLV_WRBUF_DLEN_REG; + volatile spi_slv_rdbuf_dlen_reg_t SPI_SLV_RDBUF_DLEN_REG; + volatile uint8_t pad1[0x14]; + volatile spi_slv_rd_bit_reg_t SPI_SLV_RD_BIT_REG; + volatile uint8_t pad2[0x18]; + volatile uint32_t SPI_W_REG[16]; + volatile uint32_t SPI_TX_CRC_REG; + volatile uint8_t pad3[0x34]; + volatile spi_ext2_reg_t SPI_EXT2_REG; + volatile uint8_t pad4[4]; + volatile spi_dma_conf_reg_t SPI_DMA_CONF_REG; + volatile spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; + volatile spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; + volatile spi_dma_status_reg_t SPI_DMA_STATUS_REG; + volatile spi_dma_int_ena_reg_t SPI_DMA_INT_ENA_REG; + volatile spi_dma_int_raw_reg_t SPI_DMA_INT_RAW_REG; + volatile spi_dma_int_st_reg_t SPI_DMA_INT_ST_REG; + volatile spi_dma_int_clr_reg_t SPI_DMA_INT_CLR_REG; + volatile const uint32_t SPI_IN_ERR_EOF_DES_ADDR_REG; + volatile const uint32_t SPI_IN_SUC_EOF_DES_ADDR_REG; + volatile const uint32_t SPI_INLINK_DSCR_REG; + volatile const uint32_t SPI_INLINK_DSCR_BF0_REG; + volatile const uint32_t SPI_INLINK_DSCR_BF1_REG; + volatile const uint32_t SPI_OUT_EOF_BFR_DES_ADDR_REG; + volatile const uint32_t SPI_OUT_EOF_DES_ADDR_REG; + volatile const uint32_t SPI_OUTLINK_DSCR_REG; + volatile const uint32_t SPI_OUTLINK_DSCR_BF0_REG; + volatile const uint32_t SPI_OUTLINK_DSCR_BF1_REG; + volatile spi_dma_rstatus_reg_t SPI_DMA_RSTATUS_REG; + volatile spi_dma_tstatus_reg_t SPI_DMA_TSTATUS_REG; +}; +static_assert(offsetof(spi_dev_t, SPI_CLOCK_REG) == 0x18, "invalid ESP32 offsetof SPI_CLOCK_REG"); +static_assert(offsetof(spi_dev_t, SPI_W_REG[0]) == 0x80, "invalid ESP32 offsetof SPI_W_REG"); +static_assert(offsetof(spi_dev_t, SPI_EXT2_REG) == 0xF8, "invalid ESP32 offsetof SPI_EXT2_REG"); +static_assert(sizeof(spi_dev_t) == 0x150, "wrong formatting of ESP32 spi_dev_t!"); + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS +static spi_dev_t& SPI0 = *(spi_dev_t*)0x3FF43000; // shares signals with SPI1 (USAGE DISALLOWED) +static spi_dev_t& SPI1 = *(spi_dev_t*)0x3FF42000; // (USAGE DISALLOWED) +#endif +static spi_dev_t& SPI2 = *(spi_dev_t*)0x3FF64000; // HSPI +static spi_dev_t& SPI3 = *(spi_dev_t*)0x3FF65000; // VSPI + +#define _SPI_DEFAULT_BUS 2 +#define __SPI_BUSOBJ(IDX) (SPI##IDX) +#define _SPI_BUSOBJ(IDX) (__SPI_BUSOBJ(IDX)) + +inline spi_dev_t& SPIGetBusFromIndex(uint8_t idx) { + switch(idx) { +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + case 0: return SPI0; + case 1: return SPI1; +#endif + case 2: return SPI2; + case 3: return SPI3; + default: return _SPI_BUSOBJ(_SPI_DEFAULT_BUS); + } +} + +inline uint8_t SPIGetBusIndex(spi_dev_t& SPI) { +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (&SPI == &SPI0) return 0; + else if (&SPI == &SPI1) return 1; + else +#endif + if (&SPI == &SPI2) return 2; + else if (&SPI == &SPI3) return 3; + return _SPI_DEFAULT_BUS; +} + +// page 57 of the ESP32 technical reference manual contains default GPIO states after reset. +// MOSI: SPID/HSPID/VSPID +// MISO: SPIQ/HSPIQ/VSPIQ +// CS: SPICS0/HSPICS0/VSPICS0 +// CLK: SPICLK/HSPICLK/VSPICLK + +inline void SPIGetSignalForBus(uint8_t busIdx, uint8_t& sckOut, uint8_t& misoOut, uint8_t& mosiOut, uint8_t& csOut) { +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (busIdx == 0 || busIdx == 1) { + sckOut = 0; + misoOut = 1; + mosiOut = 2; + csOut = 5; + } + else +#endif + if (busIdx == 2) { + sckOut = 8; + misoOut = 9; + mosiOut = 10; + csOut = 11; + } + else if (busIdx == 3) { + sckOut = 63; + misoOut = 64; + mosiOut = 65; + csOut = 68; + } + else { + sckOut = 0xFF; + misoOut = 0xFF; + mosiOut = 0xFF; + csOut = 0xFF; + } +} + +inline gpio_num_t _GetInternalPinName(int pin) { + if (pin >= 0 && pin <= GPIO_NUM_MAX) { + return (gpio_num_t)pin; + } + return (gpio_num_t)-1; // NC +} + +#define SPI_IOMUX_INVAL 0xFF + +// page 57 of ESP32 ref manual. +// IOMUX is faster than GPIO matrix. +inline bool SPIFindIOMUXMapping( + int gpio_sck, int gpio_miso, int gpio_mosi, int gpio_cs, + uint8_t& spibusIdxOut, uint8_t& func_sck_out, uint8_t& func_miso_out, uint8_t& func_mosi_out, uint8_t& func_cs_out +) { + uint8_t func_sck = SPI_IOMUX_INVAL; + uint8_t func_miso = SPI_IOMUX_INVAL; + uint8_t func_mosi = SPI_IOMUX_INVAL; + uint8_t func_cs = SPI_IOMUX_INVAL; + bool found = false; +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (gpio_sck == 6 || gpio_miso == 7 || gpio_mosi == 8 || gpio_cs == 11) { + if (gpio_sck == 6) func_sck = 1; + if (gpio_miso == 7) func_miso = 1; + if (gpio_mosi == 8) func_mosi = 1; + if (gpio_cs == 11) func_cs = 1; + spibusIdxOut = 0; + found = true; + } + else +#endif + if (gpio_sck == 14 || gpio_miso == 12 || gpio_mosi == 13 || gpio_cs == 15) { + if (gpio_sck == 14) func_sck = 1; + if (gpio_miso == 12) func_miso = 1; + if (gpio_mosi == 13) func_mosi = 1; + if (gpio_cs == 15) func_cs = 1; + spibusIdxOut = 2; + found = true; + } + else if (gpio_sck == 18 || gpio_miso == 19 || gpio_mosi == 23 || gpio_cs == 5) { + if (gpio_sck == 18) func_sck = 1; + if (gpio_miso == 19) func_miso = 1; + if (gpio_mosi == 23) func_mosi = 1; + if (gpio_cs == 5) func_cs = 1; + spibusIdxOut = 3; + found = true; + } + + if (found) { + func_sck_out = func_sck; + func_miso_out = func_miso; + func_mosi_out = func_mosi; + func_cs_out = func_cs; + } + return found; +} + +// There is very little documentation on certain ESP32 internals. + +struct gpioMapResult_t { + uint8_t spibusIdx; + int gpio_sck; + int gpio_miso; + int gpio_mosi; + int gpio_cs; + bool datasig_is_direct_iomux; +}; + +inline gpioMapResult_t SPIMapGPIO(int gpio_sck, int gpio_miso, int gpio_mosi, int gpio_cs) { + if (gpio_sck < 0 && gpio_miso < 0 && gpio_mosi < 0 && gpio_cs < 0) { + // Select SPI2. + gpio_sck = 14; + gpio_miso = 12; + gpio_mosi = 13; + gpio_cs = 15; + } + + uint8_t spibusIdx = _SPI_DEFAULT_BUS; // default SPI bus index + + uint8_t func_sck, func_miso, func_mosi, func_cs; + bool fastiomux = SPIFindIOMUXMapping( + gpio_sck, gpio_miso, gpio_mosi, gpio_cs, + spibusIdx, func_sck, func_miso, func_mosi, func_cs + ); + + bool has_sck_map = false; + bool has_miso_map = false; + bool has_mosi_map = false; +#if 0 + bool has_cs_map = false; +#endif + + uint8_t sck_sig, miso_sig, mosi_sig, cs_sig; + SPIGetSignalForBus(spibusIdx, sck_sig, miso_sig, mosi_sig, cs_sig); + + (void)cs_sig; + + bool miso_iomux = false; + + if (fastiomux) { + if (func_sck != SPI_IOMUX_INVAL) { + gpio_iomux_in((unsigned int)gpio_sck, sck_sig); + gpio_iomux_out((unsigned int)gpio_sck, func_sck, false); + has_sck_map = true; + } + if (func_miso != SPI_IOMUX_INVAL) { + gpio_iomux_in((unsigned int)gpio_miso, miso_sig); + gpio_iomux_out((unsigned int)gpio_miso, func_miso, false); + has_miso_map = true; + miso_iomux = true; + } + if (func_mosi != SPI_IOMUX_INVAL) { + gpio_iomux_in((unsigned int)gpio_mosi, mosi_sig); + gpio_iomux_out((unsigned int)gpio_mosi, func_mosi, false); + has_mosi_map = true; + } +#if 0 + if (func_cs != SPI_IOMUX_INVAL) { + gpio_iomux_in((unsigned int)gpio_cs, cs_sig); + gpio_iomux_out((unsigned int)gpio_cs, func_cs, false); + has_cs_map = true; + has_mosi_map = true; + } +#endif + } + + if (has_sck_map == false && gpio_sck >= 0) { + gpio_matrix_out((unsigned int)gpio_sck, sck_sig, false, false); + pinMode(gpio_sck, OUTPUT); + } + if (has_miso_map == false && gpio_miso >= 0) { + gpio_matrix_in((unsigned int)gpio_miso, miso_sig, false); + pinMode(gpio_miso, INPUT); + } + if (has_mosi_map == false && gpio_mosi >= 0) { + gpio_matrix_out((unsigned int)gpio_mosi, mosi_sig, false, false); + pinMode(gpio_mosi, OUTPUT); + } +#if 0 + if (has_cs_map == false && gpio_cs >= 0) { + gpio_matrix_out((unsigned int)gpio_cs, cs_sig, false, false); + pinMode(gpio_cs, OUTPUT); + } +#endif + + gpioMapResult_t result; + result.spibusIdx = spibusIdx; + result.gpio_sck = gpio_sck; + result.gpio_miso = gpio_miso; + result.gpio_mosi = gpio_mosi; + result.gpio_cs = gpio_cs; + result.datasig_is_direct_iomux = (miso_iomux); + return result; +} + +inline void SPIUnmapGPIO(gpioMapResult_t& result) { + if (result.gpio_sck >= 0) { + gpio_reset_pin(_GetInternalPinName(result.gpio_sck)); + } + if (result.gpio_miso >= 0) { + gpio_reset_pin(_GetInternalPinName(result.gpio_miso)); + } + if (result.gpio_mosi >= 0) { + gpio_reset_pin(_GetInternalPinName(result.gpio_mosi)); + } +#if 0 + if (result.gpio_cs >= 0) { + gpio_reset_pin(_GetInternalPinName(result.gpio_cs)); + } +#endif +} + +struct dport_perip_clk_en_reg_t { + uint32_t reserved1 : 1; + uint32_t DPORT_SPI01_CLK_EN : 1; + uint32_t DPORT_UART_CLK_EN : 1; + uint32_t reserved2 : 1; + uint32_t DPORT_I2S0_CLK_EN : 1; + uint32_t DPORT_UART1_CLK_EN : 1; + uint32_t DPORT_SPI2_CLK_EN : 1; + uint32_t DPORT_I2C_EXT0_CLK_EN : 1; + uint32_t DPORT_UHCI0_CLK_EN : 1; + uint32_t DPORT_RMT_CLK_EN : 1; + uint32_t DPORT_PCNT_CLK_EN : 1; + uint32_t DPORT_LEDC_CLK_EN : 1; + uint32_t DPORT_UHCI1_CLK_EN : 1; + uint32_t DPORT_TIMERGROUP_CLK_EN : 1; + uint32_t DPORT_EFUSE_CLK_EN : 1; + uint32_t DPORT_TIMERGROUP1_CLK_EN : 1; + uint32_t DPORT_SPI3_CLK_EN : 1; + uint32_t DPORT_PWM0_CLK_EN : 1; + uint32_t DPORT_I2C_EXT1_CLK_EN : 1; + uint32_t DPORT_TWAI_CLK_EN : 1; + uint32_t DPORT_PWM1_CLK_EN : 1; + uint32_t DPORT_I2S1_CLK_EN : 1; + uint32_t DPORT_SPI_DMA_CLK_EN : 1; + uint32_t DPORT_UART2_CLK_EN : 1; + uint32_t DPORT_UART_MEM_CLK_EN : 1; + uint32_t reserved3 : 1; + uint32_t reserved4 : 1; + uint32_t reserved5 : 5; +}; +static_assert(sizeof(dport_perip_clk_en_reg_t) == 4, "invalid size of ESP32 dport_perip_clk_en_reg_t"); + +struct dport_perip_rst_en_reg_t { + uint32_t reserved1 : 1; + uint32_t DPORT_SPI01_RST : 1; + uint32_t DPORT_UART_RST : 1; + uint32_t reserved2 : 1; + uint32_t DPORT_I2S0_RST : 1; + uint32_t DPORT_UART1_RST : 1; + uint32_t DPORT_SPI2_RST : 1; + uint32_t DPORT_I2C_EXT0_RST : 1; + uint32_t DPORT_UHCI0_RST : 1; + uint32_t DPORT_RMT_RST : 1; + uint32_t DPORT_PCNT_RST : 1; + uint32_t DPORT_LEDC_RST : 1; + uint32_t DPORT_UHCI1_RST : 1; + uint32_t DPORT_TIMERGROUP_RST : 1; + uint32_t DPORT_EFUSE_RST : 1; + uint32_t DPORT_TIMERGROUP1_RST : 1; + uint32_t DPORT_SPI3_RST : 1; + uint32_t DPORT_PWM0_RST : 1; + uint32_t DPORT_I2C_EXT1_RST : 1; + uint32_t DPORT_TWAI_RST : 1; + uint32_t DPORT_PWM1_RST : 1; + uint32_t DPORT_I2S1_RST : 1; + uint32_t DPORT_SPI_DMA_RST : 1; + uint32_t DPORT_UART2_RST : 1; + uint32_t DPORT_UART_MEM_RST : 1; + uint32_t reserved3 : 1; + uint32_t reserved4 : 1; + uint32_t reserved5 : 5; +}; +static_assert(sizeof(dport_perip_rst_en_reg_t) == 4, "invalid size of ESP32 dport_perip_rst_en_reg_t"); + +static dport_perip_clk_en_reg_t& DPORT_PERIP_CLK_EN_REG = *(dport_perip_clk_en_reg_t*)0x3FF000C0; +static dport_perip_rst_en_reg_t& DPORT_PERIP_RST_EN_REG = *(dport_perip_rst_en_reg_t*)0x3FF000C4; + +#define DPORT_SPI_DMA_CHAN_SEL_NONE 0 +#define DPORT_SPI_DMA_CHAN_SEL_CHAN1 1 +#define DPORT_SPI_DMA_CHAN_SEL_CHAN2 2 + +struct dport_spi_dma_chan_sel_reg_t { + uint32_t DPORT_SPI_SPI1_DMA_CHAN_SEL : 2; + uint32_t DPORT_SPI_SPI2_DMA_CHAN_SEL : 2; + uint32_t DPORT_SPI_SPI3_DMA_CHAN_SEL : 2; + uint32_t reserved1 : 26; +}; +static_assert(sizeof(dport_spi_dma_chan_sel_reg_t) == sizeof(uint32_t), "invalid size of ESP32 dport_spi_dma_chan_sel_reg_t"); + +static dport_spi_dma_chan_sel_reg_t& DPORT_SPI_DMA_CHAN_SEL_REG = *(dport_spi_dma_chan_sel_reg_t*)0x3FF005A8; + +#if 0 + +struct dport_cpu_per_conf_reg_t { + uint32_t DPORT_CPU_CPUPERIOD_SEL : 2; + uint32_t reserved1 : 30; +}; +static_assert(sizeof(dport_cpu_per_conf_reg_t) == 4, "invalid size of ESP32 dport_cpu_per_conf_reg_t"); + +static dport_cpu_per_conf_reg_t& DPORT_CPU_PER_CONF_REG = *(dport_cpu_per_conf_reg_t*)0x3FF0003C; + +#define RTC_CNTL_SOC_CLK_XTL 0 +#define RTC_CNTL_SOC_CLK_PLL 1 +#define RTC_CNTL_SOC_CLK_RC_FAST 2 +#define RTC_CNTL_SOC_CLK_APLL 3 + +struct rtc_cntl_clk_conf_reg_t { + uint32_t reserved1 : 4; + uint32_t RTC_CNTRL_CK8M_DIV : 2; + uint32_t RTC_CNTL_ENB_CK8M : 1; + uint32_t RTC_CNTL_ENB_CK8M_DIV : 1; + uint32_t RTC_CNTL_DIG_XTAL32K_EN : 1; + uint32_t RTC_CNTL_DIG_CLK8M_D256_EN : 1; + uint32_t RTC_CNTL_DIG_CLK8M_EN : 1; + uint32_t reserved2 : 1; + uint32_t RTC_CNTL_CK8M_DIV_SEL : 3; + uint32_t reserved3 : 2; + uint32_t RTC_CNTL_CK8M_DFREQ : 8; + uint32_t RTC_CNTL_CK8M_FORCE_PD : 1; + uint32_t RTC_CNTL_CK8M_FORCE_PU : 1; + uint32_t RTC_CNTL_SOC_CLK_SEL : 2; + uint32_t RTC_CNTL_FAST_CLK_RTC_SEL : 1; + uint32_t RTC_CNTL_ANA_CLK_RTC_SEL : 2; +}; +static_assert(sizeof(rtc_cntl_clk_conf_reg_t) == 4, "invalid size of ESP32 rtc_cntl_clk_conf_reg_t"); + +static rtc_cntl_clk_conf_reg_t& RTC_CNTL_CLK_CONF_REG = *(rtc_cntl_clk_conf_reg_t*)0x3FF48070; + +struct syscon_conf_reg_t { + uint32_t SYSCON_PRE_DIV_CNT : 10; + uint32_t SYSCON_CLK_320M_EN : 1; + uint32_t SYSCON_CLK_EN : 1; + uint32_t SYSCON_RST_TICK_CNT : 1; + uint32_t SYSCON_QUICK_CLK_CHNG : 1; + uint32_t reserved1 : 18; +}; + +// Undocumented. +static syscon_conf_reg_t& SYSCON_CONF_REG = *(syscon_conf_reg_t*)0x3FF66000; + +#endif //0 + +// You can transfer up to 64bytes in one burst using default SPI without DMA on the ESP32. + +struct clkcnt_res_t { + uint32_t n : 6; + uint32_t l : 6; + uint32_t h : 6; + uint32_t pre : 13; + uint32_t sysclock : 1; + + inline uint32_t GetFrequencyDivider(void) const { + return (n+1)*(pre+1); + } +}; + +static void SPIConfigureClock(spi_dev_t& SPI, int clkMode, bool is_direct_io, const clkcnt_res_t& clkdiv) { + if (clkMode == SPI_CLKMODE_0) { + SPI.SPI_PIN_REG.SPI_CK_IDLE_EDGE = 0; + SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 0; + } + else if (clkMode == SPI_CLKMODE_1) { + SPI.SPI_PIN_REG.SPI_CK_IDLE_EDGE = 0; + SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 1; + } + else if (clkMode == SPI_CLKMODE_2) { + SPI.SPI_PIN_REG.SPI_CK_IDLE_EDGE = 1; + SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 1; + } + else if (clkMode == SPI_CLKMODE_3) { + SPI.SPI_PIN_REG.SPI_CK_IDLE_EDGE = 1; + SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 0; + } + + SPI.SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = clkdiv.sysclock; + SPI.SPI_CLOCK_REG.SPI_CLKDIV_PRE = clkdiv.pre; + SPI.SPI_CLOCK_REG.SPI_CLKCNT_N = clkdiv.n; + SPI.SPI_CLOCK_REG.SPI_CLKCNT_L = clkdiv.l; + SPI.SPI_CLOCK_REG.SPI_CLKCNT_H = clkdiv.h; + + uint32_t apbFreqDiv = clkdiv.GetFrequencyDivider(); + + if (is_direct_io) { + if (apbFreqDiv > 4) { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 0; + } + else { + if (clkMode == SPI_CLKMODE_0 || clkMode == SPI_CLKMODE_3) { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 2; + } + else { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 1; + } + } + SPI.SPI_USER_REG.SPI_USR_DUMMY = 0; + } + else { + if (apbFreqDiv <= 2) { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 0; + SPI.SPI_USER_REG.SPI_USR_DUMMY = 1; + SPI.SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = 0; + } + else if (apbFreqDiv < 8) { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 0; + SPI.SPI_USER_REG.SPI_USR_DUMMY = 0; + } + else { + if (clkMode == SPI_CLKMODE_0 || clkMode == SPI_CLKMODE_3) { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 2; + } + else { + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 1; + } + SPI.SPI_USER_REG.SPI_USR_DUMMY = 0; + } + } + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_NUM = 0; + SPI.SPI_CTRL2_REG.SPI_MOSI_DELAY_MODE = 0; + SPI.SPI_CTRL2_REG.SPI_MOSI_DELAY_NUM = 0; +} + +static const uint8_t _spi_clkcnt_n_primes[] = { + 2, 3, 4, 5, 11, 13, 17, 19, 23, 29, 31, + 37, 41, 43, 47, 53, 59, 61 +}; + +template +inline numberType CEIL_DIV(numberType A, numberType B) { + numberType rem = ( A % B ); + return ( rem == 0 ? (A/B) : (A/B+1) ); +} + +// see page 121 of ESP32 technical reference manual (GP-SPI Clock Control) +inline clkcnt_res_t SPIApproximateClockDivider(uint32_t maxClockFreq, uint32_t spibasefreq) { +#if 0 + // compare with https://github.com/espressif/esp-idf/blob/0a93ee1337c15668c7f9998a53822f281a17670e/components/hal/esp32/include/hal/spi_ll.h#L551 + // Cannot get this code to work. + + clkcnt_res_t res; + + if (spibasefreq >= maxClockFreq) { + res.sysclock = true; + res.pre = 0; + res.n = 0; + res.l = 0; + res.h = 0; + return res; + } + res.sysclock = false; + + // maxClockFreq = f_spi + // spibasefreq = f_apb + + uint32_t approx_div = CEIL_DIV(spibasefreq, maxClockFreq); // pre + 1 + if (approx_div <= (1<<13)) { // 2^14 + res.pre = (approx_div - 1); + res.n = 1; // n needs to be at least 2 so we have one LOW and one HIGH pulse (this detail is found nowhere in the ESP32 docs) + goto finalize; + } + + { + uint8_t best_approx_prime = 2; // n + 1 + uint32_t best_approx = 2; // to avoid annoying GCC warning + bool found_best_approx_prime = false; + + for (uint8_t prime : _spi_clkcnt_n_primes) { + uint32_t primediv = (approx_div / prime); + uint32_t approx_freqdiv = (primediv * approx_div); + if (approx_freqdiv <= (1<<6)*(1<<13)) { // (2^7 * 2^14) + if (found_best_approx_prime == false || (best_approx > approx_freqdiv)) { + best_approx_prime = prime; + best_approx = approx_freqdiv; + found_best_approx_prime = true; + } + } + } + + if (found_best_approx_prime == false || (best_approx_prime*approx_div <= 1)) { + best_approx_prime = 2; + } + + res.n = (best_approx_prime - 1); + res.pre = (approx_div - 1); + } +finalize: + res.h = _MIN ( ((res.n+1) / 2), 1 ) - 1; + res.l = res.n; + return res; +#else + // Taken from the ArduinoCore ESP32 because the ESP32 clock documentation is VERY lacking! + if(maxClockFreq >= spibasefreq) { + clkcnt_res_t sysreg; + sysreg.sysclock = true; + sysreg.pre = 0; + sysreg.n = 0; + sysreg.l = 0; + sysreg.h = 0; + return sysreg; + } + + clkcnt_res_t minFreqReg; + minFreqReg.sysclock = false; + minFreqReg.pre = (1<<13)-1; + minFreqReg.n = (1<<6)-1; + minFreqReg.l = 0; + minFreqReg.h = 0; + uint32_t minFreq = (spibasefreq / minFreqReg.GetFrequencyDivider()); + if(maxClockFreq < minFreq) { + return minFreqReg; + } + + uint8_t calN = 1; + clkcnt_res_t bestReg; + bestReg.pre = 0; + bestReg.n = 0; + bestReg.l = 0; + bestReg.h = 0; + bestReg.sysclock = false; + uint32_t bestFreq = 0; + bool has_best_freq = false; + + while(calN <= (1<<6)-1) { + clkcnt_res_t reg; + reg.pre = 0; + reg.n = 0; + reg.l = 0; + reg.h = 0; + reg.sysclock = false; + uint32_t calFreq; + int32_t calPre; + int8_t calPreVari = -2; + + reg.n = calN; + reg.l = ((reg.n + 1) / 2); + + while(calPreVari++ <= 1) { + calPre = ((int32_t)((spibasefreq / (reg.n + 1)) / maxClockFreq) - 1) + calPreVari; + if(calPre > (1<<13)-1) { + reg.pre = (1<<13)-1; + } else if(calPre <= 0) { + reg.pre = 0; + } else { + reg.pre = calPre; + } + calFreq = (spibasefreq / reg.GetFrequencyDivider()); + if(calFreq == maxClockFreq) { + bestReg = reg; + break; + } + else if(calFreq < maxClockFreq) { + if(has_best_freq == false || (abs(maxClockFreq - calFreq) < abs(maxClockFreq - bestFreq))) { + bestFreq = calFreq; + bestReg = reg; + has_best_freq = true; + } + } + } + if(calFreq == maxClockFreq) { + break; + } + calN++; + } + return bestReg; +#endif +} + +static void SPIConfigureBitOrder(spi_dev_t& SPI, int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = 0; + SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = 0; + } + else { + SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = 1; + SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = 1; + } +} + +inline uint16_t SPIGetWriteBufferSize(spi_dev_t& SPI) { + return ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 32 : 64 ); +} + +template +inline uint8_t SPIGetSingleByteToTransferEx(spi_dev_t& SPI, numberType num, uint32_t byteIdx, bool notrevbits) { + using namespace ::bufmgmt; + +#ifdef HALSPI_DEBUG + if (GetNumberIndexFromTotalByteIndex (byteIdx) >= 1) return 0; +#endif + + return + GetByteFromNumber( + num, + GetLocalByteIndexFromTotalByteIndex (byteIdx), + notrevbits // reverse if MSBFIRST + ); +} + +template +inline uint8_t SPIGetSingleByteToTransfer(spi_dev_t& SPI, numberType num, uint32_t byteIdx) { + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + + return SPIGetSingleByteToTransferEx(SPI, num, byteIdx, notrevbits); +} + +inline void SPIWriteSingleByteToTransferEx(spi_dev_t& SPI, uint8_t byteval, uint32_t byteIdx, uint16_t start_num_idx) { +#ifdef HALSPI_DEBUG + auto max_transfer_size = SPIGetWriteBufferSize(SPI); + + if (byteIdx >= max_transfer_size) return; +#endif + + using namespace ::bufmgmt; + + WriteByteToNumber( + SPI.SPI_W_REG[ start_num_idx + GetNumberIndexFromTotalByteIndex ( byteIdx ) ], + GetLocalByteIndexFromTotalByteIndex ( byteIdx ), + byteval, + true + ); +} + +inline void SPIWriteSingleByteToTransfer(spi_dev_t& SPI, uint8_t byteval, uint32_t byteIdx) { + uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + + return SPIWriteSingleByteToTransferEx(SPI, byteval, byteIdx, start_num_idx); +} + +template +inline void SPIWriteDataToTransferEx( + spi_dev_t& SPI, const numberType *buf, uint32_t cnt_bytes, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, + uint16_t& cntSentBytes_out +) { + uint16_t total_bytes_written = 0; + + using namespace ::bufmgmt; + + auto max_transfer_size = SPIGetWriteBufferSize(SPI); + uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + + for (uint16_t txidx = 0; txidx < _MIN (cnt_bytes - srcByteStartIdx, max_transfer_size - dstByteStartIdx); txidx++) { + uint8_t byteval = + GetByteFromNumber( + buf[ GetNumberIndexFromTotalByteIndex ( txidx + srcByteStartIdx ) ], + GetLocalByteIndexFromTotalByteIndex ( txidx + srcByteStartIdx ), + notrevbits // reverse if MSBFIRST + ); + + WriteByteToNumber( + SPI.SPI_W_REG[ start_num_idx + GetNumberIndexFromTotalByteIndex ( txidx + dstByteStartIdx ) ], + GetLocalByteIndexFromTotalByteIndex ( txidx + dstByteStartIdx ), + byteval, + true + ); + + total_bytes_written++; + } + + cntSentBytes_out = total_bytes_written; +} + +template +inline void SPIWriteDataToTransfer( + spi_dev_t& SPI, const numberType *buf, uint16_t cnt, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, + uint16_t& cntSentBytes_out +) { + return SPIWriteDataToTransferEx(SPI, buf, cnt * sizeof(numberType), srcByteStartIdx, dstByteStartIdx, cntSentBytes_out); +} + +inline uint16_t SPIGetReadBufferSize(spi_dev_t& SPI) { + return ( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 32 : 64 ); +} + +template +inline void SPIReadDataFromTransfer( + spi_dev_t& SPI, numberType *buf, uint16_t cnt, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, + uint16_t& cntReadBytes_out +) { + uint16_t total_bytes_read = 0; + + uint16_t bufNumStartIdx = ( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 8 : 0 ); + uint16_t bufByteLen = SPIGetReadBufferSize(SPI); + + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER == 1); // reverse if MSBFIRST + + using namespace ::bufmgmt; + + for (uint16_t txidx = 0; txidx < _MIN ((uint32_t)cnt*sizeof(numberType) - srcByteStartIdx, bufByteLen - dstByteStartIdx); txidx++) { + uint8_t byteval = + GetByteFromNumber( + SPI.SPI_W_REG[ GetNumberIndexFromTotalByteIndex (txidx + dstByteStartIdx) ], + GetLocalByteIndexFromTotalByteIndex (txidx + dstByteStartIdx), + true + ); + + WriteByteToNumber( + buf[ bufNumStartIdx + GetNumberIndexFromTotalByteIndex (txidx + srcByteStartIdx) ], + GetLocalByteIndexFromTotalByteIndex (txidx + srcByteStartIdx), + byteval, + notrevbits + ); + + total_bytes_read++; + } + + cntReadBytes_out = total_bytes_read; +} + +static void SPITransaction(spi_dev_t& SPI, uint32_t txcount) { + if (txcount == 0) return; + + uint32_t txcount_bits = ( txcount * 8 ); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == true) { + SPI.SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = txcount_bits - 1; + } + if (SPI.SPI_USER_REG.SPI_USR_MISO == true) { + SPI.SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = txcount_bits - 1; + } + + SPI.SPI_CMD_REG.SPI_USR = true; + + while (SPI.SPI_CMD_REG.SPI_USR) { + /* wait until transfer has finished */ + } +} + +static void SPIResetBus(spi_dev_t& SPI) { + spi_cmd_reg_t SPI_CMD_REG; + SPI_CMD_REG.reserved1 = 0; + SPI_CMD_REG.SPI_USR = 0; + SPI_CMD_REG.reserved2 = 0; + (spi_cmd_reg_t&)SPI.SPI_CMD_REG = SPI_CMD_REG; + + SPI.SPI_ADDR_REG = 0; + + spi_ctrl_reg_t SPI_CTRL_REG; + SPI_CTRL_REG.reserved1 = 0; + SPI_CTRL_REG.SPI_FASTRD_MODE = 1; + SPI_CTRL_REG.SPI_FREAD_DUAL = 0; + SPI_CTRL_REG.reserved2 = 0; + SPI_CTRL_REG.SPI_FREAD_QUAD = 0; + SPI_CTRL_REG.SPI_WP = 1; + SPI_CTRL_REG.reserved3 = 0; + SPI_CTRL_REG.SPI_FREAD_DIO = 0; + SPI_CTRL_REG.SPI_FREAD_QIO = 0; + SPI_CTRL_REG.SPI_RD_BIT_ORDER = 0; + SPI_CTRL_REG.SPI_WR_BIT_ORDER = 0; + SPI_CTRL_REG.reserved4 = 0; + (spi_ctrl_reg_t&)SPI.SPI_CTRL_REG = SPI_CTRL_REG; + + SPI.SPI_CTRL1_REG = 0; + SPI.SPI_RD_STATUS_REG = 0; + + spi_ctrl2_reg_t SPI_CTRL2_REG; + SPI_CTRL2_REG.SPI_SETUP_TIME = 1; + SPI_CTRL2_REG.SPI_HOLD_TIME = 1; + SPI_CTRL2_REG.reserved1 = 0; + SPI_CTRL2_REG.SPI_CK_OUT_HIGH_MODE = 0; + SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 0; + SPI_CTRL2_REG.SPI_MISO_DELAY_NUM = 0; + SPI_CTRL2_REG.SPI_MOSI_DELAY_MODE = 0; + SPI_CTRL2_REG.SPI_MOSI_DELAY_NUM = 0; + SPI_CTRL2_REG.SPI_CS_DELAY_MODE = 0; + SPI_CTRL2_REG.SPI_CS_DELAY_NUM = 0; + (spi_ctrl2_reg_t&)SPI.SPI_CTRL2_REG = SPI_CTRL2_REG; + + spi_clock_reg_t SPI_CLOCK_REG; + SPI_CLOCK_REG.SPI_CLKCNT_L = 3; + SPI_CLOCK_REG.SPI_CLKCNT_H = 1; + SPI_CLOCK_REG.SPI_CLKCNT_N = 3; + SPI_CLOCK_REG.SPI_CLKDIV_PRE = 0; + SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = 1; + (spi_clock_reg_t&)SPI.SPI_CLOCK_REG = SPI_CLOCK_REG; + + spi_user_reg_t SPI_USER_REG; + SPI_USER_REG.SPI_DOUTDIN = 0; + SPI_USER_REG.reserved1 = 0; + SPI_USER_REG.SPI_CS_HOLD = 0; + SPI_USER_REG.SPI_CS_SETUP = 0; + SPI_USER_REG.SPI_CK_I_EDGE = 1; + SPI_USER_REG.SPI_CK_OUT_EDGE = 0; + SPI_USER_REG.reserved2 = 0; + SPI_USER_REG.SPI_RD_BYTE_ORDER = 0; + SPI_USER_REG.SPI_WR_BYTE_ORDER = 0; + SPI_USER_REG.SPI_FWRITE_DUAL = 0; + SPI_USER_REG.SPI_FWRITE_QUAD = 0; + SPI_USER_REG.SPI_FWRITE_DIO = 0; + SPI_USER_REG.SPI_FWRITE_QIO = 0; + SPI_USER_REG.SPI_SIO = 0; + SPI_USER_REG.reserved3 = 0; + SPI_USER_REG.SPI_USR_MISO_HIGHPART = 0; + SPI_USER_REG.SPI_USR_MOSI_HIGHPART = 0; + SPI_USER_REG.SPI_USR_DUMMY_IDLE = 0; + SPI_USER_REG.SPI_USR_MOSI = 0; + SPI_USER_REG.SPI_USR_MISO = 0; + SPI_USER_REG.SPI_USR_DUMMY = 0; + SPI_USER_REG.SPI_USR_ADDR = 0; + SPI_USER_REG.SPI_USR_COMMAND = 1; + (spi_user_reg_t&)SPI.SPI_USER_REG = SPI_USER_REG; + + SPI.SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = 0; + + spi_user2_reg_t SPI_USER2_REG; + SPI_USER2_REG.SPI_USR_COMMAND_VALUE = 0; + SPI_USER2_REG.reserved1 = 0; + SPI_USER2_REG.SPI_USR_COMMAND_BITLEN = 7; + (spi_user2_reg_t&)SPI.SPI_USER2_REG = SPI_USER2_REG; + + spi_mosi_dlen_reg_t SPI_MOSI_DLEN_REG; + SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = 0; + SPI_MOSI_DLEN_REG.reserved1 = 0; + (spi_mosi_dlen_reg_t&)SPI.SPI_MOSI_DLEN_REG = SPI_MOSI_DLEN_REG; + + spi_miso_dlen_reg_t SPI_MISO_DLEN_REG; + SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = 0; + SPI_MISO_DLEN_REG.reserved1 = 0; + (spi_miso_dlen_reg_t&)SPI.SPI_MISO_DLEN_REG = SPI_MISO_DLEN_REG; + + SPI.SPI_SLV_WR_STATUS_REG = 0; + + spi_pin_reg_t SPI_PIN_REG; + SPI_PIN_REG.SPI_CS0_DIS = 0; + SPI_PIN_REG.SPI_CS1_DIS = 1; + SPI_PIN_REG.SPI_CS2_DIS = 1; + SPI_PIN_REG.reserved1 = 0; + SPI_PIN_REG.SPI_CK_DIS = 0; + SPI_PIN_REG.SPI_MASTER_CS_POL = 0; + SPI_PIN_REG.reserved2 = 0; + SPI_PIN_REG.SPI_MASTER_CK_SEL = 0; + SPI_PIN_REG.reserved3 = 0; + SPI_PIN_REG.SPI_CK_IDLE_EDGE = 0; + SPI_PIN_REG.SPI_CS_KEEP_ACTIVE = 0; + SPI_PIN_REG.reserved4 = 0; + (spi_pin_reg_t&)SPI.SPI_PIN_REG = SPI_PIN_REG; + + spi_slave_reg_t SPI_SLAVE_REG; + SPI_SLAVE_REG.SPI_SLV_RD_BUF_DONE = 0; + SPI_SLAVE_REG.SPI_SLV_WR_BUF_DONE = 0; + SPI_SLAVE_REG.SPI_SLV_RD_STA_DONE = 0; + SPI_SLAVE_REG.SPI_SLV_WR_STA_DONE = 0; + SPI_SLAVE_REG.SPI_TRANS_DONE = 0; + SPI_SLAVE_REG.SPI_SLV_RD_BUF_INTEN = 0; + SPI_SLAVE_REG.SPI_SLV_WR_BUF_INTEN = 0; + SPI_SLAVE_REG.SPI_SLV_RD_STA_INTEN = 0; + SPI_SLAVE_REG.SPI_SLV_WR_STA_INTEN = 0; + SPI_SLAVE_REG.SPI_TRANS_INTEN = 0; + SPI_SLAVE_REG.SPI_CS_I_MODE = 0; + SPI_SLAVE_REG.reserved1 = 0; + SPI_SLAVE_REG.SPI_SLV_LAST_COMMAND = 0; + SPI_SLAVE_REG.SPI_SLV_LAST_STATE = 0; + SPI_SLAVE_REG.SPI_TRANS_CNT = 0; + SPI_SLAVE_REG.SPI_SLV_CMD_DEFINE = 0; + SPI_SLAVE_REG.SPI_SLV_WR_RD_STA_EN = 0; + SPI_SLAVE_REG.SPI_SLV_WR_RD_BUF_EN = 0; + SPI_SLAVE_REG.SPI_SLAVE_MODE = 0; + SPI_SLAVE_REG.SPI_SYNC_RESET = 0; + (spi_slave_reg_t&)SPI.SPI_SLAVE_REG = SPI_SLAVE_REG; + + spi_slave1_reg_t SPI_SLAVE1_REG; + SPI_SLAVE1_REG.SPI_SLV_RDBUF_DUMMY_EN = 0; + SPI_SLAVE1_REG.SPI_SLV_WRBUF_DUMMY_EN = 0; + SPI_SLAVE1_REG.SPI_SLV_RDSTA_DUMMY_EN = 0; + SPI_SLAVE1_REG.SPI_SLV_WRSTA_DUMMY_EN = 0; + SPI_SLAVE1_REG.SPI_SLV_WR_ADDR_BITLEN = 0; + SPI_SLAVE1_REG.SPI_SLV_RD_ADDR_BITLEN = 0; + SPI_SLAVE1_REG.reserved1 = 0; + SPI_SLAVE1_REG.SPI_SLV_STATUS_READBACK = 1; + SPI_SLAVE1_REG.SPI_SLV_STATUS_FAST_EN = 0; + SPI_SLAVE1_REG.SPI_SLV_STATUS_BITLEN = 0; + (spi_slave1_reg_t&)SPI.SPI_SLAVE1_REG = SPI_SLAVE1_REG; + + spi_slave2_reg_t SPI_SLAVE2_REG; + SPI_SLAVE2_REG.SPI_SLV_RDSTA_DUMMY_CYCLELEN = 0; + SPI_SLAVE2_REG.SPI_SLV_WRSTA_DUMMY_CYCLELEN = 0; + SPI_SLAVE2_REG.SPI_SLV_RDBUF_DUMMY_CYCLELEN = 0; + SPI_SLAVE2_REG.SPI_SLV_WRBUF_DUMMY_CYCLELEN = 0; + (spi_slave2_reg_t&)SPI.SPI_SLAVE2_REG = SPI_SLAVE2_REG; + + spi_slave3_reg_t SPI_SLAVE3_REG; + SPI_SLAVE3_REG.SPI_SLV_RDBUF_CMD_VALUE = 0; + SPI_SLAVE3_REG.SPI_SLV_WRBUF_CMD_VALUE = 0; + SPI_SLAVE3_REG.SPI_SLV_RDSTA_CMD_VALUE = 0; + SPI_SLAVE3_REG.SPI_SLV_WRSTA_CMD_VALUE = 0; + (spi_slave3_reg_t&)SPI.SPI_SLAVE3_REG = SPI_SLAVE3_REG; + + spi_slv_wrbuf_dlen_reg_t SPI_SLV_WRBUF_DLEN_REG; + SPI_SLV_WRBUF_DLEN_REG.SPI_SLV_WRBUF_DBITLEN = 0; + SPI_SLV_WRBUF_DLEN_REG.reserved1 = 0; + (spi_slv_wrbuf_dlen_reg_t&)SPI.SPI_SLV_WRBUF_DLEN_REG = SPI_SLV_WRBUF_DLEN_REG; + + spi_slv_rdbuf_dlen_reg_t SPI_SLV_RDBUF_DLEN_REG; + SPI_SLV_RDBUF_DLEN_REG.SPI_SLV_RDBUF_DBITLEN = 0; + SPI_SLV_RDBUF_DLEN_REG.reserved1 = 0; + (spi_slv_rdbuf_dlen_reg_t&)SPI.SPI_SLV_RDBUF_DLEN_REG = SPI_SLV_RDBUF_DLEN_REG; + + spi_slv_rd_bit_reg_t SPI_SLV_RD_BIT_REG; + SPI_SLV_RD_BIT_REG.SPI_SLV_RDATA_BIT = 0; + SPI_SLV_RD_BIT_REG.reserved1 = 0; + (spi_slv_rd_bit_reg_t&)SPI.SPI_SLV_RD_BIT_REG = SPI_SLV_RD_BIT_REG; + + for (uint32_t n = 0; n < 16; n++) + SPI.SPI_W_REG[n] = 0; + + SPI.SPI_TX_CRC_REG = 0; + + //SPI.SPI_EXT2_REG.SPI_ST = 0; + SPI.SPI_EXT2_REG.reserved1 = 0; + + spi_dma_conf_reg_t SPI_DMA_CONF_REG; + SPI_DMA_CONF_REG.reserved1 = 0; + SPI_DMA_CONF_REG.SPI_IN_RST = 0; + SPI_DMA_CONF_REG.SPI_OUT_RST = 0; + SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = 0; + SPI_DMA_CONF_REG.SPI_AHBM_RST = 0; + SPI_DMA_CONF_REG.reserved2 = 0; + SPI_DMA_CONF_REG.SPI_OUT_EOF_MODE = 1; + SPI_DMA_CONF_REG.SPI_OUTDSCR_BURST_EN = 0; + SPI_DMA_CONF_REG.SPI_INDSCR_BURST_EN = 0; + SPI_DMA_CONF_REG.SPI_OUT_DATA_BURST_EN = 0; + SPI_DMA_CONF_REG.reserved3 = 0; + SPI_DMA_CONF_REG.SPI_DMA_RX_STOP = 0; + SPI_DMA_CONF_REG.SPI_DMA_TX_STOP = 0; + SPI_DMA_CONF_REG.SPI_DMA_CONTINUE = 0; + SPI_DMA_CONF_REG.reserved4 = 0; + (spi_dma_conf_reg_t&)SPI.SPI_DMA_CONF_REG = SPI_DMA_CONF_REG; + + spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = 0; + SPI_DMA_OUT_LINK_REG.reserved1 = 0; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_STOP = 0; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = 0; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_RESTART = 0; + SPI_DMA_OUT_LINK_REG.reserved2 = 0; + (spi_dma_out_link_reg_t&)SPI.SPI_DMA_OUT_LINK_REG = SPI_DMA_OUT_LINK_REG; + + spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; + SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_AUTO_RET = 0; + SPI_DMA_IN_LINK_REG.reserved1 = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_STOP = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_START = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_RESTART = 0; + SPI_DMA_IN_LINK_REG.reserved2 = 0; + (spi_dma_in_link_reg_t&)SPI.SPI_DMA_IN_LINK_REG = SPI_DMA_IN_LINK_REG; + + SPI.SPI_DMA_STATUS_REG.reserved1 = 0; + + spi_dma_int_ena_reg_t SPI_DMA_INT_ENA_REG; + SPI_DMA_INT_ENA_REG.SPI_INLINK_DSCR_EMPTY_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_OUTLINK_DSCR_ERROR_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_INLINK_DSCR_ERROR_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_IN_DONE_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_IN_ERR_EOF_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_IN_SUC_EOF_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_OUT_DONE_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_OUT_EOF_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.SPI_OUT_TOTAL_EOF_INT_ENA = 0; + SPI_DMA_INT_ENA_REG.reserved1 = 0; + (spi_dma_int_ena_reg_t&)SPI.SPI_DMA_INT_ENA_REG = SPI_DMA_INT_ENA_REG; + + SPI.SPI_DMA_INT_RAW_REG.reserved1 = 0; + + SPI.SPI_DMA_INT_ST_REG.reserved1 = 0; + + SPI.SPI_DMA_RSTATUS_REG.reserved1 = 0; + SPI.SPI_DMA_TSTATUS_REG.reserved1 = 0; +} + +#ifdef HAL_SPI_SUPPORTS_ASYNC + +struct spi_async_process_t { + spi_dev_t *current_spibus; + const void *current_buffer; + size_t curoff_bytes; + size_t txlen; + uint8_t txunitsize; + void (*completeCallback)(void*); + void *complete_ud; + bool is_active = false; +}; +static volatile spi_async_process_t _current_spi_proc; + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS +static intr_handle_t _spi0_interrupt; +static intr_handle_t _spi1_interrupt; +#endif +static intr_handle_t _spi2_interrupt; +static intr_handle_t _spi3_interrupt; + +#ifdef HALSPI_DEBUG +static int _cpu_core_id = -1; +#endif + +static void IRAM_ATTR spi_async_fill_buffer(volatile spi_async_process_t& proc) { +#ifdef HALSPI_DEBUG + if (_cpu_core_id == -1) + _cpu_core_id = xPortGetCoreID(); + else if (_cpu_core_id != xPortGetCoreID()) + _spi_on_error(13); +#endif + + spi_dev_t& SPI = *proc.current_spibus; + + bool has_prepared_spibus = false; + uint16_t writecnt_bytes = 0; + + if (proc.txunitsize == 1) { + SPIWriteDataToTransfer(SPI, (const uint8_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + has_prepared_spibus = true; + } + else if (proc.txunitsize == 2) { + SPIWriteDataToTransfer(SPI, (const uint16_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + has_prepared_spibus = true; + } + else if (proc.txunitsize == 4) { + SPIWriteDataToTransfer(SPI, (const uint32_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + has_prepared_spibus = true; + } + + if (has_prepared_spibus == false || writecnt_bytes == 0) { + #ifdef HALSPI_DEBUG + if (proc.curoff_bytes < proc.txlen * proc.txunitsize) { + _spi_on_error(12); + } + #endif + + // Disable the interrupt. + SPI.SPI_SLAVE_REG.SPI_TRANS_INTEN = false; + + auto cb = proc.completeCallback; + auto ud = proc.complete_ud; + + proc.current_spibus = nullptr; + proc.current_buffer = nullptr; + proc.curoff_bytes = 0; + proc.txlen = 0; + proc.txunitsize = 0; + proc.completeCallback = nullptr; + proc.complete_ud = nullptr; + proc.is_active = false; + + // Call any completion handler, if provided by the user. + if (cb) { + cb(ud); + } + } + else { + proc.curoff_bytes += writecnt_bytes; + + uint32_t txcount_bits = ( writecnt_bytes * 8 ); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == true) { + SPI.SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = txcount_bits - 1; + } + if (SPI.SPI_USER_REG.SPI_USR_MISO == true) { + SPI.SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = txcount_bits - 1; + } + + // Kick-off another async SPI transfer. + SPI.SPI_CMD_REG.SPI_USR = true; + } +} + +static void IRAM_ATTR spi_async_process_isr(void *ud, uint32_t spibusIdx) { + spi_dev_t& SPI = SPIGetBusFromIndex(spibusIdx); + + // Check the type of the triggered interrupt. + if (SPI.SPI_SLAVE_REG.SPI_TRANS_DONE) { + // Clear the interrupt. + SPI.SPI_SLAVE_REG.SPI_TRANS_DONE = false; + + volatile spi_async_process_t& proc = _current_spi_proc; + + if (proc.is_active && proc.current_spibus == &SPI) { + // Is the SPI bus ready? Otherwise we could have a spurious interrupt call. + if (SPI.SPI_CMD_REG.SPI_USR == false) { + spi_async_fill_buffer(proc); + } + } + } +#ifdef HALSPI_DEBUG + else { + SERIAL_ECHO_MSG("SPI ERROR (", spibusIdx, ")"); + } +#endif +} + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS +static void IRAM_ATTR spi_async_process_isr_spibus0(void *ud) { + spi_async_process_isr(ud, 0); +} +static void IRAM_ATTR spi_async_process_isr_spibus1(void *ud) { + spi_async_process_isr(ud, 1); +} +#endif +static void IRAM_ATTR spi_async_process_isr_spibus2(void *ud) { + spi_async_process_isr(ud, 2); +} +static void IRAM_ATTR spi_async_process_isr_spibus3(void *ud) { + spi_async_process_isr(ud, 3); +} + +static void SPIInstallAsync(spi_dev_t& SPI, intr_handle_t& handleOut) { + int intsrc = -1; + void (*inthandler)(void*) = nullptr; + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (&SPI == &SPI0) { + intsrc = ETS_SPI0_INTR_SOURCE; + inthandler = spi_async_process_isr_spibus0; + } + else if (&SPI == &SPI1) { + intsrc = ETS_SPI1_INTR_SOURCE; + inthandler = spi_async_process_isr_spibus1; + } + else +#endif + if (&SPI == &SPI2) { + intsrc = ETS_SPI2_INTR_SOURCE; + inthandler = spi_async_process_isr_spibus2; + } + else if (&SPI == &SPI3) { + intsrc = ETS_SPI3_INTR_SOURCE; + inthandler = spi_async_process_isr_spibus3; + } + else + _spi_on_error(1); + + esp_err_t err = esp_intr_alloc(intsrc, ESP_INTR_FLAG_IRAM, inthandler, nullptr, &handleOut); + + if (err != ESP_OK) + _spi_on_error(1); +} + +static void SPIUninstallAsync(intr_handle_t handle) { + // Unregister the ISR. + esp_err_t err = esp_intr_free(handle); + + if (err != ESP_OK) + _spi_on_error(2); +} + +static void SPIAsyncInitialize() { +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + SPIInstallAsync(SPI0, _spi0_interrupt); + SPIInstallAsync(SPI1, _spi1_interrupt); +#endif + SPIInstallAsync(SPI2, _spi2_interrupt); + SPIInstallAsync(SPI3, _spi3_interrupt); +} + +static void SPIStartRawAsync(spi_dev_t& SPI, const void *buf, uint32_t txlen, uint8_t txunitsize, void (*completeCallback)(void*), void *ud) { + volatile spi_async_process_t& proc = _current_spi_proc; + + while (proc.is_active) { /* wait for any async process to conclude before we start another */ } + + cli(); + + proc.current_spibus = &SPI; + proc.current_buffer = buf; + proc.curoff_bytes = 0; + proc.txlen = txlen; + proc.txunitsize = txunitsize; + proc.completeCallback = completeCallback; + proc.complete_ud = ud; + proc.is_active = true; + + sei(); + + // Enable the interrupt (make sure that we do not trigger it over here already). + SPI.SPI_SLAVE_REG.SPI_TRANS_DONE = false; + SPI.SPI_SLAVE_REG.SPI_TRANS_INTEN = true; + + // Kick it off. + spi_async_fill_buffer(proc); +} + +static void SPIAbortRawAsync() { + cli(); + + volatile spi_async_process_t& proc = _current_spi_proc; + + if (proc.is_active) { + proc.is_active = false; + + spi_dev_t& SPI = *proc.current_spibus; + + SPI.SPI_SLAVE_REG.SPI_TRANS_INTEN = false; + SPI.SPI_SLAVE_REG.SPI_TRANS_DONE = false; + } + + sei(); +} + +#endif //HAL_SPI_SUPPORTS_ASYNC + +#ifndef HALSPI_DISABLE_DMA + +#define SPIDMA_OWNER_CPU 0 +#define SPIDMA_OWNER_DMAC 1 + +// Has to be allocated inside the DMA-accessible memory range. +// page 113 of ESP32 TRM. +struct dma_descriptor_t { + // Configuration bits. + volatile uint32_t size : 12; + volatile uint32_t length : 12; + volatile uint32_t reserved : 6; + volatile uint32_t eof : 1; + volatile uint32_t owner : 1; + + void *address; + dma_descriptor_t *next; +}; +static_assert(sizeof(dma_descriptor_t) == 12, "invalid size of ESP32 dma_descriptor_t"); + +#ifndef HALSPI_ESP32_DMADESC_COUNT + // The default count of DMA descriptors usable. + #define HALSPI_ESP32_DMADESC_COUNT 1 +#endif + +#ifdef HALSPI_ESP32_STATIC_DMADESCS +static dma_descriptor_t _usable_dma_descs_static[HALSPI_ESP32_DMADESC_COUNT]; +#else +static dma_descriptor_t *_usable_dma_descs_dynamic = nullptr; +static uint32_t _usable_dma_descs_count = 0; +#endif + +// Specifies the valid memory range for DMA descriptors (not specified if necessary for DMA buffers). +#define ESP32_DMA_BASE 0x3FF00000 +#define ESP32_DMA_SIZE (1<<20) + +inline bool DMAIsValidDescriptor(dma_descriptor_t *desc) { + size_t addr = (size_t)desc; + + return ( addr >= ESP32_DMA_BASE && addr <= (ESP32_DMA_BASE + ESP32_DMA_SIZE) ); +} + +inline void DMAInitializeMachine() { +#ifdef HALSPI_ESP32_STATIC_DMADESCS + for (dma_descriptor_t& desc : _usable_dma_descs_static) { + if (DMAIsValidDescriptor(&desc) == false) { + _spi_on_error(3); + } + } +#else + void *dmabuf = heap_caps_malloc( sizeof(dma_descriptor_t)*HALSPI_ESP32_DMADESC_COUNT, MALLOC_CAP_DMA ); + if (dmabuf == nullptr) + _spi_on_error(3); + _usable_dma_descs_dynamic = (dma_descriptor_t*)dmabuf; + _usable_dma_descs_count = HALSPI_ESP32_DMADESC_COUNT; + if (DMAIsValidDescriptor(_usable_dma_descs_dynamic) == false) + _spi_on_error(3); +#endif +} + +/* Important restriction on DMA-usable memory addresses and their buffer sizes: + Please note that the buffer address pointer field in in_link descriptors should be word-aligned, and the size field (...). + -> each DMA-depending Marlin operation will need to use a special memory allocation function that ensures DMA-capability! + -> each DMA-internal memory buffer accepting function has to deny the buffer if it does not match + the requirements! +*/ +inline bool DMAIsValidDataBuffer(const void *buf, size_t bufsz) { + size_t bufaddr = (size_t)buf; + + if (bufaddr % sizeof(uint32_t) != 0) return false; + if (bufsz % sizeof(uint32_t) != 0) return false; + + return true; +} + +// Not every SPI bus is DMA-capable. +inline bool DMAIsCapableSPIBus(spi_dev_t& SPI) { +#ifdef HALSPI_ENABLE_INTERNBUS + if (&SPI == &SPI1) return true; +#endif + if (&SPI == &SPI2) return true; + if (&SPI == &SPI3) return true; + return false; +} + +struct dma_process_t { + const void *current_buffer; + size_t bufsize; + size_t txlen; + size_t curoff; + bool is_active; +}; + +static dma_process_t dma_current_process; + +static void DMABusInitialize(spi_dev_t& SPI) { +#ifdef HALSPI_DEBUG + if (DMAIsCapableSPIBus(SPI) == false) + _spi_on_error(4); +#endif + + // Reset and enable the SPI DMA clock. + DPORT_PERIP_RST_EN_REG.DPORT_SPI_DMA_RST = true; + DPORT_PERIP_RST_EN_REG.DPORT_SPI_DMA_RST = false; + DPORT_PERIP_CLK_EN_REG.DPORT_SPI_DMA_CLK_EN = true; + + // Select the SPI DMA channel. + auto spibusIdx = SPIGetBusIndex(SPI); + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (spibusIdx == 1) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI1_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + } + else +#endif + if (spibusIdx == 2) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI2_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + } + else if (spibusIdx == 3) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI3_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + } +} + +static void DMABusShutdown(spi_dev_t& SPI) { + // Unselect the SPI DMA channel. + auto spibusIdx = SPIGetBusIndex(SPI); + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (spibusIdx == 1) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI1_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; + } + else +#endif + if (spibusIdx == 2) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI2_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; + } + else if (spibusIdx == 3) { + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI3_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; + } + + // Disable the SPI DMA clock. + DPORT_PERIP_CLK_EN_REG.DPORT_SPI_DMA_CLK_EN = false; +} + +// TODO: manage list of free descriptors to speed up the process of generating a DMA chain. + +static dma_descriptor_t* DMAGetFreeDescriptor() { +#ifdef HALSPI_ESP32_STATIC_DMADESCS + for (dma_descriptor_t& desc : _usable_dma_descs_static) { +#else + for (uint32_t _n = 0; _n < _usable_dma_descs_count; _n++) { + dma_descriptor_t& desc = _usable_dma_descs_dynamic[_n]; +#endif + if (desc.owner == SPIDMA_OWNER_CPU) { +#ifdef HALSPI_DEBUG + if (DMAIsValidDescriptor(&desc) == false) + _spi_on_error(5); +#endif + + return &desc; + } + } + return nullptr; +} + +// UNSIGNED ONLY! +// (this would be much nicer with C++17 constexpr-if or C++20 concepts) +template +inline numberType _ALIGN(numberType val, numberType alignBy) { + numberType rem = (val % alignBy); + +#if 0 + if (rem < (numberType)0) rem = (numberType)-rem; +#endif + + return ( rem > 0 ? val + rem : val ); +} + +static dma_descriptor_t* DMAGenerateAcquireChain(dma_process_t& proc) { + dma_descriptor_t *startdesc = nullptr; + dma_descriptor_t *chainend = nullptr; + + while (proc.curoff < proc.txlen) { + dma_descriptor_t *freedesc = DMAGetFreeDescriptor(); + + if (freedesc == nullptr) break; + + size_t left_to_transmit = (proc.txlen - proc.curoff); + uint32_t txcount = (uint32_t)_MIN ((1<<12)-4, left_to_transmit); + uint32_t txbufsz = _ALIGN(txcount, (uint32_t)4u); + + freedesc->size = txbufsz; + freedesc->length = txcount; + freedesc->reserved = 0; + freedesc->eof = true; + freedesc->address = ((uint8_t*)proc.current_buffer + proc.curoff); + freedesc->next = nullptr; + + // Advance the process. + proc.curoff += txcount; + + // Give ownership of the descriptor to the DMA controller. + // (this decision turns valid as soon as the DMAC is kicked-off!) + freedesc->owner = SPIDMA_OWNER_DMAC; + + if (chainend != nullptr) { + chainend->eof = false; + chainend->next = freedesc; + } + chainend = freedesc; + + if (startdesc == nullptr) { + startdesc = freedesc; + } + } + + return startdesc; +} + +static void DMASendBlocking(spi_dev_t& SPI, const void *buf, size_t bufsize, size_t txlen) { + DMABusInitialize(SPI); + + // Configure DMA for the SPI bus. + spi_dma_conf_reg_t SPI_DMA_CONF_REG; + SPI_DMA_CONF_REG.SPI_DMA_CONTINUE = false; + SPI_DMA_CONF_REG.SPI_DMA_TX_STOP = false; + SPI_DMA_CONF_REG.SPI_DMA_RX_STOP = false; + SPI_DMA_CONF_REG.SPI_OUT_DATA_BURST_EN = true; + SPI_DMA_CONF_REG.SPI_INDSCR_BURST_EN = true; + SPI_DMA_CONF_REG.SPI_OUTDSCR_BURST_EN = true; + SPI_DMA_CONF_REG.SPI_OUT_EOF_MODE = 1; + SPI_DMA_CONF_REG.SPI_AHBM_RST = false; + SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = false; + SPI_DMA_CONF_REG.SPI_OUT_RST = false; + SPI_DMA_CONF_REG.SPI_IN_RST = false; + (spi_dma_conf_reg_t&)SPI.SPI_DMA_CONF_REG = SPI_DMA_CONF_REG; + + dma_process_t& proc = dma_current_process; + proc.is_active = true; + proc.current_buffer = buf; + proc.bufsize = bufsize; + proc.txlen = txlen; + proc.curoff = 0; + + // Is there data left to send? + while (proc.curoff < proc.txlen) { + // Generate a transfer chain. + dma_descriptor_t *chain = DMAGenerateAcquireChain(proc); + + // Configure the transfer. + SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = ((uint32_t)chain - ESP32_DMA_BASE); + SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = true; + + // Kick it off. + SPI.SPI_CMD_REG.SPI_USR = true; + while (SPI.SPI_CMD_REG.SPI_USR) { + /* wait until DMA transfer has finished */ + _spi_infobeep(3); + } + } + + proc.is_active = false; + + DMABusShutdown(SPI); +} + +#endif //HALSPI_DISABLE_DMA + +} // namespace MarlinESP32 + +static void _spiAsyncBarrier() { +#ifdef HAL_SPI_SUPPORTS_ASYNC + while (MarlinESP32::_current_spi_proc.is_active) { /* wait until any async-SPI process has finished */ } +#endif +} + +static MarlinESP32::gpioMapResult_t _spi_gpiomap; +static volatile bool _spi_is_active = false; +static volatile bool _spi_transaction_is_running = false; +static MarlinESP32::clkcnt_res_t _spi_clkcnt; +#ifdef HALSPI_DEBUG +static int _spi_core_id; +#endif + +void spiBegin() { +#ifdef HALSPI_DEBUG + _spi_core_id = xPortGetCoreID(); +#endif + +#ifdef HAL_SPI_SUPPORTS_ASYNC + MarlinESP32::SPIAsyncInitialize(); +#endif + +#ifndef HALSPI_DISABLE_DMA + // Security checks. + MarlinESP32::DMAInitializeMachine(); +#endif + + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + + // By default disable the clock signals. +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + // SPI0/1 are used for instruction-flash-memory access so it is not a good idea + // to use them in Marlin! + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI01_CLK_EN = false; +#endif + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI2_CLK_EN = false; + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI3_CLK_EN = false; +#if !defined(HALSPI_DISABLE_DMA) + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI_DMA_CLK_EN = false; +#endif + + // Reset DMA channel selections. +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + MarlinESP32::DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI1_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; +#endif + MarlinESP32::DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI2_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; + MarlinESP32::DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI3_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_NONE; + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + MarlinESP32::SPIResetBus(MarlinESP32::SPI0); + MarlinESP32::SPIResetBus(MarlinESP32::SPI1); +#endif + MarlinESP32::SPIResetBus(MarlinESP32::SPI2); + MarlinESP32::SPIResetBus(MarlinESP32::SPI3); +} + +void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +#ifdef HALSPI_DEBUG + if (_spi_core_id != xPortGetCoreID()) + _spi_on_error(10); +#endif + +#ifdef HAL_SPI_SUPPORTS_ASYNC + while (_spi_is_active) { /* wait until any other transaction has finished */ } +#else + if (_spi_is_active) + _spi_on_error(6); +#endif + + _spi_gpiomap = MarlinESP32::SPIMapGPIO(hint_sck, hint_miso, hint_mosi, hint_cs); + _spi_is_active = true; + + uint8_t spibusIdx = _spi_gpiomap.spibusIdx; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(spibusIdx); + + // Enable the clock signal and reset the peripheral. +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (spibusIdx == 0 || spibusIdx == 1) { + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI01_RST = true; + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI01_RST = false; + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI01_CLK_EN = true; + } + else +#endif + if (spibusIdx == 2) { + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI2_RST = true; + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI2_RST = false; + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI2_CLK_EN = true; + } + else if (spibusIdx == 3) { + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI3_RST = true; + MarlinESP32::DPORT_PERIP_RST_EN_REG.DPORT_SPI3_RST = false; + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI3_CLK_EN = true; + } + + // By default we transfer using MSB. + MarlinESP32::SPIConfigureBitOrder(SPI, SPI_BITORDER_MSB); + + // Chapter 7.4.2 is relevant for the direct-IO/IOMUX timing optimization. + uint32_t apbfreq = getApbFrequency(); // from Arduino SDK, depends on undocumented things. + MarlinESP32::clkcnt_res_t clkdiv = MarlinESP32::SPIApproximateClockDivider(maxClockFreq, apbfreq); + + _spi_clkcnt = clkdiv; + + // Set basic SPI configuration. + SPI.SPI_SLAVE_REG.SPI_SLAVE_MODE = 0; // master. + + // Enable the required SPI phases. + SPI.SPI_USER_REG.SPI_USR_COMMAND = false; + SPI.SPI_USER_REG.SPI_USR_ADDR = false; + SPI.SPI_USER_REG.SPI_USR_DUMMY = false; + SPI.SPI_USER_REG.SPI_USR_DUMMY_IDLE = false; + SPI.SPI_USER_REG.SPI_SIO = false; + SPI.SPI_USER_REG.SPI_USR_MOSI = (_spi_gpiomap.gpio_mosi >= 0); + SPI.SPI_USER_REG.SPI_USR_MISO = (_spi_gpiomap.gpio_miso >= 0); + +#ifdef HAL_SPI_SUPPORTS_ASYNC + // Clear important interrupt settings. + SPI.SPI_SLAVE_REG.SPI_TRANS_INTEN = false; + SPI.SPI_SLAVE_REG.SPI_SLV_WR_STA_INTEN = false; + SPI.SPI_SLAVE_REG.SPI_SLV_RD_STA_INTEN = false; + SPI.SPI_SLAVE_REG.SPI_SLV_RD_BUF_INTEN = false; + SPI.SPI_SLAVE_REG.SPI_SLV_WR_BUF_INTEN = false; +#endif + + // Configure the SPI clock to MODE0 by default. + MarlinESP32::SPIConfigureClock(SPI, SPI_CLKMODE_0, _spi_gpiomap.datasig_is_direct_iomux, clkdiv); + + // Enable full-duplex communication (4lines R/W) + SPI.SPI_USER_REG.SPI_DOUTDIN = true; + + // On ESP32 the input and output buffers of SPI are always being randomly overwritten/trashed. + // Thus it makes no sense to divide them! + // Notes: + // "If the data length is over 64 bytes, the extra part will be written from SPI_W0_REG." + // - page 120 of ESP32 technical reference manual. + // The buffer on the HIGHPART is limited to the HIGHPART. + SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART = false; + SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART = false; + + _spi_transaction_is_running = false; +} + +static void _maybe_start_transaction() { + if (_spi_transaction_is_running) return; + if (_spi_gpiomap.gpio_cs >= 0) { + OUT_WRITE(_spi_gpiomap.gpio_cs, LOW); + } + _spi_transaction_is_running = true; +} + +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + uint32_t clock; + + switch (spiRate) { + case SPI_FULL_SPEED: clock = 16000000; break; + case SPI_HALF_SPEED: clock = 8000000; break; + case SPI_QUARTER_SPEED: clock = 4000000; break; + case SPI_EIGHTH_SPEED: clock = 2000000; break; + case SPI_SIXTEENTH_SPEED: clock = 1000000; break; + case SPI_SPEED_5: clock = 500000; break; + case SPI_SPEED_6: clock = 250000; break; + default: clock = 1000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); +} + +void spiClose() { + _spiAsyncBarrier(); + + if (_spi_is_active == false) + _spi_on_error(7); + + if (_spi_transaction_is_running) { + if (_spi_gpiomap.gpio_cs >= 0) { + OUT_WRITE(_spi_gpiomap.gpio_cs, HIGH); + } + _spi_transaction_is_running = false; + } + + // Disable the clock signal. + uint8_t spibusIdx = _spi_gpiomap.spibusIdx; + +#ifdef HALSPI_ESP32_ENABLE_INTERNBUS + if (spibusIdx == 0 || spibusIdx == 1) { + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI01_CLK_EN = false; + } + else +#endif + if (spibusIdx == 2) { + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI2_CLK_EN = false; + } + else if (spibusIdx == 3) { + MarlinESP32::DPORT_PERIP_CLK_EN_REG.DPORT_SPI3_CLK_EN = false; + } + + MarlinESP32::SPIUnmapGPIO(_spi_gpiomap); + + _spi_is_active = false; +} + +void spiSetBitOrder(int bitOrder) { + _spiAsyncBarrier(); + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + MarlinESP32::SPIConfigureBitOrder(SPI, bitOrder); +} + +void spiSetClockMode(int mode) { + _spiAsyncBarrier(); + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + MarlinESP32::SPIConfigureClock(SPI, mode, _spi_gpiomap.datasig_is_direct_iomux, _spi_clkcnt); +} + +void spiSend(uint8_t txval) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + MarlinESP32::SPITransaction(SPI, actualWriteCount); +} + +void spiSend16(uint16_t txval) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + MarlinESP32::SPITransaction(SPI, actualWriteCount); +} + +uint8_t spiRec(uint8_t txval) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MISO == false) return 0; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI) { + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + } + + MarlinESP32::SPITransaction(SPI, sizeof(uint8_t)); + + uint8_t result; + uint16_t actualReadCount; + MarlinESP32::SPIReadDataFromTransfer(SPI, &result, 1, 0, 0, actualReadCount); + + return result; +} + +uint16_t spiRec16(uint16_t txval) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MISO == false) return 0; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI) { + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + } + + MarlinESP32::SPITransaction(SPI, sizeof(uint16_t)); + + uint16_t result; + uint16_t actualReadCount; + MarlinESP32::SPIReadDataFromTransfer(SPI, &result, 1, 0, 0, actualReadCount); + + return result; +} + +template +inline void _spiWriteRepeatToBufferEx( + MarlinESP32::spi_dev_t& SPI, numberType val, uint32_t cnt_bytes, uint16_t& total_write_cnt_out, + uint16_t spi_writebuf_size, bool notrevbits, uint16_t spi_buf_numstartidx +) { + uint16_t txcount = (uint16_t)_MIN (cnt_bytes, spi_writebuf_size); + + for (uint16_t n = 0; n < txcount; n++) { + uint8_t byteval = MarlinESP32::SPIGetSingleByteToTransferEx(SPI, val, (n % sizeof(numberType)), notrevbits); + MarlinESP32::SPIWriteSingleByteToTransferEx(SPI, byteval, n, spi_buf_numstartidx); + } + total_write_cnt_out = txcount; +} + +template +inline void _spiWriteRepeatToBuffer(MarlinESP32::spi_dev_t& SPI, numberType val, uint32_t cnt_bytes, uint16_t& total_write_cnt_out) { + uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + uint16_t spi_buf_numstartidx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + + _spiWriteRepeatToBufferEx(SPI, val, cnt_bytes, total_write_cnt_out, spi_writebuf_size, notrevbits, spi_buf_numstartidx); +} + +void spiRead(uint8_t *buf, uint16_t cnt, uint8_t txval) { + if (cnt == 0) return; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MISO == false) { + spiWriteRepeat(txval, cnt); + return; + } + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + +#if 0 +#ifndef HALSPI_DISABLE_DMA + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt) +#ifndef HALSPI_ESP32_DMA_ALWAYS + && cnt > MarlinESP32::SPIGetReadBufferSize(SPI) +#endif + ) { + // For bigger transfers we should use DMA. + //TODO. + return; + } + + // Use direct SPI for such small transfer sizes. +#endif +#endif + // The no-DMA version. + + uint16_t txprogress = 0; + + while (txprogress < cnt) { + uint16_t txcount = _MIN(cnt - txprogress, MarlinESP32::SPIGetReadBufferSize(SPI)); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == true) { + uint16_t _tmp; + _spiWriteRepeatToBuffer(SPI, txval, txcount, _tmp); + } + + MarlinESP32::SPITransaction(SPI, txcount); + + uint16_t actualWriteCount; + MarlinESP32::SPIReadDataFromTransfer(SPI, buf, cnt, txprogress, 0, actualWriteCount); + + txprogress += txcount; + } +} + +void spiSendBlock(uint8_t token, const uint8_t *buf) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + +#ifndef HALSPI_DISABLE_DMA + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, 512)) { + // Only attempt DMA transfer if the buffer is valid. + MarlinESP32::DMASendBlocking(SPI, buf, 512, 512); + return; + } + + // Use direct SPI otherwise. +#endif + + uint16_t outbufprog = 0; + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, &token, 1, 0, 0, actualWriteCount); + + outbufprog = actualWriteCount; + + uint16_t bufprog = 0; + + while (bufprog < 512) { + MarlinESP32::SPIWriteDataToTransfer(SPI, buf, 512, bufprog, outbufprog, actualWriteCount); + outbufprog += actualWriteCount; + MarlinESP32::SPITransaction(SPI, outbufprog); + + bufprog += outbufprog; + outbufprog = 0; + } +} + +void spiWrite(const uint8_t *buf, uint16_t cnt) { + if (cnt == 0) return; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + +#ifndef HALSPI_DISABLE_DMA + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt) +#ifndef HALSPI_ESP32_DMA_ALWAYS + && cnt > MarlinESP32::SPIGetWriteBufferSize(SPI) +#endif + ) { + // For bigger transfers we should use DMA. + MarlinESP32::DMASendBlocking(SPI, buf, cnt, cnt); + return; + } + + // Use direct SPI for small transfer sizes. +#endif + + uint16_t bufprog = 0; + + while (bufprog < cnt) { + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, buf, cnt, bufprog, 0, actualWriteCount); + MarlinESP32::SPITransaction(SPI, actualWriteCount); + + bufprog += actualWriteCount; + } +} + +void spiWrite16(const uint16_t *buf, uint16_t cnt) { + if (cnt == 0) return; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + uint32_t cnt_bytes = (cnt * sizeof(uint16_t)); + + // Problem: before we can kick-off the DMA transfer to the SPI device we have to FORMAT THE ENTIRE DMA BUFFER to match + // the byte-by-byte requirement of the DMA-to-SPI-buffer filling! This is kind of a bummer because it means that DMA + // transfers of color buffers have to be filled in a special way, at best directly when they are created. + // Not only that but also the buffer needs to meet special allocation rules. Yikes! + + // This would call for a special DMA-capable buffer filling structure/framework that is also part of the HAL and + // specialized per architecture. + // At least, ESP32 SPI is pretty fast as it currently stands, even without async DMA. + +#if 0 +#ifndef HALSPI_DISABLE_DMA + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt_bytes) && cnt > MarlinESP32::SPIGetWriteBufferSize(SPI)) { + // For bigger transfers we should use DMA. + //TODO. + return; + } + + // Use direct SPI for small transfer sizes. +#endif +#endif + + uint32_t bufprog = 0; + + while (bufprog < cnt_bytes) { + uint16_t actualWriteCount; + MarlinESP32::SPIWriteDataToTransfer(SPI, buf, cnt, bufprog, 0, actualWriteCount); + MarlinESP32::SPITransaction(SPI, actualWriteCount); + + bufprog += actualWriteCount; + } +} + +void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + if (repcnt == 0) return; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + // There is no good repetition output engine on the ESP32 DMAC. + // Thus we have to use generic SPI. + + uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + + uint16_t txprog = 0; + + while (txprog < repcnt) { + uint16_t actualWriteCount; + _spiWriteRepeatToBufferEx(SPI, val, repcnt - txprog, actualWriteCount, spi_writebuf_size, notrevbits, start_num_idx); + + MarlinESP32::SPITransaction(SPI, actualWriteCount); + + txprog += actualWriteCount; + } +} + +void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + if (repcnt == 0) return; + + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + _spiAsyncBarrier(); + + _maybe_start_transaction(); + + // There is no good repetition output engine on the ESP32 DMAC. + // Thus we have to use generic SPI. + + uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); + bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + + uint32_t txprog = 0; + uint32_t repcnt_bytes = repcnt * sizeof(uint16_t); + + while (txprog < repcnt_bytes) { + uint16_t actualWriteCount; + _spiWriteRepeatToBufferEx(SPI, val, repcnt_bytes - txprog, actualWriteCount, spi_writebuf_size, notrevbits, start_num_idx); + + MarlinESP32::SPITransaction(SPI, actualWriteCount); + + txprog += actualWriteCount; + } +} + +#ifdef HAL_SPI_SUPPORTS_ASYNC + +void spiWriteAsync(const uint8_t *buf, uint16_t nbyte, void (*completeCallback)(void*), void *ud) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + if (nbyte == 0) { + if (completeCallback) + completeCallback(ud); + return; + } + + _maybe_start_transaction(); + + // TODO: we could implement this async using DMA aswell because 8bit transfers are easily done using + // the hardware. Right now it is fine using SPI interrupts anyway (CPU is not being slowed down by slow SPI rates). + + MarlinESP32::SPIStartRawAsync(SPI, buf, nbyte, sizeof(uint8_t), completeCallback, ud); +} + +void spiWriteAsync16(const uint16_t *buf, uint16_t txcnt, void (*completeCallback)(void*), void *ud) { + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + + if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; + + if (txcnt == 0) { + if (completeCallback) + completeCallback(ud); + return; + } + + _maybe_start_transaction(); + + MarlinESP32::SPIStartRawAsync(SPI, buf, txcnt, sizeof(uint16_t), completeCallback, ud); +} + +void spiAsyncAbort() { + MarlinESP32::SPIAbortRawAsync(); +} + +void spiAsyncJoin() { + _spiAsyncBarrier(); +} + +bool spiAsyncIsRunning() { + return (MarlinESP32::_current_spi_proc.is_active); +} + +#endif + +#endif + +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp new file mode 100644 index 000000000000..925fa563643f --- /dev/null +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp @@ -0,0 +1,277 @@ +/** + * 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 + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ +#ifdef ARDUINO_ARCH_ESP32 + +#include "../../inc/MarlinConfig.h" + +#include "../shared/HAL_SPI.h" + +#if !ENABLED(SOFTWARE_SPI) && ENABLED(HALSPI_HW_GENERIC) + +// ------------------------ +// Hardware SPI +// ------------------------ + +static void _spi_on_error() { + for (;;) { +#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(150); + OUT_WRITE(BEEPER_PIN, LOW); + delay(3000); +#endif + } +} + +static void _spi_infobeep(uint32_t code) { +#if PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(300); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); +#endif +} + +#include +#include + +static SPISettings spiConfig; + +static uint32_t _spi_clock; +static int _spi_bitOrder; +static int _spi_clkmode; +static int _spi_pin_cs; +static bool _spi_initialized = false; +static bool _spi_transaction_is_running = false; + +void spiBegin() { + #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif +} + +void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + if (hint_sck != -1) { + SET_OUTPUT(hint_sck); + } + if (hint_miso != -1) { + SET_INPUT(hint_miso); + } + if (hint_mosi != -1) { + SET_OUTPUT(hint_mosi); + } + if (hint_cs != -1) { + SET_OUTPUT(hint_cs); + } + + if (_spi_initialized) + _spi_on_error(); + + _spi_clock = maxClockFreq; + _spi_bitOrder = MSBFIRST; + _spi_clkmode = SPI_MODE0; + _spi_pin_cs = hint_cs; + spiConfig = SPISettings(maxClockFreq, _spi_bitOrder, _spi_clkmode); + // https://github.com/espressif/arduino-esp32/blob/master/libraries/SPI/src/SPI.cpp SPIClass::begin method. + SPI.begin(hint_sck, hint_miso, hint_mosi); + _spi_initialized = true; + _spi_transaction_is_running = false; +} + +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + uint32_t clock; + + switch (spiRate) { + case SPI_FULL_SPEED: clock = 16000000; break; + case SPI_HALF_SPEED: clock = 8000000; break; + case SPI_QUARTER_SPEED: clock = 4000000; break; + case SPI_EIGHTH_SPEED: clock = 2000000; break; + case SPI_SIXTEENTH_SPEED: clock = 1000000; break; + case SPI_SPEED_5: clock = 500000; break; + case SPI_SPEED_6: clock = 250000; break; + default: clock = 1000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); +} + +static void _maybe_start_transaction() { + if (_spi_transaction_is_running) return; + SPI.beginTransaction(spiConfig); + if (_spi_pin_cs != -1) + OUT_WRITE(_spi_pin_cs, LOW); + _spi_transaction_is_running = true; +} + +void spiClose() { + if (!_spi_initialized) + _spi_on_error(); + if (_spi_transaction_is_running) { + if (_spi_pin_cs != -1) + OUT_WRITE(_spi_pin_cs, HIGH); + SPI.endTransaction(); + _spi_transaction_is_running = false; + } + SPI.end(); + _spi_initialized = false; +} + +void spiSetBitOrder(int bitOrder) { + bool update = false; + if (bitOrder == SPI_BITORDER_MSB) { + _spi_bitOrder = MSBFIRST; + update = true; + } + else if (bitOrder == SPI_BITORDER_LSB) { + _spi_bitOrder = LSBFIRST; + update = true; + } + if (update) { + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clkmode); + if (_spi_transaction_is_running) { + // On ESP32 it is safe to keep the chip-select LOW even if restarting + // a transaction, judging by the SPI library and HAL sources. + SPI.endTransaction(); + SPI.beginTransaction(spiConfig); + } + } +} + +void spiSetClockMode(int mode) { + bool update = false; + if (mode == SPI_CLKMODE_0) { + _spi_clkmode = SPI_MODE0; + update = true; + } + else if (mode == SPI_CLKMODE_1) { + _spi_clkmode = SPI_MODE1; + update = true; + } + else if (mode == SPI_CLKMODE_2) { + _spi_clkmode = SPI_MODE2; + update = true; + } + else if (mode == SPI_CLKMODE_3) { + _spi_clkmode = SPI_MODE3; + update = true; + } + if (update) { + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clkmode); + if (_spi_transaction_is_running) { + SPI.endTransaction(); + SPI.beginTransaction(spiConfig); + } + } +} + +uint8_t spiRec(uint8_t txval) { + _maybe_start_transaction(); + uint8_t returnByte = SPI.transfer(txval); + return returnByte; +} + +uint16_t spiRec16(uint16_t txval) { + _maybe_start_transaction(); + uint16_t res = SPI.transfer16(txval); + return res; +} + +void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + if (nbyte == 0) return; + _maybe_start_transaction(); + for (uint16_t n = 0; n < nbyte; n++) + buf[n] = SPI.transfer(txval); +} + +void spiSend(uint8_t b) { + _maybe_start_transaction(); + SPI.write(b); +} + +void spiSend16(uint16_t v) { + _maybe_start_transaction(); + SPI.write16(v); +} + +void spiSendBlock(uint8_t token, const uint8_t *buf) { + _maybe_start_transaction(); + SPI.write(token); + SPI.writeBytes(buf, 512); +} + +void spiWrite(const uint8_t *buf, uint16_t cnt) { + _maybe_start_transaction(); + SPI.writeBytes(buf, cnt); +} + +void spiWrite16(const uint16_t *buf, uint16_t cnt) { + if (cnt == 0) return; + _maybe_start_transaction(); + for (uint16_t n = 0; n < cnt; n++) + SPI.write16(buf[n]); +} + +void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + if (repcnt == 0) return; + _maybe_start_transaction(); + for (uint16_t n = 0; n < repcnt; n++) + SPI.write(val); +} + +void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + if (repcnt == 0) return; + _maybe_start_transaction(); + for (uint16_t n = 0; n < repcnt; n++) { + SPI.write16(val); + } +} + +#endif + +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/MarlinSPI.h b/Marlin/src/HAL/ESP32/HAL_SPI_SW.cpp similarity index 67% rename from Marlin/src/HAL/AVR/MarlinSPI.h rename to Marlin/src/HAL/ESP32/HAL_SPI_SW.cpp index 0c447ba4cb3d..bd1a76b90e55 100644 --- a/Marlin/src/HAL/AVR/MarlinSPI.h +++ b/Marlin/src/HAL/ESP32/HAL_SPI_SW.cpp @@ -1,9 +1,10 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez * * 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 @@ -19,8 +20,19 @@ * along with this program. If not, see . * */ -#pragma once +#ifdef ARDUINO_ARCH_ESP32 -#include +#include "../../inc/MarlinConfig.h" -using MarlinSPI = SPIClass; +#include "../shared/HAL_SPI.h" + +#if ENABLED(SOFTWARE_SPI) + + // ------------------------ + // Software SPI + // ------------------------ + #error "Software SPI not supported for ESP32. Use Hardware SPI." + +#endif + +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/MarlinSPI.h b/Marlin/src/HAL/ESP32/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/ESP32/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h index 4da600179d6c..ed320ebab849 100644 --- a/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/ESP32/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/ESP32." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/ESP32." #endif diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 8f95d7eef7d5..4cf9da005061 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -72,8 +72,7 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt OUT_WRITE(DOGLCD_A0, HIGH); OUT_WRITE(LCD_RESET_PIN, HIGH); u8g_Delay(5); - spiBegin(); - spiInit(LCD_SPI_SPEED); // TODO: we should hint the used SPI pins here. + spiInit(LCD_SPI_SPEED, DOGLCD_SCK, DOGLCD_MISO, DOGLCD_MOSI, DOGLCD_CS); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/LINUX/MarlinSPI.h b/Marlin/src/HAL/LINUX/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/LINUX/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h index 99a6fc27534a..e66038511069 100644 --- a/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/LINUX/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/LINUX." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/LINUX." #endif diff --git a/Marlin/src/HAL/LINUX/spi_pins.h b/Marlin/src/HAL/LINUX/spi_pins.h index 33136ac9dd80..91e1f509865e 100644 --- a/Marlin/src/HAL/LINUX/spi_pins.h +++ b/Marlin/src/HAL/LINUX/spi_pins.h @@ -25,7 +25,7 @@ #include "../../inc/MarlinConfigPre.h" #if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently + #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use // spiBeginTransaction. diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index b0eeb983b445..8d64ce69e48a 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -236,13 +236,21 @@ class MarlinHAL { // Called by Temperature::init for each sensor at startup static void adc_enable(const pin_t pin) { + // On some BTT SKR V1.4 boards the ADC peripheral could be faulty. + // Disable it by setting that macro in your Configuration.h +#ifndef LPC_DISABLE_ADC FilteredADC::enable_channel(pin); +#endif } // Begin ADC sampling on the given pin. Called from Temperature::isr! static uint32_t adc_result; static void adc_start(const pin_t pin) { +#ifndef LPC_DISABLE_ADC adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits +#else + adc_result = 0; +#endif } // Is the ADC ready for reading? diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp deleted file mode 100644 index 800e23847dd9..000000000000 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ /dev/null @@ -1,423 +0,0 @@ -/** - * 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 . - * - */ - -/** - * Software SPI functions originally from Arduino Sd2Card Library - * Copyright (c) 2009 by William Greiman - */ - -/** - * For TARGET_LPC1768 - */ - -/** - * Hardware SPI and Software SPI implementations are included in this file. - * The hardware SPI runs faster and has higher throughput but is not compatible - * with some LCD interfaces/adapters. - * - * Control of the slave select pin(s) is handled by the calling routines. - * - * Some of the LCD interfaces/adapters result in the LCD SPI and the SD card - * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with - * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is - * active. If any of these pins are shared then the software SPI must be used. - * - * A more sophisticated hardware SPI can be found at the following link. - * This implementation has not been fully debugged. - * https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e - */ - -#ifdef TARGET_LPC1768 - -#include "../../inc/MarlinConfig.h" -#include - -// Hardware SPI and SPIClass -#include -#include - -#include "../shared/HAL_SPI.h" - -// ------------------------ -// Public functions -// ------------------------ -#if ENABLED(LPC_SOFTWARE_SPI) - - // Software SPI - - #include - - static uint8_t SPI_speed = SPI_FULL_SPEED; - - static uint8_t spiTransfer(uint8_t b) { - return swSpiTransfer(b, SPI_speed, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); - } - - void spiBegin() { - swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); - } - - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - SPI_speed = - swSpiInit(spiRate, - ( hint_sck != -1 ) ? hint_sck : SD_SCK_PIN, - ( hint_mosi != -1 ) ? hint_mosi : SD_MOSI_PIN - ); - } - - void spiClose() { - } - - uint8_t spiRec() { return spiTransfer(0xFF); } - - void spiRead(uint8_t*buf, uint16_t nbyte) { - for (int i = 0; i < nbyte; i++) - buf[i] = spiTransfer(0xFF); - } - - void spiSend(uint8_t b) { (void)spiTransfer(b); } - - void spiSend(const uint8_t *buf, size_t nbyte) { - for (uint16_t i = 0; i < nbyte; i++) - (void)spiTransfer(buf[i]); - } - - void spiSendBlock(uint8_t token, const uint8_t *buf) { - (void)spiTransfer(token); - for (uint16_t i = 0; i < 512; i++) - (void)spiTransfer(buf[i]); - } - -#else - - #ifdef SD_SPI_SPEED - #define INIT_SPI_SPEED SD_SPI_SPEED - #else - #define INIT_SPI_SPEED SPI_FULL_SPEED - #endif - - void spiBegin() {} // Set up SCK, MOSI & MISO pins for SSP0 - - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - if (spiRate == SPI_SPEED_DEFAULT) - spiRate = INIT_SPI_SPEED; - // We basically ignore all pins other than MISO because we assume that all - // belong to the same hardware SPI capable pin "module". - int used_miso_pin = ( hint_miso != -1 ) ? hint_miso : SD_MISO_PIN; -#ifdef BOARD_SPI1_MISO_PIN - if (used_miso_pin == BOARD_SPI1_MISO_PIN) - SPI.setModule(1); -#endif -#ifdef BOARD_SPI2_MISO_PIN - if (used_miso_pin == BOARD_SPI2_MISO_PIN) - SPI.setModule(2); -#endif - SPI.setDataSize(DATA_SIZE_8BIT); - SPI.setDataMode(SPI_MODE0); - - SPI.setClock(SPISettings::spiRate2Clock(spiRate)); - SPI.begin(); - } - - void spiClose() { SPI.end(); } - - static uint8_t doio(uint8_t b) { - return SPI.transfer(b & 0x00FF) & 0x00FF; - } - - void spiSend(uint8_t b) { doio(b); } - - void spiSend(const uint8_t *buf, size_t nbyte) { - for (uint16_t i = 0; i < nbyte; i++) doio(buf[i]); - } - - void spiSend(uint32_t chan, byte b) {} - - void spiSend(uint32_t chan, const uint8_t *buf, size_t nbyte) {} - - // Read single byte from SPI - uint8_t spiRec() { return doio(0xFF); } - - uint8_t spiRec(uint32_t chan) { return 0; } - - // Read from SPI into buffer - void spiRead(uint8_t *buf, uint16_t nbyte) { - for (uint16_t i = 0; i < nbyte; i++) buf[i] = doio(0xFF); - } - - uint8_t spiTransfer(uint8_t b) { return doio(b); } - - // Write from buffer to SPI - void spiSendBlock(uint8_t token, const uint8_t *buf) { - (void)spiTransfer(token); - for (uint16_t i = 0; i < 512; i++) - (void)spiTransfer(buf[i]); - } - - // Begin SPI transaction, set clock, bit order, data mode - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - // TODO: Implement this method - } - -#endif // LPC_SOFTWARE_SPI - -/** - * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. - */ -static inline void waitSpiTxEnd(LPC_SSP_TypeDef *spi_d) { - while (SSP_GetStatus(spi_d, SSP_STAT_TXFIFO_EMPTY) == RESET) { /* nada */ } // wait until TXE=1 - while (SSP_GetStatus(spi_d, SSP_STAT_BUSY) == SET) { /* nada */ } // wait until BSY=0 -} - -// Retain the pin init state of the SPI, to avoid init more than once, -// even if more instances of SPIClass exist -static bool spiInitialised[BOARD_NR_SPI] = { false }; - -SPIClass::SPIClass(uint8_t device) { - // Init things specific to each SPI device - // clock divider setup is a bit of hack, and needs to be improved at a later date. - - #if BOARD_NR_SPI >= 1 - _settings[0].spi_d = LPC_SSP0; - _settings[0].dataMode = SPI_MODE0; - _settings[0].dataSize = DATA_SIZE_8BIT; - _settings[0].clock = SPI_CLOCK_MAX; - //_settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); - #endif - - #if BOARD_NR_SPI >= 2 - _settings[1].spi_d = LPC_SSP1; - _settings[1].dataMode = SPI_MODE0; - _settings[1].dataSize = DATA_SIZE_8BIT; - _settings[1].clock = SPI_CLOCK_MAX; - //_settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); - #endif - - setModule(device); - - // Init the GPDMA controller - // TODO: call once in the constructor? or each time? - GPDMA_Init(); -} - -SPIClass::SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel) { - #if BOARD_NR_SPI >= 1 - if (mosi == BOARD_SPI1_MOSI_PIN) SPIClass(1); - #endif - #if BOARD_NR_SPI >= 2 - if (mosi == BOARD_SPI2_MOSI_PIN) SPIClass(2); - #endif -} - -void SPIClass::begin() { - // Init the SPI pins in the first begin call - if ((_currentSetting->spi_d == LPC_SSP0 && spiInitialised[0] == false) || - (_currentSetting->spi_d == LPC_SSP1 && spiInitialised[1] == false)) { - pin_t sck, miso, mosi; - if (_currentSetting->spi_d == LPC_SSP0) { - sck = BOARD_SPI1_SCK_PIN; - miso = BOARD_SPI1_MISO_PIN; - mosi = BOARD_SPI1_MOSI_PIN; - spiInitialised[0] = true; - } - else if (_currentSetting->spi_d == LPC_SSP1) { - sck = BOARD_SPI2_SCK_PIN; - miso = BOARD_SPI2_MISO_PIN; - mosi = BOARD_SPI2_MOSI_PIN; - spiInitialised[1] = true; - } - PINSEL_CFG_Type PinCfg; // data structure to hold init values - PinCfg.Funcnum = 2; - PinCfg.OpenDrain = 0; - PinCfg.Pinmode = 0; - PinCfg.Pinnum = LPC176x::pin_bit(sck); - PinCfg.Portnum = LPC176x::pin_port(sck); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(sck); - - PinCfg.Pinnum = LPC176x::pin_bit(miso); - PinCfg.Portnum = LPC176x::pin_port(miso); - PINSEL_ConfigPin(&PinCfg); - SET_INPUT(miso); - - PinCfg.Pinnum = LPC176x::pin_bit(mosi); - PinCfg.Portnum = LPC176x::pin_port(mosi); - PINSEL_ConfigPin(&PinCfg); - SET_OUTPUT(mosi); - } - - updateSettings(); - SSP_Cmd(_currentSetting->spi_d, ENABLE); // start SSP running -} - -void SPIClass::beginTransaction(const SPISettings &cfg) { - setBitOrder(cfg.bitOrder); - setDataMode(cfg.dataMode); - setDataSize(cfg.dataSize); - //setClockDivider(determine_baud_rate(_currentSetting->spi_d, settings.clock)); - begin(); -} - -uint8_t SPIClass::transfer(const uint16_t b) { - // Send and receive a single byte - SSP_ReceiveData(_currentSetting->spi_d); // read any previous data - SSP_SendData(_currentSetting->spi_d, b); - waitSpiTxEnd(_currentSetting->spi_d); // wait for it to finish - return SSP_ReceiveData(_currentSetting->spi_d); -} - -uint16_t SPIClass::transfer16(const uint16_t data) { - return (transfer((data >> 8) & 0xFF) << 8) | (transfer(data & 0xFF) & 0xFF); -} - -void SPIClass::end() { - // Neither is needed for Marlin - //SSP_Cmd(_currentSetting->spi_d, DISABLE); - //SSP_DeInit(_currentSetting->spi_d); -} - -void SPIClass::send(uint8_t data) { - SSP_SendData(_currentSetting->spi_d, data); -} - -void SPIClass::dmaSend(void *buf, uint16_t length, bool minc) { - //TODO: LPC dma can only write 0xFFF bytes at once. - GPDMA_Channel_CFG_Type GPDMACfg; - - /* Configure GPDMA channel 0 -------------------------------------------------------------*/ - /* DMA Channel 0 */ - GPDMACfg.ChannelNum = 0; - // Source memory - GPDMACfg.SrcMemAddr = (uint32_t)buf; - // Destination memory - Not used - GPDMACfg.DstMemAddr = 0; - // Transfer size - GPDMACfg.TransferSize = length; - // Transfer width - GPDMACfg.TransferWidth = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? GPDMA_WIDTH_HALFWORD : GPDMA_WIDTH_BYTE; - // Transfer type - GPDMACfg.TransferType = GPDMA_TRANSFERTYPE_M2P; - // Source connection - unused - GPDMACfg.SrcConn = 0; - // Destination connection - GPDMACfg.DstConn = (_currentSetting->spi_d == LPC_SSP0) ? GPDMA_CONN_SSP0_Tx : GPDMA_CONN_SSP1_Tx; - - GPDMACfg.DMALLI = 0; - - // Enable dma on SPI - SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, ENABLE); - - // Only increase memory if minc is true - GPDMACfg.MemoryIncrease = (minc ? GPDMA_DMACCxControl_SI : 0); - - // Setup channel with given parameter - GPDMA_Setup(&GPDMACfg); - - // Enable DMA - GPDMA_ChannelCmd(0, ENABLE); - - // Wait for data transfer - while (!GPDMA_IntGetStatus(GPDMA_STAT_RAWINTTC, 0) && !GPDMA_IntGetStatus(GPDMA_STAT_RAWINTERR, 0)) { } - - // Clear err and int - GPDMA_ClearIntPending (GPDMA_STATCLR_INTTC, 0); - GPDMA_ClearIntPending (GPDMA_STATCLR_INTERR, 0); - - // Disable DMA - GPDMA_ChannelCmd(0, DISABLE); - - waitSpiTxEnd(_currentSetting->spi_d); - - SSP_DMACmd(_currentSetting->spi_d, SSP_DMA_TX, DISABLE); -} - -uint16_t SPIClass::read() { - return SSP_ReceiveData(_currentSetting->spi_d); -} - -void SPIClass::read(uint8_t *buf, uint32_t len) { - for (uint16_t i = 0; i < len; i++) buf[i] = transfer(0xFF); -} - -void SPIClass::setClock(uint32_t clock) { _currentSetting->clock = clock; } - -void SPIClass::setModule(uint8_t device) { _currentSetting = &_settings[device - 1]; } // SPI channels are called 1, 2, and 3 but the array is zero-indexed - -void SPIClass::setBitOrder(uint8_t bitOrder) { _currentSetting->bitOrder = bitOrder; } - -void SPIClass::setDataMode(uint8_t dataMode) { _currentSetting->dataMode = dataMode; } - -void SPIClass::setDataSize(uint32_t dataSize) { _currentSetting->dataSize = dataSize; } - -/** - * Set up/tear down - */ -void SPIClass::updateSettings() { - //SSP_DeInit(_currentSetting->spi_d); //todo: need force de init?! - - // Divide PCLK by 2 for SSP0 - //CLKPWR_SetPCLKDiv(_currentSetting->spi_d == LPC_SSP0 ? CLKPWR_PCLKSEL_SSP0 : CLKPWR_PCLKSEL_SSP1, CLKPWR_PCLKSEL_CCLK_DIV_2); - - SSP_CFG_Type HW_SPI_init; // data structure to hold init values - SSP_ConfigStructInit(&HW_SPI_init); // set values for SPI mode - HW_SPI_init.ClockRate = _currentSetting->clock; - HW_SPI_init.Databit = _currentSetting->dataSize; - - /** - * SPI Mode CPOL CPHA Shift SCK-edge Capture SCK-edge - * 0 0 0 Falling Rising - * 1 0 1 Rising Falling - * 2 1 0 Rising Falling - * 3 1 1 Falling Rising - */ - switch (_currentSetting->dataMode) { - case SPI_MODE0: - HW_SPI_init.CPHA = SSP_CPHA_FIRST; - HW_SPI_init.CPOL = SSP_CPOL_HI; - break; - case SPI_MODE1: - HW_SPI_init.CPHA = SSP_CPHA_SECOND; - HW_SPI_init.CPOL = SSP_CPOL_HI; - break; - case SPI_MODE2: - HW_SPI_init.CPHA = SSP_CPHA_FIRST; - HW_SPI_init.CPOL = SSP_CPOL_LO; - break; - case SPI_MODE3: - HW_SPI_init.CPHA = SSP_CPHA_SECOND; - HW_SPI_init.CPOL = SSP_CPOL_LO; - break; - default: - break; - } - - // TODO: handle bitOrder - SSP_Init(_currentSetting->spi_d, &HW_SPI_init); // puts the values into the proper bits in the SSP0 registers -} - -#if SD_MISO_PIN == BOARD_SPI1_MISO_PIN - SPIClass SPI(1); -#elif SD_MISO_PIN == BOARD_SPI2_MISO_PIN - SPIClass SPI(2); -#endif - -#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp new file mode 100644 index 000000000000..25e2b266ad3a --- /dev/null +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -0,0 +1,2569 @@ +/** + * 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 . + * + */ + +// TODO: test the DMA with an actually working LPC1768 board because the one I got was faulty... +//#define HALSPI_DISABLE_DMA + +/** + * For TARGET_LPC1768 + */ + +/** + * Hardware SPI and Software SPI implementations are included in this file. + * + * Control of the slave select pin(s) is handled by the calling routines. + * + * Some of the LCD interfaces/adapters result in the LCD SPI and the SD card + * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with + * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is + * active. If any of these pins are shared then the software SPI must be used. + */ + +/* + HAL SPI implementation by Martin Turski, company owner of EirDev + Inclusion date: 24th of November, 2022 + Contact mail: turningtides@outlook.de + --- + + Contact Martin if there is any grave SPI design or functionality issue. + Include a link to the Marlin FW GitHub issue post. Otherwise the mail + may be ignored. This implementation has been created specifically for the + Marlin FW. It was made with performance and simplicity-of-maintenance in + mind, while keeping all the SPI requirements in check. + + Original pull request: https://github.com/MarlinFirmware/Marlin/pull/24911 +*/ + +// Actually: LPC176x/LPC175x +#ifdef TARGET_LPC1768 + +#include "../../inc/MarlinConfig.h" + +#include "../shared/HAL_SPI.h" +#include "../shared/ARM/HAL_NVIC.h" + +#if !ENABLED(SOFTWARE_SPI) + +#ifndef LPC_MAINOSCILLATOR_FREQ +#error Missing LPC176X/LPC175X main oscillator frequency! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) +#endif + +static void _spi_on_error(uint32_t code = 0) { + for (;;) { +#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (code > 0) + delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(250); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code-1) + delay(250); + } + if (code > 0) + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } +} + +static void _spi_infobeep(uint32_t code) { +#if PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (code > 0) + delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code-1) + delay(200); + } + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif +} + +template +inline numberType __MIN(numberType a, numberType b) { + return ( a < b ? a : b ); +} + +namespace MarlinLPC { + +// NXP UM10360 date: 20th of November, 2022 + +// There are pins for each "port" on the LPC1768. Do not be confused with other architectures +// where there is GPIO_0 .. GPIO_n linearly numbered. The naming convention on the LPC1768 is +// very unique. + +struct pinsel0_reg_t { + uint32_t p0_00 : 2; + uint32_t p0_01 : 2; + uint32_t p0_02 : 2; + uint32_t p0_03 : 2; + uint32_t p0_04 : 2; + uint32_t p0_05 : 2; + uint32_t p0_06 : 2; + uint32_t p0_07 : 2; + uint32_t p0_08 : 2; + uint32_t p0_09 : 2; + uint32_t p0_10 : 2; + uint32_t p0_11 : 2; + uint32_t reserved1 : 6; + uint32_t p0_15 : 2; +}; +static_assert(sizeof(pinsel0_reg_t) == 4, "invalid size of LPC pinsel0_reg_t"); + +struct pinsel1_reg_t { + uint32_t p0_16 : 2; + uint32_t p0_17 : 2; + uint32_t p0_18 : 2; + uint32_t p0_19 : 2; + uint32_t p0_20 : 2; + uint32_t p0_21 : 2; + uint32_t p0_22 : 2; + uint32_t p0_23 : 2; + uint32_t p0_24 : 2; + uint32_t p0_25 : 2; + uint32_t p0_26 : 2; + uint32_t p0_27 : 2; + uint32_t p0_28 : 2; + uint32_t p0_29 : 2; + uint32_t p0_30 : 2; + uint32_t reserved1 : 2; +}; +static_assert(sizeof(pinsel1_reg_t) == 4, "invalid size of LPC pinsel1_reg_t"); + +struct pinsel2_reg_t { + uint32_t p1_00 : 2; + uint32_t p1_01 : 2; + uint32_t reserved1 : 4; + uint32_t p1_04 : 2; + uint32_t reserved2 : 6; + uint32_t p1_08 : 2; + uint32_t p1_09 : 2; + uint32_t p1_10 : 2; + uint32_t reserved3 : 6; + uint32_t p1_14 : 2; + uint32_t p1_15 : 2; +}; +static_assert(sizeof(pinsel2_reg_t) == 4, "invalid size of LPC pinsel2_reg_t"); + +struct pinsel3_reg_t { + uint32_t p1_16 : 2; + uint32_t p1_17 : 2; + uint32_t p1_18 : 2; + uint32_t p1_19 : 2; + uint32_t p1_20 : 2; + uint32_t p1_21 : 2; + uint32_t p1_22 : 2; + uint32_t p1_23 : 2; + uint32_t p1_24 : 2; + uint32_t p1_25 : 2; + uint32_t p1_26 : 2; + uint32_t p1_27 : 2; + uint32_t p1_28 : 2; + uint32_t p1_29 : 2; + uint32_t p1_30 : 2; + uint32_t p1_31 : 2; +}; +static_assert(sizeof(pinsel3_reg_t) == 4, "invalid size of LPC pinsel3_reg_t"); + +struct pinsel4_reg_t { + uint32_t p2_00 : 2; + uint32_t p2_01 : 2; + uint32_t p2_02 : 2; + uint32_t p2_03 : 2; + uint32_t p2_04 : 2; + uint32_t p2_05 : 2; + uint32_t p2_06 : 2; + uint32_t p2_07 : 2; + uint32_t p2_08 : 2; + uint32_t p2_09 : 2; + uint32_t p2_10 : 2; + uint32_t p2_11 : 2; + uint32_t p2_12 : 2; + uint32_t p2_13 : 2; + uint32_t p2_14 : 2; + uint32_t p2_15 : 2; +}; +static_assert(sizeof(pinsel4_reg_t) == 4, "invalid size of LPC pinsel4_reg_t"); + +struct pinsel7_reg_t { + uint32_t reserved1 : 18; + uint32_t p3_25 : 2; + uint32_t p3_26 : 2; + uint32_t reserved2 : 10; +}; +static_assert(sizeof(pinsel7_reg_t) == 4, "invalid size of LPC pinsel7_reg_t"); + +struct pinsel9_reg_t { + uint32_t reserved1 : 24; + uint32_t p4_28 : 2; + uint32_t p4_29 : 2; + uint32_t reserved2 : 4; +}; +static_assert(sizeof(pinsel9_reg_t) == 4, "invalid size of LPC pinsel9_reg_t"); + +struct pinsel10_reg_t { + uint32_t reserved1 : 2; + uint32_t gpio_trace : 1; + uint32_t reserved2 : 29; +}; +static_assert(sizeof(pinsel10_reg_t) == 4, "invalid size of LPC pinsel10_reg_t"); + +#define LPC_PINMODE_PULLUP 0 +#define LPC_PINMODE_REPEATER 1 +#define LPC_PINMODE_NONE 2 +#define LPC_PINMODE_PULLDOWN 3 + +struct pinmode0_reg_t { + uint32_t p0_00mode : 2; + uint32_t p0_01mode : 2; + uint32_t p0_02mode : 2; + uint32_t p0_03mode : 2; + uint32_t p0_04mode : 2; + uint32_t p0_05mode : 2; + uint32_t p0_06mode : 2; + uint32_t p0_07mode : 2; + uint32_t p0_08mode : 2; + uint32_t p0_09mode : 2; + uint32_t p0_10mode : 2; + uint32_t p0_11mode : 2; + uint32_t reserved1 : 6; + uint32_t p0_15mode : 2; +}; +static_assert(sizeof(pinmode0_reg_t) == 4, "invalid size of LPC pinmode0_reg_t"); + +struct pinmode1_reg_t { + uint32_t p0_16mode : 2; + uint32_t p0_17mode : 2; + uint32_t p0_18mode : 2; + uint32_t p0_19mode : 2; + uint32_t p0_20mode : 2; + uint32_t p0_21mode : 2; + uint32_t p0_22mode : 2; + uint32_t p0_23mode : 2; + uint32_t p0_24mode : 2; + uint32_t p0_25mode : 2; + uint32_t p0_26mode : 2; + uint32_t reserved1 : 10; +}; +static_assert(sizeof(pinmode1_reg_t) == 4, "invalid size of pinmode1_reg_t"); + +struct pinmode2_reg_t { + uint32_t p1_00mode : 2; + uint32_t p1_01mode : 2; + uint32_t reserved1 : 4; + uint32_t p1_04mode : 2; + uint32_t reserved2 : 6; + uint32_t p1_08mode : 2; + uint32_t p1_09mode : 2; + uint32_t p1_10mode : 2; + uint32_t reserved3 : 6; + uint32_t p1_14mode : 2; + uint32_t p1_15mode : 2; +}; +static_assert(sizeof(pinmode2_reg_t) == 4, "invalid size of pinmode2_reg_t"); + +struct pinmode3_reg_t { + uint32_t p1_16mode : 2; + uint32_t p1_17mode : 2; + uint32_t p1_18mode : 2; + uint32_t p1_19mode : 2; + uint32_t p1_20mode : 2; + uint32_t p1_21mode : 2; + uint32_t p1_22mode : 2; + uint32_t p1_23mode : 2; + uint32_t p1_24mode : 2; + uint32_t p1_25mode : 2; + uint32_t p1_26mode : 2; + uint32_t p1_27mode : 2; + uint32_t p1_28mode : 2; + uint32_t p1_29mode : 2; + uint32_t p1_30mode : 2; + uint32_t p1_31mode : 2; +}; +static_assert(sizeof(pinmode3_reg_t) == 4, "invalid size of pinmode3_reg_t"); + +struct pinmode4_reg_t { + uint32_t p2_00mode : 2; + uint32_t p2_01mode : 2; + uint32_t p2_02mode : 2; + uint32_t p2_03mode : 2; + uint32_t p2_04mode : 2; + uint32_t p2_05mode : 2; + uint32_t p2_06mode : 2; + uint32_t p2_07mode : 2; + uint32_t p2_08mode : 2; + uint32_t p2_09mode : 2; + uint32_t p2_10mode : 2; + uint32_t p2_11mode : 2; + uint32_t p2_12mode : 2; + uint32_t p2_13mode : 2; + uint32_t reserved1 : 4; +}; +static_assert(sizeof(pinmode4_reg_t) == 4, "invalid size of pinmode4_reg_t"); + +struct pinmode7_reg_t { + uint32_t reserved1 : 18; + uint32_t p3_25mode : 2; + uint32_t p3_26mode : 2; + uint32_t reserved2 : 10; +}; +static_assert(sizeof(pinmode7_reg_t) == 4, "invalid size of pinmode7_reg_t"); + +struct pinmode9_reg_t { + uint32_t reserved1 : 24; + uint32_t p4_28mode : 2; + uint32_t p4_29mode : 2; + uint32_t reserved2 : 4; +}; +static_assert(sizeof(pinmode9_reg_t) == 4, "invalid size of pinmode9_reg_t"); + +static pinsel0_reg_t& PINSEL0 = *(pinsel0_reg_t*)0x4002C000; +static pinsel1_reg_t& PINSEL1 = *(pinsel1_reg_t*)0x4002C004; +static pinsel2_reg_t& PINSEL2 = *(pinsel2_reg_t*)0x4002C008; +static pinsel3_reg_t& PINSEL3 = *(pinsel3_reg_t*)0x4002C00C; +static pinsel4_reg_t& PINSEL4 = *(pinsel4_reg_t*)0x4002C010; +static pinsel7_reg_t& PINSEL7 = *(pinsel7_reg_t*)0x4002C01C; +//static pinsel8_reg_t& PINSEL8 = *(pinsel8_reg_t*)0x4002C020; +static pinsel9_reg_t& PINSEL9 = *(pinsel9_reg_t*)0x4002C024; +static pinsel10_reg_t& PINSEL10 = *(pinsel10_reg_t*)0x4002C028; + +static pinmode0_reg_t& PINMODE0 = *(pinmode0_reg_t*)0x4002C040; +static pinmode1_reg_t& PINMODE1 = *(pinmode1_reg_t*)0x4002C044; +static pinmode2_reg_t& PINMODE2 = *(pinmode2_reg_t*)0x4002C048; +static pinmode3_reg_t& PINMODE3 = *(pinmode3_reg_t*)0x4002C04C; +static pinmode4_reg_t& PINMODE4 = *(pinmode4_reg_t*)0x4002C050; +//static pinmode5_reg_t& PINMODE5 = *(pinmode5_reg_t*)0x4002C054; +//static pinmode6_reg_t& PINMODE6 = *(pinmode6_reg_t*)0x4002C058; +static pinmode7_reg_t& PINMODE7 = *(pinmode7_reg_t*)0x4002C05C; +static pinmode9_reg_t& PINMODE9 = *(pinmode9_reg_t*)0x4002C064; + +// Left out OD and I2C-specific. +// UM10360 page 103: I am only taking the pin descriptions for LPC176x +// but support could (easily) be enabled for LPC175x aswell, if the community demands it. + +#if 0 + +#define LPC_GPIODIR_INPUT 0 +#define LPC_GPIODIR_OUTPUT 1 + +struct fioXdir_reg_t { + uint32_t val; + + inline void set(uint8_t reg, uint8_t val) { + if (val == LPC_GPIODIR_INPUT) + val &= ~(1<> reg ); + } +}; + +struct fioXpin_reg_t { + uint32_t val; + + inline void set(uint8_t reg, bool high) { + if (high) + val |= (1<> reg ); + } +}; + +static fioXdir_reg_t& FIO0DIR = *(fioXdir_reg_t*)0x2009C000; +static fioXdir_reg_t& FIO1DIR = *(fioXdir_reg_t*)0x2009C020; +static fioXdir_reg_t& FIO2DIR = *(fioXdir_reg_t*)0x2009C040; +static fioXdir_reg_t& FIO3DIR = *(fioXdir_reg_t*)0x2009C060; +static fioXdir_reg_t& FIO4DIR = *(fioXdir_reg_t*)0x2009C080; + +static fioXmask_reg_t& FIO0MASK = *(fioXmask_reg_t*)0x2009C010; +static fioXmask_reg_t& FIO1MASK = *(fioXmask_reg_t*)0x2009C030; +static fioXmask_reg_t& FIO2MASK = *(fioXmask_reg_t*)0x2009C050; +static fioXmask_reg_t& FIO3MASK = *(fioXmask_reg_t*)0x2009C070; +static fioXmask_reg_t& FIO4MASK = *(fioXmask_reg_t*)0x2009C090; + +static fioXpin_reg_t& FIO0PIN = *(fioXpin_reg_t*)0x2009C014; +static fioXpin_reg_t& FIO1PIN = *(fioXpin_reg_t*)0x2009C034; +static fioXpin_reg_t& FIO2PIN = *(fioXpin_reg_t*)0x2009C054; +static fioXpin_reg_t& FIO3PIN = *(fioXpin_reg_t*)0x2009C074; +static fioXpin_reg_t& FIO4PIN = *(fioXpin_reg_t*)0x2009C094; + +#endif + +// Find a valid port-mapping for the given GPIO to a SPI bus peripheral. +// If it fails then a recommended SPI bus with a recommended set of GPIO +// pins should be used. +// The LPC1768 is a really good architecture, even though in comparison +// to the ESP32 it does not support mapping any peripheral signal to any +// GPIO pin. +struct portMapResult_t { + inline portMapResult_t() { + func = 0xFF; + } + inline bool isMapped() const { + return ( func != 0xFF ); + } + uint8_t func; +}; + +static bool SPIFindPortMapping( + int gpio_sck, int gpio_miso, int gpio_mosi, int gpio_cs, + uint8_t& sspBusOut, portMapResult_t& map_sck_out, portMapResult_t& map_miso_out, portMapResult_t& map_mosi_out, portMapResult_t& map_cs_out +) +{ + portMapResult_t map_sck, map_miso, map_mosi, map_cs; + bool found = false; + + if ((gpio_sck == P0_15 || gpio_sck == P1_20) || (gpio_miso == P0_17 || gpio_miso == P1_23) || (gpio_mosi == P0_18 || gpio_mosi == P1_24) || (gpio_cs == P0_16 || gpio_cs == P1_21)) { + sspBusOut = 0; + if (gpio_sck == P0_15) { + map_sck.func = 2; + } + else if (gpio_sck == P1_20) { + map_sck.func = 3; + } + if (gpio_miso == P0_17) { + map_miso.func = 2; + } + else if (gpio_miso == P1_23) { + map_miso.func = 3; + } + if (gpio_mosi == P0_18) { + map_mosi.func = 2; + } + else if (gpio_mosi == P1_24) { + map_mosi.func = 3; + } + if (gpio_cs == P0_16) { + map_cs.func = 2; + } + else if (gpio_cs == P1_21) { + map_cs.func = 3; + } + found = true; + } + else if ((gpio_sck == P0_07 || gpio_sck == P1_31) || gpio_miso == P0_08 || gpio_mosi == P0_09 || gpio_cs == P0_06) { + sspBusOut = 1; + if (gpio_sck == P0_07) { + map_sck.func = 2; + } + else if (gpio_sck == P1_31) { + map_sck.func = 2; + } + if (gpio_miso == P0_08) { + map_miso.func = 2; + } + if (gpio_mosi == P0_09) { + map_mosi.func = 2; + } + if (gpio_cs == P0_06) { + map_cs.func = 2; + } + found = true; + } + if (found) { + map_sck_out = map_sck; + map_miso_out = map_miso; + map_mosi_out = map_mosi; + map_cs_out = map_cs; + } + return found; +} + +struct gpioMapResult_t { + uint8_t sspBusIdx; + int gpio_sck; + int gpio_miso; + int gpio_mosi; + int gpio_cs; +}; + +static void MapPortPinFunc(int pin, uint8_t func) { +#define _SWENT_MPPF(PS,PT,PN) case P##PT##_##PN: PINSEL##PS.p##PT##_##PN = func; break; + switch(pin) { + _SWENT_MPPF(0,0,00)_SWENT_MPPF(0,0,01)_SWENT_MPPF(0,0,02)_SWENT_MPPF(0,0,03)_SWENT_MPPF(0,0,04)_SWENT_MPPF(0,0,05)_SWENT_MPPF(0,0,06)_SWENT_MPPF(0,0,07) + _SWENT_MPPF(0,0,08)_SWENT_MPPF(0,0,09)_SWENT_MPPF(0,0,10)_SWENT_MPPF(0,0,11)_SWENT_MPPF(0,0,15) + _SWENT_MPPF(1,0,16)_SWENT_MPPF(1,0,17)_SWENT_MPPF(1,0,18)_SWENT_MPPF(1,0,19)_SWENT_MPPF(1,0,20) + _SWENT_MPPF(1,0,21)_SWENT_MPPF(1,0,22)_SWENT_MPPF(1,0,23)_SWENT_MPPF(1,0,24)_SWENT_MPPF(1,0,25) + _SWENT_MPPF(1,0,26)_SWENT_MPPF(1,0,27)_SWENT_MPPF(1,0,28)_SWENT_MPPF(1,0,29)_SWENT_MPPF(1,0,30) + _SWENT_MPPF(2,1,00)_SWENT_MPPF(2,1,01)_SWENT_MPPF(2,1,04)_SWENT_MPPF(2,1,08)_SWENT_MPPF(2,1,09)_SWENT_MPPF(2,1,10) + _SWENT_MPPF(2,1,14)_SWENT_MPPF(2,1,15) + _SWENT_MPPF(3,1,16)_SWENT_MPPF(3,1,17)_SWENT_MPPF(3,1,18)_SWENT_MPPF(3,1,19)_SWENT_MPPF(3,1,20) + _SWENT_MPPF(3,1,21)_SWENT_MPPF(3,1,22)_SWENT_MPPF(3,1,23)_SWENT_MPPF(3,1,24)_SWENT_MPPF(3,1,25) + _SWENT_MPPF(3,1,26)_SWENT_MPPF(3,1,27)_SWENT_MPPF(3,1,28)_SWENT_MPPF(3,1,29)_SWENT_MPPF(3,1,30) + _SWENT_MPPF(3,1,31) + _SWENT_MPPF(4,2,00)_SWENT_MPPF(4,2,01)_SWENT_MPPF(4,2,02)_SWENT_MPPF(4,2,03)_SWENT_MPPF(4,2,04) + _SWENT_MPPF(4,2,05)_SWENT_MPPF(4,2,06)_SWENT_MPPF(4,2,07)_SWENT_MPPF(4,2,08)_SWENT_MPPF(4,2,09) + _SWENT_MPPF(4,2,10)_SWENT_MPPF(4,2,11)_SWENT_MPPF(4,2,12)_SWENT_MPPF(4,2,13) + _SWENT_MPPF(7,3,25)_SWENT_MPPF(7,3,26) + _SWENT_MPPF(9,4,28)_SWENT_MPPF(9,4,29) + } +#undef _SWENT_MPPF +} + +static void SetPortPinMode(int pin, uint8_t mode) { +#define _SWENT_MPPM(PM,PT,PN) case P##PT##_##PN: PINMODE##PM.p##PT##_##PN##mode = mode; break; + switch(pin) { + _SWENT_MPPM(0,0,00)_SWENT_MPPM(0,0,01)_SWENT_MPPM(0,0,02)_SWENT_MPPM(0,0,03)_SWENT_MPPM(0,0,04)_SWENT_MPPM(0,0,05) + _SWENT_MPPM(0,0,06)_SWENT_MPPM(0,0,07)_SWENT_MPPM(0,0,08)_SWENT_MPPM(0,0,09)_SWENT_MPPM(0,0,10)_SWENT_MPPM(0,0,11) + _SWENT_MPPM(0,0,15) + _SWENT_MPPM(1,0,16)_SWENT_MPPM(1,0,17)_SWENT_MPPM(1,0,18)_SWENT_MPPM(1,0,19)_SWENT_MPPM(1,0,20)_SWENT_MPPM(1,0,21) + _SWENT_MPPM(1,0,22)_SWENT_MPPM(1,0,23)_SWENT_MPPM(1,0,24)_SWENT_MPPM(1,0,25)_SWENT_MPPM(1,0,26) + _SWENT_MPPM(2,1,00)_SWENT_MPPM(2,1,01)_SWENT_MPPM(2,1,04)_SWENT_MPPM(2,1,08)_SWENT_MPPM(2,1,09)_SWENT_MPPM(2,1,10) + _SWENT_MPPM(2,1,14)_SWENT_MPPM(2,1,15) + _SWENT_MPPM(3,1,16)_SWENT_MPPM(3,1,17)_SWENT_MPPM(3,1,18)_SWENT_MPPM(3,1,19)_SWENT_MPPM(3,1,20)_SWENT_MPPM(3,1,21) + _SWENT_MPPM(3,1,22)_SWENT_MPPM(3,1,23)_SWENT_MPPM(3,1,24)_SWENT_MPPM(3,1,25)_SWENT_MPPM(3,1,26)_SWENT_MPPM(3,1,27) + _SWENT_MPPM(3,1,28)_SWENT_MPPM(3,1,29)_SWENT_MPPM(3,1,30)_SWENT_MPPM(3,1,31) + _SWENT_MPPM(4,2,00)_SWENT_MPPM(4,2,01)_SWENT_MPPM(4,2,02)_SWENT_MPPM(4,2,03)_SWENT_MPPM(4,2,04)_SWENT_MPPM(4,2,05) + _SWENT_MPPM(4,2,06)_SWENT_MPPM(4,2,07)_SWENT_MPPM(4,2,08)_SWENT_MPPM(4,2,09)_SWENT_MPPM(4,2,10)_SWENT_MPPM(4,2,11) + _SWENT_MPPM(4,2,12)_SWENT_MPPM(4,2,13) + _SWENT_MPPM(7,3,25)_SWENT_MPPM(7,3,26) + _SWENT_MPPM(9,4,28)_SWENT_MPPM(9,4,29) + } +#undef _SWENT_MPPM +} + +#if 0 +static void SetPortPinDirection(int pin, uint8_t dir) { +#define _SWENT_SPPD_(PT,PNN,PN) case P##PT##_##PNN: FIO##PT##DIR.set(PN, dir); break; +#define _SWENT_SPPD(PT,PN) case P##PT##_##PN: FIO##PT##DIR.set(PN, dir); break; + switch(pin) { + _SWENT_SPPD_(0,00,0)_SWENT_SPPD_(0,01,1)_SWENT_SPPD_(0,02,2)_SWENT_SPPD_(0,03,3)_SWENT_SPPD_(0,04,4)_SWENT_SPPD_(0,05,5)_SWENT_SPPD_(0,06,6) + _SWENT_SPPD_(0,07,7)_SWENT_SPPD_(0,08,8)_SWENT_SPPD_(0,09,9)_SWENT_SPPD(0,10)_SWENT_SPPD(0,11)_SWENT_SPPD(0,15)_SWENT_SPPD(0,16) + _SWENT_SPPD(0,17)_SWENT_SPPD(0,18)_SWENT_SPPD(0,19)_SWENT_SPPD(0,20)_SWENT_SPPD(0,21)_SWENT_SPPD(0,22)_SWENT_SPPD(0,23) + _SWENT_SPPD(0,24)_SWENT_SPPD(0,25)_SWENT_SPPD(0,26)_SWENT_SPPD(0,27)_SWENT_SPPD(0,28)_SWENT_SPPD(0,29)_SWENT_SPPD(0,30) + _SWENT_SPPD_(1,00,0)_SWENT_SPPD_(1,01,1)_SWENT_SPPD_(1,04,4)_SWENT_SPPD_(1,08,8)_SWENT_SPPD_(1,09,9)_SWENT_SPPD(1,10)_SWENT_SPPD(1,14) + _SWENT_SPPD(1,15)_SWENT_SPPD(1,16)_SWENT_SPPD(1,17)_SWENT_SPPD(1,18)_SWENT_SPPD(1,19)_SWENT_SPPD(1,20)_SWENT_SPPD(1,21) + _SWENT_SPPD(1,22)_SWENT_SPPD(1,23)_SWENT_SPPD(1,24)_SWENT_SPPD(1,25)_SWENT_SPPD(1,26)_SWENT_SPPD(1,27)_SWENT_SPPD(1,28) + _SWENT_SPPD(1,29)_SWENT_SPPD(1,30)_SWENT_SPPD(1,31) + _SWENT_SPPD_(2,00,0)_SWENT_SPPD_(2,01,1)_SWENT_SPPD_(2,02,2)_SWENT_SPPD_(2,03,3)_SWENT_SPPD_(2,04,4)_SWENT_SPPD_(2,05,5)_SWENT_SPPD_(2,06,6)_SWENT_SPPD_(2,07,7) + _SWENT_SPPD_(2,08,8)_SWENT_SPPD_(2,09,9)_SWENT_SPPD(2,10)_SWENT_SPPD(2,11)_SWENT_SPPD(2,12)_SWENT_SPPD(2,13) + _SWENT_SPPD(3,25)_SWENT_SPPD(3,26) + _SWENT_SPPD(4,28)_SWENT_SPPD(4,29) + } +#undef _SWENT_SPPD +#undef _SWENT_SPPD_ +} +#endif + +static gpioMapResult_t SPIMapGPIO(int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // First try to find a direct mapping to SSP peripheral based on the given pin hints. + uint8_t sspBusIdx; + portMapResult_t map_sck, map_miso, map_mosi, map_cs; + + bool foundPortMap = SPIFindPortMapping(hint_sck, hint_miso, hint_mosi, hint_cs, sspBusIdx, map_sck, map_miso, map_mosi, map_cs); + + if (foundPortMap == false) { + // Just select the default SSP config. + sspBusIdx = 0; + hint_sck = P0_15; + map_sck.func = 2; + hint_miso = P0_17; + map_miso.func = 2; + hint_mosi = P0_18; + map_mosi.func = 2; + hint_cs = P0_16; + map_cs.func = 2; + } + + // Map the functions that exist. + if (map_sck.isMapped()) { + MapPortPinFunc(hint_sck, map_sck.func); + SetPortPinMode(hint_sck, LPC_PINMODE_NONE); + } + if (map_miso.isMapped()) { + MapPortPinFunc(hint_miso, map_miso.func); + SetPortPinMode(hint_miso, LPC_PINMODE_PULLDOWN); + } + if (map_mosi.isMapped()) { + MapPortPinFunc(hint_mosi, map_mosi.func); + SetPortPinMode(hint_mosi, LPC_PINMODE_NONE); + } +#if 0 + if (map_cs.isMapped()) { + MapPortPinFunc(hint_cs, map_cs.func); + SetPortPinMode(hint_cs, LPC_PINMODE_NONE); + } +#endif + + gpioMapResult_t res; + res.sspBusIdx = sspBusIdx; + res.gpio_sck = ( map_sck.isMapped() ? hint_sck : -1 ); + res.gpio_miso = ( map_miso.isMapped() ? hint_miso : -1 ); + res.gpio_mosi = ( map_mosi.isMapped() ? hint_mosi : -1 ); + res.gpio_cs = ( map_cs.isMapped() ? hint_cs : -1 ); + return res; +} + +static void SPIUnmapGPIO(const gpioMapResult_t& res) { + // Reset to architecture default configs on the pins that we previously mapped. + if (res.gpio_sck >= 0) { + MapPortPinFunc(res.gpio_sck, 0); + SetPortPinMode(res.gpio_sck, LPC_PINMODE_PULLDOWN); + } + if (res.gpio_miso >= 0) { + MapPortPinFunc(res.gpio_miso, 0); + SetPortPinMode(res.gpio_miso, LPC_PINMODE_PULLDOWN); + } + if (res.gpio_mosi >= 0) { + MapPortPinFunc(res.gpio_mosi, 0); + SetPortPinMode(res.gpio_mosi, LPC_PINMODE_PULLDOWN); + } +#if 0 + if (res.gpio_cs >= 0) { + MapPortPinFunc(res.gpio_cs, 0); + SetPortPinMode(res.gpio_cs, LPC_PINMODE_PULLDOWN); + } +#endif +} + +#define LPC_OSCRANGE_1_20_MHZ 0 +#define LPC_OSCRANGE_15_25_MHZ 1 + +struct scs_reg_t { + uint32_t reserved1 : 4; + uint32_t OSCRANGE : 1; + uint32_t OSCEN : 1; + uint32_t OSCSTAT : 1; + uint32_t reserved2 : 25; +}; +static_assert(sizeof(scs_reg_t) == 4, "invalid size of LPC scs_reg_t"); + +static scs_reg_t& SCS = *(scs_reg_t*)0x400FC1A0; + +#define LPC_CLKSRC_IRC 0 // 4MHz +#define LPC_CLKSRC_MAINOSC 1 // depending on OSCRANGE +#define LPC_CLKSRC_RTCOSC 2 // 32kHz + +struct clksrcsel_reg_t { + uint32_t CLKSRC : 2; + uint32_t reserved1 : 30; +}; +static_assert(sizeof(clksrcsel_reg_t) == 4, "invalid size of LPC clksrcsel_reg_t"); + +static clksrcsel_reg_t& CLKSRCSEL = *(clksrcsel_reg_t*)0x400FC10C; + +struct pll0stat_reg_t { + uint32_t MSEL0 : 15; // M - 1 + uint32_t reserved1 : 1; + uint32_t NSEL0 : 8; // N - 1 + uint32_t PLLE0_STAT : 1; // enable bit + uint32_t PLLC0_STAT : 1; // connect bit + uint32_t PLOCK0 : 1; // ready bit + uint32_t reserved2 : 5; +}; +static_assert(sizeof(pll0stat_reg_t) == 4, "invalid size of LPC pll0stat_reg_t"); + +static pll0stat_reg_t& PLL0STAT = *(pll0stat_reg_t*)0x400FC088; + +struct cclkcfg_reg_t { + uint32_t CCLKSEL : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(cclkcfg_reg_t) == 4, "invalid size of LPC cclkcfg_reg_t"); + +static cclkcfg_reg_t& CCLKCFG = *(cclkcfg_reg_t*)0x400FC104; + +#define LPC_PCLKSEL_QUARTER 0 +#define LPC_PCLKSEL_ONE 1 +#define LPC_PCLKSEL_HALF 2 +#define LPC_PCLKSEL_8_6 3 // 1/8 for generic, 1/6 for CAN1/2 + +struct pclksel0_reg_t { + uint32_t PCLK_WDT : 2; + uint32_t PCLK_TIMER0 : 2; + uint32_t PCLK_TIMER1 : 2; + uint32_t PCLK_UART0 : 2; + uint32_t PCLK_UART1 : 2; + uint32_t reserved1 : 2; + uint32_t PCLK_PWM1 : 2; + uint32_t PCLK_I2C0 : 2; + uint32_t PCLK_SPI : 2; + uint32_t reserved2 : 2; + uint32_t PCLK_SSP1 : 2; + uint32_t PCLK_DAC : 2; + uint32_t PCLK_ADC : 2; + uint32_t PCLK_CAN1 : 2; + uint32_t PCLK_CAN2 : 2; + uint32_t PCLK_ACF : 2; +}; +static_assert(sizeof(pclksel0_reg_t) == 4, "invalid size of LPC pclksel0_reg_t"); + +static pclksel0_reg_t& PCLKSEL0 = *(pclksel0_reg_t*)0x400FC1A8; + +struct pclksel1_reg_t { + uint32_t PCLK_QEI : 2; + uint32_t PCLK_GPIOINT : 2; + uint32_t PCLK_PCB : 2; + uint32_t PCLK_I2C1 : 2; + uint32_t reserved1 : 2; + uint32_t PCLK_SSP0 : 2; + uint32_t PCLK_TIMER2 : 2; + uint32_t PCLK_TIMER3 : 2; + uint32_t PCLK_UART2 : 2; + uint32_t PCLK_UART3 : 2; + uint32_t PCLK_I2C2 : 2; + uint32_t PCLK_I2S : 2; + uint32_t reserved2 : 2; + uint32_t PCLK_RIT : 2; + uint32_t PCLK_SYSCON : 2; + uint32_t PCLK_MC : 2; +}; +static_assert(sizeof(pclksel1_reg_t) == 4, "invalid size of LPC pclksel1_reg_t"); + +static pclksel1_reg_t& PCLKSEL1 = *(pclksel1_reg_t*)0x400FC1AC; + +// Enables or disables peripherals (power control for peripherals). +struct pconp_reg_t { + uint32_t reserved1 : 1; + uint32_t PCTIM0 : 1; + uint32_t PCTIM1 : 1; + uint32_t PCUART0 : 1; + uint32_t PCUART1 : 1; + uint32_t reserved2 : 1; + uint32_t PCPWM1 : 1; + uint32_t PCI2C0 : 1; + uint32_t PCSPI : 1; + uint32_t PCRTC : 1; + uint32_t PCSSP1 : 1; + uint32_t reserved3 : 1; + uint32_t PCADC : 1; + uint32_t PCCAN1 : 1; + uint32_t PCCAN2 : 1; + uint32_t PCGPIO : 1; + uint32_t PCRIT : 1; + uint32_t PCMCPWM : 1; + uint32_t PCQEI : 1; + uint32_t PCI2C1 : 1; + uint32_t reserved4 : 1; + uint32_t PCSSP0 : 1; + uint32_t PCTIM2 : 1; + uint32_t PCTIM3 : 1; + uint32_t PCUART2 : 1; + uint32_t PCUART3 : 1; + uint32_t PCI2C2 : 1; + uint32_t PC12S : 1; + uint32_t reserved5 : 1; + uint32_t PCGPDMA : 1; + uint32_t PCENET : 1; + uint32_t PCUSB : 1; +}; +static_assert(sizeof(pconp_reg_t) == 4, "invalid size of LPC pconp_reg_t"); + +static pconp_reg_t& PCONP = *(pconp_reg_t*)0x400FC0C4; + +static uint32_t GetCPUClockFrequency() { + if (PLL0STAT.PLLE0_STAT == false || PLL0STAT.PLLC0_STAT == false) { + // The CPU is running on the IRC. + return 4000000; + } + + uint32_t clksrc = 0; + + switch(CLKSRCSEL.CLKSRC) { + case LPC_CLKSRC_IRC: + clksrc = 4000000; + break; + case LPC_CLKSRC_MAINOSC: + clksrc = LPC_MAINOSCILLATOR_FREQ; + break; + case LPC_CLKSRC_RTCOSC: + clksrc = 32000; + break; + } + + uint32_t M = PLL0STAT.MSEL0 + 1; // M = 25 + uint32_t N = PLL0STAT.NSEL0 + 1; // N = 2 + + uint32_t f_cco = (2 * M * clksrc) / N; + + uint32_t cclkdiv = CCLKCFG.CCLKSEL + 1; + + return (f_cco / cclkdiv); +} + +struct sspClockResult_t { + uint32_t pclk_ssp : 2; + uint32_t scr : 8; + uint32_t cpsdvsr : 8; // value between 2 and 254 +}; + +static sspClockResult_t SPICalculateClock(uint32_t maxClockFreq) { + uint32_t cpuFreq = GetCPUClockFrequency(); + + if (maxClockFreq >= cpuFreq) { + // Return the fastest clock. + sspClockResult_t maxRes; + maxRes.pclk_ssp = LPC_PCLKSEL_ONE; + maxRes.scr = 0; + maxRes.cpsdvsr = 2; // minimum value. + return maxRes; + } + + uint32_t DIV_ceil = ((cpuFreq + (maxClockFreq - 1)) / maxClockFreq); + + if (/* DIV_ceil >= 1 && */ DIV_ceil <= 256) { + uint32_t rem_two = (DIV_ceil % 2); + + if (rem_two == 0 && DIV_ceil >= 2 && DIV_ceil <= 254) { + sspClockResult_t accRes; + accRes.pclk_ssp = LPC_PCLKSEL_ONE; + accRes.scr = 0; + accRes.cpsdvsr = DIV_ceil; + return accRes; + } + else { + // Return a very accurate SCR representation. + sspClockResult_t accRes; + accRes.pclk_ssp = LPC_PCLKSEL_ONE; + accRes.scr = (DIV_ceil+rem_two)/2 - 1; + accRes.cpsdvsr = 2; // minimum value. + return accRes; + } + } + + // Brute-force find the clock result. + // Still very fast, optimized using math. + sspClockResult_t best; + best.pclk_ssp = LPC_PCLKSEL_8_6; + best.scr = 255; + best.cpsdvsr = 254; + uint32_t last_best_clockfreq = 0; + bool has_result = false; + + uint32_t ps_ssp = 2; + + while (ps_ssp <= 8) { + uint32_t ps_dvsr = (1<<7)*ps_ssp; + + while (ps_dvsr <= (254u*ps_ssp)) { + uint32_t presc = (ps_dvsr*ps_ssp); + uint32_t scr = (DIV_ceil/presc); + uint32_t freq = (cpuFreq/(presc*scr)); + + if (freq <= maxClockFreq) { + if (has_result == false || last_best_clockfreq < freq) { + last_best_clockfreq = freq; + if (ps_ssp == 2) + best.pclk_ssp = LPC_PCLKSEL_HALF; + else if (ps_ssp == 4) + best.pclk_ssp = LPC_PCLKSEL_QUARTER; + else + best.pclk_ssp = LPC_PCLKSEL_8_6; + best.scr = (scr-1); + best.cpsdvsr = ps_dvsr; + has_result = true; + } + } + + ps_dvsr += ps_ssp*2; + } + + ps_ssp *= 2; + } + + return best; +} + +struct sspNcr0_reg_t { + uint32_t DSS : 4; + uint32_t FRF : 2; + uint32_t CPOL : 1; + uint32_t CPHA : 1; + uint32_t SCR : 8; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(sspNcr0_reg_t) == 4, "invalid size of LPC sspNcr0_reg_t"); + +struct sspNcr1_reg_t { + uint32_t LBM : 1; + uint32_t SSE : 1; + uint32_t MS : 1; + uint32_t SOD : 1; + uint32_t reserved1 : 28; +}; +static_assert(sizeof(sspNcr1_reg_t) == 4, "invalid size of LPC sspNcr1_reg_t"); + +struct sspNdr_reg_t { + uint32_t DATA : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(sspNdr_reg_t) == 4, "invalid size of LPC sspNdr_reg_t"); + +struct sspNsr_reg_t { + uint32_t TFE : 1; + uint32_t TNF : 1; + uint32_t RNE : 1; + uint32_t RFF : 1; + uint32_t BSY : 1; + uint32_t reserved1 : 27; +}; +static_assert(sizeof(sspNsr_reg_t) == 4, "invalid size of LPC sspNsr_reg_t"); + +struct sspNcpsr_reg_t { + uint32_t CPSDVSR : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(sspNcpsr_reg_t) == 4, "invalid size of LPC sspNcpsr_reg_t"); + +struct sspNimsc_reg_t { + uint32_t RORIM : 1; + uint32_t RTIM : 1; + uint32_t RXIM : 1; + uint32_t TXIM : 1; + uint32_t reserved1 : 28; +}; +static_assert(sizeof(sspNimsc_reg_t) == 4, "invalid size of LPC sspNimsc_reg_t"); + +struct sspNris_reg_t { + uint32_t RORRIS : 1; + uint32_t RTRIS : 1; + uint32_t RXRIS : 1; + uint32_t TXRIS : 1; + uint32_t reserved1 : 28; +}; +static_assert(sizeof(sspNris_reg_t) == 4, "invalid size of LPC sspNris_reg_t"); + +struct sspNmis_reg_t { + uint32_t RORMIS : 1; + uint32_t RTMIS : 1; + uint32_t RXMIS : 1; + uint32_t TXMIS : 1; + uint32_t reserved1 : 28; +}; +static_assert(sizeof(sspNmis_reg_t) == 4, "invalid size of LPC sspNmis_reg_t"); + +struct sspNicr_reg_t { + uint32_t RORIC : 1; + uint32_t RTIC : 1; + uint32_t reserved1 : 30; +}; +static_assert(sizeof(sspNicr_reg_t) == 4, "invalid size of LPC sspNicr_reg_t"); + +struct sspNdmacr_reg_t { + uint32_t RXDMAE : 1; + uint32_t TXDMAE : 1; + uint32_t reserved1 : 30; +}; +static_assert(sizeof(sspNdmacr_reg_t) == 4, "invalid size of LPC sspNdmacr_reg_t"); + +struct ssp_dev_t { + sspNcr0_reg_t CR0; + sspNcr1_reg_t CR1; + sspNdr_reg_t DR; + sspNsr_reg_t SR; + sspNcpsr_reg_t CPSR; + sspNimsc_reg_t IMSC; + sspNris_reg_t RIS; + sspNmis_reg_t MIS; + sspNicr_reg_t ICR; + sspNdmacr_reg_t DMACR; +}; +static_assert(sizeof(ssp_dev_t) == 40, "invalid size of LPC ssp_dev_t"); + +static volatile ssp_dev_t& SSP0 = *(volatile ssp_dev_t*)0x40088000; +static volatile ssp_dev_t& SSP1 = *(volatile ssp_dev_t*)0x40030000; + +inline volatile ssp_dev_t& SPIGetBusFromIndex(uint8_t idx) { + if (idx == 0) return SSP0; + if (idx == 1) return SSP1; + return SSP0; // default +} + +inline uint8_t SPIGetBusIndex(volatile ssp_dev_t& SSP) { + if (&SSP == &SSP0) return 0; + if (&SSP == &SSP1) return 1; + return 0; // default +} + +#ifndef HALSPI_DISABLE_DMA + +struct DMACIntStat_reg_t { + uint32_t IntStat : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACIntStat_reg_t) == 4, "invalid size of LPC DMACIntStat_reg_t"); + +static DMACIntStat_reg_t& DMACIntStat = *(DMACIntStat_reg_t*)0x50004000; + +struct DMACIntTCStat_reg_t { + uint32_t IntTCStat : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACIntTCStat_reg_t) == 4, "invalid size of LPC DMACIntTCStat_reg_t"); + +static DMACIntTCStat_reg_t& DMACIntTCStat = *(DMACIntTCStat_reg_t*)0x50004004; + +struct DMACIntTCClear_reg_t { + uint32_t IntTCClear : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACIntTCClear_reg_t) == 4, "invalid size of LPC DMAIntTCClear_reg_t"); + +static DMACIntTCClear_reg_t& DMACIntTCClear = *(DMACIntTCClear_reg_t*)0x50004008; + +struct DMACIntErrStat_reg_t { + uint32_t IntErrStat : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACIntErrStat_reg_t) == 4, "invalid size of LPC DMACIntErrStat_reg_t"); + +static DMACIntErrStat_reg_t& DMACIntErrStat = *(DMACIntErrStat_reg_t*)0x5000400C; + +struct DMACIntErrClr_reg_t { + uint32_t IntErrClr : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACIntErrClr_reg_t) == 4, "invalid size of LPC DMACIntErrClr_reg_t"); + +static DMACIntErrClr_reg_t& DMACIntErrClr = *(DMACIntErrClr_reg_t*)0x50004010; + +struct DMACRawIntTCStat_reg_t { + uint32_t RawIntTCStat : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACRawIntTCStat_reg_t) == 4, "invalid size of LPC DMACRawIntTCStat_reg_t"); + +static DMACRawIntTCStat_reg_t& DMACRawIntTCStat = *(DMACRawIntTCStat_reg_t*)0x50004014; + +struct DMACRawIntErrStat_reg_t { + uint32_t RawIntErrStat : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACRawIntErrStat_reg_t) == 4, "invalid size of LPC DMACRawIntErrStat_reg_t"); + +static DMACRawIntErrStat_reg_t& DMACRawIntErrStat = *(DMACRawIntErrStat_reg_t*)0x50004018; + +struct DMACEnbldChns_reg_t { + uint32_t EnabledChannels : 8; + uint32_t reserved1 : 24; +}; +static_assert(sizeof(DMACEnbldChns_reg_t) == 4, "invalid size of LPC DMACEnbldChns_reg_t"); + +static DMACEnbldChns_reg_t& DMACEnbldChns = *(DMACEnbldChns_reg_t*)0x5000401C; + +struct DMACSoftBReq_reg_t { + uint32_t SoftBReq : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(DMACSoftBReq_reg_t) == 4, "invalid size of LPC DMACSoftBReq_reg_t"); + +static DMACSoftBReq_reg_t& DMACSoftBReq = *(DMACSoftBReq_reg_t*)0x50004020; + +struct DMACSoftSReq_reg_t { + uint32_t SoftSReq : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(DMACSoftSReq_reg_t) == 4, "invalid size of LPC DMACSoftSReq_reg_t"); + +static DMACSoftSReq_reg_t& DMACSoftSReq = *(DMACSoftSReq_reg_t*)0x50004024; + +struct DMACSoftLBReq_reg_t { + uint32_t SoftLBReq : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(DMACSoftLBReq_reg_t) == 4, "invalid size of LPC DMACSoftLBReq_reg_t"); + +static DMACSoftLBReq_reg_t& DMACSoftLBReq = *(DMACSoftLBReq_reg_t*)0x50004028; + +struct DMACSoftLSReq_reg_t { + uint32_t SoftLSReq : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(DMACSoftLSReq_reg_t) == 4, "invalid size of LPC DMACSoftLSReq_reg_t"); + +static DMACSoftLSReq_reg_t& DMACSoftLSReq = *(DMACSoftLSReq_reg_t*)0x5000402C; + +struct DMACConfig_reg_t { + uint32_t E : 1; + uint32_t M : 1; + uint32_t reserved1 : 30; +}; +static_assert(sizeof(DMACConfig_reg_t) == 4, "invalid size of LPC DMACConfig_reg_t"); + +static DMACConfig_reg_t& DMACConfig = *(DMACConfig_reg_t*)0x50004030; + +struct DMACSync_reg_t { + uint32_t DMACSync : 16; + uint32_t reserved1 : 16; +}; +static_assert(sizeof(DMACSync_reg_t) == 4, "invalid size of LPC DMACSync_reg_t"); + +static DMACSync_reg_t& DMACSync = *(DMACSync_reg_t*)0x50004034; + +struct DMAReqSel_reg_t { + uint32_t DMASEL08 : 1; + uint32_t DMASEL09 : 1; + uint32_t DMASEL10 : 1; + uint32_t DMASEL11 : 1; + uint32_t DMASEL12 : 1; + uint32_t DMASEL13 : 1; + uint32_t DMASEL14 : 1; + uint32_t DMASEL15 : 1; + uint32_t reserved : 24; +}; +static_assert(sizeof(DMAReqSel_reg_t) == 4, "invalid size of LPC DMAReqSel_reg_t"); + +static DMAReqSel_reg_t& DMAReqSel = *(DMAReqSel_reg_t*)0x400FC1C4; + +struct DMACCxLLI_reg_t { + uint32_t reserved1 : 2; + uint32_t LLI : 30; +}; +static_assert(sizeof(DMACCxLLI_reg_t) == 4, "invalid size of LPC DMACCxLLI_reg_t"); + +struct DMACCxControl_reg_t { + uint32_t TransferSize : 12; + uint32_t SBSize : 3; + uint32_t DBSize : 3; + uint32_t SWidth : 3; + uint32_t DWidth : 3; + uint32_t reserved1 : 2; + uint32_t SI : 1; + uint32_t DI : 1; + uint32_t Prot1 : 1; + uint32_t Prot2 : 1; + uint32_t Prot3 : 1; + uint32_t I : 1; +}; +static_assert(sizeof(DMACCxControl_reg_t) == 4, "invalid size of LPC DMACCxControl_reg_t"); + +struct DMACCxConfig_reg_t { + uint32_t E : 1; + uint32_t SrcPeripheral : 5; + uint32_t DestPeripheral : 5; + uint32_t TransferType : 3; + uint32_t IE : 1; + uint32_t ITC : 1; + uint32_t L : 1; + uint32_t A : 1; + uint32_t H : 1; + uint32_t reserved1 : 13; +}; +static_assert(sizeof(DMACCxConfig_reg_t) == 4, "invalid size of LPC DMACCxConfig_reg_t"); + +struct DMACChannel_dev_t { + uint32_t SrcAddr; + uint32_t DestAddr; + DMACCxLLI_reg_t LLI; + DMACCxControl_reg_t Control; + DMACCxConfig_reg_t Config; +}; +static_assert(sizeof(DMACChannel_dev_t) == 20, "invalid size of LPC DMACChannel_dev_t"); + +static DMACChannel_dev_t& DMACC0 = *(DMACChannel_dev_t*)0x50004100; +static DMACChannel_dev_t& DMACC1 = *(DMACChannel_dev_t*)0x50004120; +static DMACChannel_dev_t& DMACC2 = *(DMACChannel_dev_t*)0x50004140; +static DMACChannel_dev_t& DMACC3 = *(DMACChannel_dev_t*)0x50004160; +static DMACChannel_dev_t& DMACC4 = *(DMACChannel_dev_t*)0x50004180; +static DMACChannel_dev_t& DMACC5 = *(DMACChannel_dev_t*)0x500041A0; +static DMACChannel_dev_t& DMACC6 = *(DMACChannel_dev_t*)0x500041C0; +static DMACChannel_dev_t& DMACC7 = *(DMACChannel_dev_t*)0x500041E0; + +static DMACChannel_dev_t& DMAGetChannel(uint32_t idx) { + switch(idx) { + case 0: return DMACC0; + case 1: return DMACC1; + case 2: return DMACC2; + case 3: return DMACC3; + case 4: return DMACC4; + case 5: return DMACC5; + case 6: return DMACC6; + case 7: return DMACC7; + } + return DMACC0; // default. +} + +static uint32_t __attribute__((unused)) DMAGetChannelIndex(DMACChannel_dev_t& DMACC) { + if (&DMACC == &DMACC0) return 0; + if (&DMACC == &DMACC1) return 1; + if (&DMACC == &DMACC2) return 2; + if (&DMACC == &DMACC3) return 3; + if (&DMACC == &DMACC4) return 4; + if (&DMACC == &DMACC5) return 5; + if (&DMACC == &DMACC6) return 6; + if (&DMACC == &DMACC7) return 7; + return 0; // default. +} + +#ifdef HAL_SPI_SUPPORTS_ASYNC + +struct DMACCxLLI_desc_t { + uint32_t SrcAddr; + uint32_t DestAddr; + DMACCxLLI_desc_t *Next; + DMACCxControl_reg_t Control; +}; +static_assert(sizeof(DMACCxLLI_desc_t) == 16, "invalid size of LPC DMACCxLLI_desc_t"); + +struct DMACCxLLI_desc_user_t : public DMACCxLLI_desc_t { + // User data by software. + bool available = true; +}; + +#ifndef HALSPI_LPC_STATIC_DMADESCS +#define HALSPI_LPC_STATIC_DMADESCS 3 +#endif + +static DMACCxLLI_desc_user_t _available_dma_descs[HALSPI_LPC_STATIC_DMADESCS]; + +static DMACCxLLI_desc_user_t* DMAFindFreeChainLLI() { + for (auto& item : _available_dma_descs) { + if (item.available) { + return &item; + } + } + return nullptr; +} + +struct dma_process_t { + DMACChannel_dev_t *current_DMACC; + const void *current_buffer; + size_t curoff; + size_t txlen; + uint8_t txunitsize; + void (*completeCallback)(void*); + void *complete_ud; + DMACCxLLI_desc_user_t *last_chain; + bool is_active = false; +}; + +static dma_process_t _dma_async_proc; + +static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { + DMACCxLLI_desc_user_t *first = nullptr; + DMACCxLLI_desc_user_t *last = nullptr; + + uint32_t txwidth = 0; + + if (proc.txunitsize == 1) { + txwidth = 0; + } + else if (proc.txunitsize == 2) { + txwidth = 1; + } + else if (proc.txunitsize == 4) { + txwidth = 2; + } + else + _spi_on_error(4); + + DMACCxControl_reg_t Control; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.SI = true; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 1; + Control.I = false; + + bool init_ch_prog = false; + + auto& DMACC = *proc.current_DMACC; + DMACC.Config.ITC = true; + + while (proc.curoff < proc.txlen) { + size_t left = (proc.txlen - proc.curoff); + size_t takecnt = (uint32_t)__MIN (left, (1<<12)-1); + + Control.TransferSize = takecnt; + + uint32_t SrcAddr = ( (uint32_t)proc.current_buffer + proc.curoff * proc.txunitsize ); + uint32_t DestAddr = (uint32_t)&SSP.DR; + + if (init_ch_prog == false) { + // We first have to program the channel itself. + DMACC.SrcAddr = SrcAddr; + DMACC.DestAddr = DestAddr; + DMACC.LLI.LLI = 0; + DMACC.Control = Control; + init_ch_prog = true; + } + else { + auto *freelli = DMAFindFreeChainLLI(); + + if (freelli == nullptr) break; + + freelli->SrcAddr = SrcAddr; + freelli->DestAddr = DestAddr; + freelli->Next = nullptr; + freelli->Control = Control; + freelli->available = false; + + if (first == nullptr) { + first = freelli; + DMACC.LLI.LLI = ( (uint32_t)freelli >> 2 ); + } + + if (last) { + last->Next = freelli; + } + last = freelli; + } + + proc.curoff += takecnt; + } + + if (last) { + last->Control.I = true; + } + else { + DMACC.Control.I = true; + } + + proc.last_chain = first; +} + +#endif //HAL_SPI_SUPPORTS_ASYNC + +#endif //HALSPI_DISABLE_DMA + +} // namespace MarlinLPC + + // Hardware SPI + +#ifndef HALSPI_LOOPBEEP_TIMEOUT +#define HALSPI_LOOPBEEP_TIMEOUT 3000 +#endif + + struct spi_monitored_loop + { + private: +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; +#endif + public: + inline spi_monitored_loop() { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); +#endif + } + inline void update(unsigned int beep_code) { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + }; + + static MarlinLPC::gpioMapResult_t _ssp_gpioMap; + static volatile bool _ssp_is_active = false; + static volatile bool _ssp_transaction_is_running = false; + static volatile int _ssp_cs_pin; + static volatile int _ssp_bitOrder; + static volatile int _ssp_clockMode; + static volatile uint8_t _ssp_framesize; + static volatile bool _ssp_dirty_rxbuffer; + +#ifdef HAL_SPI_SUPPORTS_ASYNC + + struct ssp_process_t { + volatile MarlinLPC::ssp_dev_t *current_ssp; + const void *current_buffer; + size_t curoff_bytes; + size_t txlen_bytes; + uint8_t txunitsize; + bool is_active = false; + void (*completeCallback)(void*); + void *complete_ud; + }; + + static ssp_process_t _ssp_async_proc; + +#endif //HAL_SPI_SUPPORTS_ASYNC + + static void _spiAsyncBarrier() { +#ifdef HAL_SPI_SUPPORTS_ASYNC + while (_ssp_async_proc.is_active) { /* wait until completion of any async SPI TX */ } +#ifndef HALSPI_DISABLE_DMA + while (MarlinLPC::_dma_async_proc.is_active) { /* wait until completion of any async DMA TX */ } +#endif +#endif + } + + void spiBegin() { + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + + // Turn off peripherals by default. + MarlinLPC::PCONP.PCSPI = false; + MarlinLPC::PCONP.PCSSP0 = false; + MarlinLPC::PCONP.PCSSP1 = false; + MarlinLPC::PCONP.PCGPDMA = false; + } + + static void _spiConfigClock(volatile MarlinLPC::ssp_dev_t& SSP, int clockMode) { + if (clockMode == SPI_CLKMODE_0) { + SSP.CR0.CPOL = false; + SSP.CR0.CPHA = false; + } + else if (clockMode == SPI_CLKMODE_1) { + SSP.CR0.CPOL = false; + SSP.CR0.CPHA = true; + } + else if (clockMode == SPI_CLKMODE_2) { + SSP.CR0.CPOL = true; + SSP.CR0.CPHA = false; + } + else if (clockMode == SPI_CLKMODE_3) { + SSP.CR0.CPOL = true; + SSP.CR0.CPHA = true; + } + _ssp_clockMode = clockMode; + } + + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +#ifdef HAL_SPI_SUPPORTS_ASYNC + while (_ssp_is_active) { /* wait until completion of any other SPI activity */ } +#else + if (_ssp_is_active) + _spi_on_error(1); +#endif + + _ssp_gpioMap = MarlinLPC::SPIMapGPIO(hint_sck, hint_miso, hint_mosi, -1); + _ssp_is_active = true; + _ssp_cs_pin = hint_cs; + + MarlinLPC::sspClockResult_t clockRes = MarlinLPC::SPICalculateClock(maxClockFreq); + + uint8_t sspBusIdx = _ssp_gpioMap.sspBusIdx; + auto& SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); + + if (sspBusIdx == 0) { + MarlinLPC::PCONP.PCSSP0 = true; + MarlinLPC::PCLKSEL1.PCLK_SSP0 = clockRes.pclk_ssp; + } + else if (sspBusIdx == 1) { + MarlinLPC::PCONP.PCSSP1 = true; + MarlinLPC::PCLKSEL0.PCLK_SSP1 = clockRes.pclk_ssp; + } + SSP.CPSR.CPSDVSR = clockRes.cpsdvsr; + SSP.CR0.DSS = 7; // 8 bit transfer + SSP.CR0.SCR = clockRes.scr; + SSP.CR0.FRF = 0; // SPI + _spiConfigClock(SSP, SPI_CLKMODE_DEFAULT); + SSP.CR1.LBM = 0; + SSP.CR1.SSE = 0; + SSP.CR1.MS = 0; // master + + _ssp_transaction_is_running = false; + _ssp_bitOrder = SPI_BITORDER_DEFAULT; // SSP peripheral has no bit-order specification support (legacy SPI peripheral only) + _ssp_dirty_rxbuffer = false; + _ssp_framesize = sizeof(uint8_t); // default (DSS = 7). + } + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + static void _spiStart() { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + SSP.CR1.SSE = true; + if (_ssp_cs_pin >= 0) { + MarlinLPC::MapPortPinFunc(_ssp_cs_pin, 0); // make sure that the CS pin is configured as GPIO. + OUT_WRITE(_ssp_cs_pin, LOW); + } + } + static void _spiEnd() { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + spi_monitored_loop tfew; + while (SSP.SR.TFE == false) { tfew.update(1); /* wait until all items from the TX queue were pushed */ } + spi_monitored_loop bsyw; + while (SSP.SR.BSY) { bsyw.update(2); /* wait until the current data transfer has finished (clean shutdown) */ } + if (_ssp_cs_pin >= 0) { + OUT_WRITE(_ssp_cs_pin, HIGH); + } + SSP.CR1.SSE = false; + } + + static void _maybe_start_transaction() { + if (_ssp_transaction_is_running == false) { + _spiStart(); + _ssp_transaction_is_running = true; + } + } + + void spiClose() { + if (_ssp_is_active == false) + _spi_on_error(2); + + _spiAsyncBarrier(); + + uint8_t sspBusIdx = _ssp_gpioMap.sspBusIdx; + + if (_ssp_transaction_is_running) { + _spiEnd(); + _ssp_transaction_is_running = false; + } + + if (sspBusIdx == 0) { + MarlinLPC::PCONP.PCSSP0 = false; + } + else if (sspBusIdx == 1) { + MarlinLPC::PCONP.PCSSP1 = false; + } + + MarlinLPC::SPIUnmapGPIO(_ssp_gpioMap); + + _ssp_is_active = false; + } + + void spiSetBitOrder(int bitOrder) { + if (_ssp_bitOrder != bitOrder) { + _spiAsyncBarrier(); + + if (_ssp_transaction_is_running) { + _spiEnd(); + } + + _ssp_bitOrder = bitOrder; + + if (_ssp_transaction_is_running) { + _spiStart(); + } + } + } + + void spiSetClockMode(int clockMode) { + if (_ssp_clockMode != clockMode) { + _spiAsyncBarrier(); + + if (_ssp_transaction_is_running) { + _spiEnd(); + } + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spiConfigClock(SSP, clockMode); + + if (_ssp_transaction_is_running) { + _spiStart(); + } + } + } + + // Internal. + inline void _spiSetFrameSize(uint8_t fsize) { + if (_ssp_framesize != fsize) { + _spiAsyncBarrier(); + + if (_ssp_transaction_is_running) { + _spiEnd(); + } + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + SSP.CR0.DSS = (fsize * 8)-1; + _ssp_framesize = fsize; + + if (_ssp_transaction_is_running) { + _spiStart(); + } + } + } + + // Unsigned integer only. + template + inline numberType _flip_bits(numberType v) { + numberType result = 0; + for (unsigned int n = 0; n < (sizeof(numberType)*8); n++) + { + result <<= 1; + bool bitval = ( v & (1< + inline void _spi_push_to_queue(volatile MarlinLPC::ssp_dev_t& SSP, numberType val) { + bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); + if (_ssp_framesize == 1) { + // Push it byte-by-byte (DSS = 7). + uint32_t num_bytes = sizeof(numberType); + + bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); + + for (uint32_t n = 0; n < num_bytes; n++) { + uint32_t byte_idx; + + if (revbytes) { + byte_idx = (num_bytes-1) - n; + } + else { + byte_idx = 0; + } + uint32_t bitidx = byte_idx * 8; + + spi_monitored_loop tnfw; + while (SSP.SR.TNF == false) { tnfw.update(3); /* wait for space on the TX FIFO */ } + + uint8_t byteval = (val >> bitidx) & 0xFF; + + if (revbits) + byteval = _flip_bits(byteval); + + SSP.DR.DATA = byteval; + } + } + else if (_ssp_framesize == 2) { + spi_monitored_loop tnfw; + while (SSP.SR.TNF == false) { tnfw.update(3); /* wait for space om´n the TX FIFO */ } + + if (revbits) { + val = _flip_bits(val); + } + + // The number size must match the framesize. + SSP.DR.DATA = val; + } + } + + void spiSend(uint8_t val) { + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(val)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_push_to_queue(SSP, val); + + // Ignore read buffer; it will be flushed if required. + _ssp_dirty_rxbuffer = true; + } + + void spiSend16(uint16_t val) { + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(val)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_push_to_queue(SSP, val); + + // Ignore read buffer; it will be flushed if required. + _ssp_dirty_rxbuffer = true; + } + + static void _spi_flush_rxqueue(volatile MarlinLPC::ssp_dev_t& SSP) { + if (_ssp_dirty_rxbuffer == false) return; + + spi_monitored_loop tfew; + while (SSP.SR.TFE == false) { tfew.update(4); /* wait until any tx data has been acquired that is still left */ } + spi_monitored_loop bsyw; + while (SSP.SR.BSY) { bsyw.update(5); /* wait until transfers and their parallel receives have finished */ } + spi_monitored_loop rnew; + while (SSP.SR.RNE) { + rnew.update(6); + auto unused = SSP.DR.DATA; + (void)unused; + } + _ssp_dirty_rxbuffer = false; + } + + template + inline numberType _spi_fetch_from_queue(volatile MarlinLPC::ssp_dev_t& SSP) { + numberType result = 0; + bool revbits = (_ssp_bitOrder == SPI_BITORDER_MSB); + + if (_ssp_framesize == 1) { + // Fetch it byte-by-byte (DSS = 7). + uint32_t num_bytes = sizeof(numberType); + + bool revbytes = (_ssp_bitOrder == SPI_BITORDER_LSB); + + for (uint32_t n = 0; n < num_bytes; n++) { + uint32_t byte_idx; + + if (revbytes) { + byte_idx = (num_bytes-1) - n; + } + else { + byte_idx = n; + } + uint32_t bitidx = byte_idx * 8; + + spi_monitored_loop rnew; + while (SSP.SR.RNE == false) { rnew.update(7); /* wait until we have received any data */ } + + uint8_t byteval = SSP.DR.DATA & 0xFF; + + if (revbits) { + byteval = _flip_bits(byteval); + } + + result |= ( (numberType)byteval << bitidx ); + } + } + else if (_ssp_framesize == 2) { + spi_monitored_loop rnew; + while (SSP.SR.RNE == false) { rnew.update(7); /* wait until we have received any data */ } + + result = SSP.DR.DATA; + + if (revbits) { + result = _flip_bits(result); + } + } + return result; + } + + uint8_t spiRec(uint8_t txval) { + if (_ssp_gpioMap.gpio_miso < 0) { + spiSend(txval); + return 0; + } + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_flush_rxqueue(SSP); + + _spi_push_to_queue(SSP, txval); + + return _spi_fetch_from_queue (SSP); + } + + uint16_t spiRec16(uint16_t txval) { + if (_ssp_gpioMap.gpio_miso < 0) return 0; + + _spiSetFrameSize(sizeof(uint16_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_flush_rxqueue(SSP); + + _spi_push_to_queue(SSP, txval); + + return _spi_fetch_from_queue (SSP); + } + + void spiRead(uint8_t *buf, uint16_t cnt, uint8_t txval) { + if (cnt == 0) return; + if (_ssp_gpioMap.gpio_miso < 0) { + spiWriteRepeat(txval, cnt); + return; + } + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_flush_rxqueue(SSP); + + for (uint16_t n = 0; n < cnt; n++) { + _spi_push_to_queue(SSP, txval); + buf[n] = _spi_fetch_from_queue (SSP); + } + } + + void spiSendBlock(uint8_t token, const uint8_t *buf) { + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + _spi_push_to_queue(SSP, token); + + for (uint16_t n = 0; n < 512; n++) { + _spi_push_to_queue(SSP, buf[n]); + } + + _ssp_dirty_rxbuffer = true; + } + +#ifndef HALSPI_DISABLE_DMA + +static void _dmaStart() { + MarlinLPC::PCONP.PCGPDMA = true; + MarlinLPC::DMACConfig.E = true; + MarlinLPC::DMACConfig.M = 0; +} + +static void _dmaEnd() { + MarlinLPC::DMACConfig.E = false; + MarlinLPC::PCONP.PCGPDMA = false; +} + +static void _dmacInitSSP(MarlinLPC::DMACChannel_dev_t& DMACC, uint8_t sspBusIdx) { + if (sspBusIdx == 0) { + DMACC.Config.DestPeripheral = 0; + } + else if (sspBusIdx == 1) { + DMACC.Config.DestPeripheral = 2; + } + DMACC.Config.TransferType = 1; // memory to peripheral + DMACC.Config.IE = false; + DMACC.Config.ITC = false; + DMACC.Config.L = false; + DMACC.Config.H = false; +} + +template +inline void _dmaSendBlocking(const numberType *buf, uint32_t cnt) { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + uint32_t txwidth = 0; + + if (sizeof(numberType) == 1) { + txwidth = 0; + } + else if (sizeof(numberType) == 2) { + txwidth = 1; + } + else if (sizeof(numberType) == 4) { + txwidth = 2; + } + else + _spi_on_error(5); + + auto& DMACC = MarlinLPC::DMAGetChannel(0); + DMACC.DestAddr = (uint32_t)&SSP.DR; + DMACC.LLI.LLI = 0; + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + + size_t curoff = 0; + + while (curoff < cnt) { + uint32_t left = (cnt - curoff); + uint32_t takecnt = __MIN (left, (1<<12)-1); + + MarlinLPC::DMACCxControl_reg_t Control; + Control.TransferSize = takecnt; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.reserved1 = 0; + Control.SI = true; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 0; + Control.I = false; + + DMACC.SrcAddr = (uint32_t)( buf + curoff ); + DMACC.Control = Control; + + curoff += takecnt; + + // Kick off the DMA. + DMACC.Config.E = true; + while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + } + + _ssp_dirty_rxbuffer = true; +} + +template +static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + uint32_t txwidth = 0; + + if (sizeof(numberType) == 1) { + txwidth = 0; + } + else if (sizeof(numberType) == 2) { + txwidth = 1; + } + else if (sizeof(numberType) == 4) { + txwidth = 2; + } + else + _spi_on_error(5); + + auto& DMACC = MarlinLPC::DMAGetChannel(0); + DMACC.SrcAddr = (uint32_t)&val; + DMACC.DestAddr = (uint32_t)&SSP.DR; + DMACC.LLI.LLI = 0; + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + + size_t curoff = 0; + + while (curoff < repcnt) { + uint32_t left = (repcnt - curoff); + uint32_t takecnt = __MIN (left, (1<<12)-1); + + MarlinLPC::DMACCxControl_reg_t Control; + Control.TransferSize = takecnt; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.reserved1 = 0; + Control.SI = false; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 0; + Control.I = false; + + DMACC.Control = Control; + + curoff += takecnt; + + // Kick off the DMA. + DMACC.Config.E = true; + while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + } + + _ssp_dirty_rxbuffer = true; +} + +#endif + +#ifndef HALSPI_DMA_THRESHOLD +#define HALSPI_DMA_THRESHOLD 32 +#endif + + void spiWrite(const uint8_t *buf, uint16_t cnt) { + if (cnt == 0) return; + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendBlocking(buf, cnt); + _dmaEnd(); + return; + } +#endif + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + for (uint16_t n = 0; n < cnt; n++) { + _spi_push_to_queue(SSP, buf[n]); + } + + _ssp_dirty_rxbuffer = true; + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + if (cnt == 0) return; + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(uint16_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendBlocking(buf, cnt); + _dmaEnd(); + return; + } +#endif + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + for (uint16_t n = 0; n < cnt; n++) { + _spi_push_to_queue(SSP, buf[n]); + } + + _ssp_dirty_rxbuffer = true; + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + if (repcnt == 0) return; + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (repcnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendRepeatBlocking(val, repcnt); + _dmaEnd(); + return; + } +#endif + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + for (uint16_t n = 0; n < repcnt; n++) { + _spi_push_to_queue(SSP, val); + } + + _ssp_dirty_rxbuffer = true; + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + if (repcnt == 0) return; + if (_ssp_gpioMap.gpio_mosi < 0) return; + + _spiSetFrameSize(sizeof(uint16_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (repcnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendRepeatBlocking(val, repcnt); + _dmaEnd(); + return; + } +#endif + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + for (uint16_t n = 0; n < repcnt; n++) { + _spi_push_to_queue(SSP, val); + } + + _ssp_dirty_rxbuffer = true; + } + +#ifdef HAL_SPI_SUPPORTS_ASYNC + +#ifndef HALSPI_DISABLE_DMA + +static void _dmaUninstallInterrupt(); + +static void _dmacAdvance(MarlinLPC::dma_process_t& proc) { + // If there is any last chain that was used then clear it. + if (auto *last_chain = proc.last_chain) { + MarlinLPC::DMACCxLLI_desc_user_t *iter = last_chain; + + while (iter) { + iter->available = true; + iter = (MarlinLPC::DMACCxLLI_desc_user_t*)iter->Next; + } + proc.last_chain = nullptr; + } + + auto& DMACC = *proc.current_DMACC; + + if (proc.curoff == proc.txlen) { + // Disable the terminal count interrupt. + DMACC.Control.I = false; + DMACC.Config.ITC = false; + + _dmaUninstallInterrupt(); + _dmaEnd(); + + auto completeCallback = proc.completeCallback; + void *complete_ud = proc.complete_ud; + + // Finished. + proc.current_DMACC = nullptr; + proc.current_buffer = nullptr; + proc.curoff = 0; + proc.txlen = 0; + proc.txunitsize = 0; + proc.completeCallback = nullptr; + proc.complete_ud = nullptr; + proc.is_active = false; + + if (completeCallback) { + completeCallback(complete_ud); + } + return; + } + + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + MarlinLPC::DMAProgramSSPChain(SSP, proc); + + // Kick-off another async TX. + DMACC.Config.E = true; +} + +static void _dma_interrupt() { + for (uint8_t n = 0; n < 8; n++) { + uint32_t chmask = (1< +inline void _dmaSendAsync(const numberType *buf, uint32_t cnt, void (*completeCallback)(void*), void *ud) { + auto& DMACC = MarlinLPC::DMAGetChannel(0); + + auto& proc = MarlinLPC::_dma_async_proc; + proc.current_DMACC = &DMACC; + proc.current_buffer = buf; + proc.curoff = 0; + proc.txlen = cnt; + proc.txunitsize = sizeof(numberType); + proc.completeCallback = completeCallback; + proc.complete_ud = ud; + proc.is_active = true; + + _dmaStart(); + MarlinLPC::DMACIntTCClear.IntTCClear |= (1<<0); + _dmaInstallInterrupt(); + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + _dmacAdvance(proc); +} + +#endif + +#include "../shared/SPI/bufmgmt.h" + + static void _spiDisableInterrupt(uint8_t sspBusIdx); + + template + inline void _spi_interrupt( void ) { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); + + ssp_process_t& proc = _ssp_async_proc; + + if (proc.is_active == false || proc.current_ssp != &SSP) + _spi_on_error(3); + + using namespace ::bufmgmt; + + // Check interrupt type. + if (SSP.MIS.TXMIS) { + bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); + bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); + + uint8_t txunitsize = proc.txunitsize; + size_t txmax = proc.txlen_bytes; + const void *current_buffer = proc.current_buffer; + uint8_t framesize = _ssp_framesize; + + uint32_t curoff_bytes = proc.curoff_bytes; + + // Write as much data as possible. + while (SSP.SR.TNF) { + bool has_more_data = false; + + if (framesize == 1) { + uint8_t byteval; + if (txunitsize == 1) { + if (curoff_bytes < txmax) { + const uint8_t *buf = (const uint8_t*)current_buffer; + byteval = GetByteFromNumber( + buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], + GetLocalByteIndexFromTotalByteIndex (curoff_bytes), + !revbytes + ); + has_more_data = true; + } + } + else if (txunitsize == 2) { + if (curoff_bytes < txmax) { + const uint16_t *buf = (const uint16_t*)current_buffer; + byteval = GetByteFromNumber( + buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], + GetLocalByteIndexFromTotalByteIndex (curoff_bytes), + !revbytes + ); + has_more_data = true; + } + } + + if (has_more_data) { + if (revbits) { + byteval = _flip_bits(byteval); + } + + // Push the data onto the (not-full) queue, byte-by-byte (DSS = 7). + SSP.DR.DATA = byteval; + + curoff_bytes += sizeof(uint8_t); + } + } + else if (framesize == 2) { + uint16_t val; + if (txunitsize == 2) { + if (curoff_bytes < txmax) { + const uint16_t *buf = (const uint16_t*)current_buffer; + val = buf[ curoff_bytes / sizeof(uint16_t) ]; + has_more_data = true; + } + } + + if (has_more_data) { + if (revbits) { + val = _flip_bits(val); + } + + SSP.DR.DATA = val; + + curoff_bytes += sizeof(uint16_t); + } + } + + if (has_more_data) { + // We are ignoring the reception part. + _ssp_dirty_rxbuffer = true; + } + else { + // Disable the interrupt. + _spiDisableInterrupt(sspBusIdx); + + SSP.IMSC.TXIM = false; + + auto completeCallback = proc.completeCallback; + auto complete_ud = proc.complete_ud; + + // We have finished the transfer, thus dismantle. + proc.current_ssp = nullptr; + proc.current_buffer = nullptr; + proc.curoff_bytes = 0; + proc.txlen_bytes = 0; + proc.txunitsize = 0; + proc.completeCallback = nullptr; + proc.complete_ud = nullptr; + proc.is_active = false; + + // Call any completion routine. + if (completeCallback) { + completeCallback(complete_ud); + } + + goto finished; + } + } + // Save progress. + proc.curoff_bytes = curoff_bytes; + + finished:; + } + } + + static void _spi_interrupt_sspbus0() { + _spi_interrupt <0> (); + } + static void _spi_interrupt_sspbus1() { + _spi_interrupt <1> (); + } + + static void _spiEnableInterrupt(uint8_t sspBusIdx) { + if (sspBusIdx == 0) { + nvicSetIRQHandler((IRQn_Type)14, _spi_interrupt_sspbus0); + } + else if (sspBusIdx == 1) { + nvicSetIRQHandler((IRQn_Type)15, _spi_interrupt_sspbus1); + } + nvicInstallRedirect(); + if (sspBusIdx == 0) { + NVIC_EnableIRQ((IRQn_Type)14); + NVIC_SetPriority((IRQn_Type)14, 5); + } + else if (sspBusIdx == 1) { + NVIC_EnableIRQ((IRQn_Type)15); + NVIC_SetPriority((IRQn_Type)15, 5); + } + } + + static void _spiDisableInterrupt(uint8_t sspBusIdx) { + if (sspBusIdx == 0) { + NVIC_SetPriority((IRQn_Type)14, 255); + NVIC_DisableIRQ((IRQn_Type)14); + } + else if (sspBusIdx == 1) { + NVIC_SetPriority((IRQn_Type)15, 255); + NVIC_DisableIRQ((IRQn_Type)15); + } + nvicUninstallRedirect(); + if (sspBusIdx == 0) { + nvicResetIRQHandler((IRQn_Type)14); + } + else if (sspBusIdx == 1) { + nvicResetIRQHandler((IRQn_Type)15); + } + } + + template + static void _spiStartAsyncTX(const numberType *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + + // Start the async process. + auto& proc = _ssp_async_proc; + proc.current_ssp = &SSP; + proc.current_buffer = buf; + proc.curoff_bytes = 0; + proc.txlen_bytes = cnt * sizeof(numberType); + proc.txunitsize = sizeof(numberType); + proc.completeCallback = completeCallback; + proc.complete_ud = ud; + proc.is_active = true; + + // Register the interrupt. + _spiEnableInterrupt(_ssp_gpioMap.sspBusIdx); + + // Enable the interrupt. This should kick it off. + SSP.IMSC.TXIM = true; + } + + void spiWriteAsync(const uint8_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { + if (completeCallback) { + completeCallback(ud); + } + return; + } + + _spiSetFrameSize(sizeof(uint8_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaSendAsync(buf, cnt, completeCallback, ud); + return; + } +#endif + + _spiStartAsyncTX(buf, cnt, completeCallback, ud); + } + + void spiWriteAsync16(const uint16_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { + if (completeCallback) { + completeCallback(ud); + } + return; + } + + _spiSetFrameSize(sizeof(uint16_t)); + + _maybe_start_transaction(); + + _spiAsyncBarrier(); + +#ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaSendAsync(buf, cnt, completeCallback, ud); + return; + } +#endif + + _spiStartAsyncTX(buf, cnt, completeCallback, ud); + } + + void spiAsyncAbort() { + cli(); + { + auto& proc = _ssp_async_proc; + + if (proc.is_active) { + auto& SSP = *proc.current_ssp; + + // Disable the interrupt processing. + SSP.IMSC.TXIM = false; + + // Unregister the interrupt. + _spiDisableInterrupt(MarlinLPC::SPIGetBusIndex(SSP)); + + // Cancel the process. + proc.is_active = false; + } + } +#ifndef HALSPI_DISABLE_DMA + { + auto& proc = MarlinLPC::_dma_async_proc; + + if (proc.is_active) { + auto& DMACC = *proc.current_DMACC; + + DMACC.Config.H = true; + while (DMACC.Config.A) { /* wait until the DMA channel has no more data to process */ } + DMACC.Config.E = false; + + DMACC.Config.ITC = false; + DMACC.Control.I = false; + + // Cancel the process. + proc.is_active = false; + } + } +#endif + + sei(); + } + + void spiAsyncJoin() { + _spiAsyncBarrier(); + } + + bool spiAsyncIsRunning() { + if (_ssp_async_proc.is_active) return true; + #ifndef HALSPI_DISABLE_DMA + if (MarlinLPC::_dma_async_proc.is_active) return true; + #endif + return false; + } + +#endif + +#endif + +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp new file mode 100644 index 000000000000..933a3553cbea --- /dev/null +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp @@ -0,0 +1,212 @@ +/** + * 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 . + * + */ + +/** + * For TARGET_LPC1768 + */ + +/** + * Hardware SPI and Software SPI implementations are included in this file. + * + * Control of the slave select pin(s) is handled by the calling routines. + * + * Some of the LCD interfaces/adapters result in the LCD SPI and the SD card + * SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with + * WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is + * active. If any of these pins are shared then the software SPI must be used. + */ + +// Actually: LPC176x/LPC175x +#ifdef TARGET_LPC1768 + +#include "../../inc/MarlinConfig.h" + +#include "../shared/HAL_SPI.h" + +// ------------------------ +// Public functions +// ------------------------ +#if ENABLED(SOFTWARE_SPI) + + // Software SPI + + #include + + static uint8_t SPI_speed = SPI_FULL_SPEED; + static int _spi_bit_order = SPI_BITORDER_DEFAULT; + static int _spi_sck_pin, _spi_miso_pin, _spi_mosi_pin; + static int _spi_cs_pin; + + static uint8_t spiTransfer(uint8_t b) { + return swSpiTransfer(b, SPI_speed, _spi_sck_pin, _spi_miso_pin, _spi_mosi_pin); + } + + void spiBegin() { + //swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); + } + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + int use_sck = ( ( hint_sck >= 0 ) ? hint_sck : SD_SCK_PIN ); + int use_miso = ( ( hint_miso >= 0 ) ? hint_miso : SD_MISO_PIN ); + int use_mosi = ( ( hint_mosi >= 0 ) ? hint_mosi : SD_MOSI_PIN ); + _spi_sck_pin = use_sck; + _spi_miso_pin = use_miso; + _spi_mosi_pin = use_mosi; + swSpiBegin(use_sck, use_miso, use_mosi); + SPI_speed = swSpiInit(spiRate, use_sck, use_mosi); + _spi_bit_order = SPI_BITORDER_DEFAULT; + _spi_cs_pin = hint_cs; + if (hint_cs >= 0) + OUT_WRITE(hint_cs, LOW); + } + + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint8_t spiRate; + if (maxClockFreq >= 20000000) { + spiRate = SPI_FULL_SPEED; + } + else if (maxClockFreq >= 5000000) { + spiRate = SPI_HALF_SPEED; + } + else if (maxClockFreq >= 2500000) { + spiRate = SPI_QUARTER_SPEED; + } + else if (maxClockFreq >= 1250000) { + spiRate = SPI_EIGHTH_SPEED; + } + else if (maxClockFreq >= 625000) { + spiRate = SPI_SPEED_5; + } + else if (maxClockFreq >= 300000) { + spiRate = SPI_SPEED_6; + } + else + spiRate = SPI_SPEED_6; + + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + void spiClose() { + if (_spi_cs_pin >= 0) + OUT_WRITE(_spi_cs_pin, HIGH); + } + + static inline uint8_t _flip_bits_8(uint8_t v) { + uint8_t result = 0; + for (int n = 0; n < 8; n++) + { + result <<= 1; + bool bitval = ( v & ( 1 << n ) ) != 0; + result |= bitval; + } + return result; + } + + void spiSetBitOrder(int bitOrder) { + _spi_bit_order = bitOrder; + } + + void spiSetClockMode(int mode) { + if (mode != SPI_CLKMODE_0) { + // FATAL ERROR: not supported. + while (true) { +#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(300); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1500); +#endif + } + } + } + + uint8_t spiRec(uint8_t txval) { return (_spi_bit_order == SPI_BITORDER_MSB) ? spiTransfer(txval) : _flip_bits_8(spiTransfer(_flip_bits_8(txval))); } + + uint16_t spiRec16(uint16_t txval) { + bool msb = (_spi_bit_order == SPI_BITORDER_MSB); + uint8_t tx_first, tx_second; + if (msb) { + tx_first = ( txval >> 8 ); + tx_second = ( txval & 0xFF ); + } + else { + tx_first = ( txval & 0xFF ); + tx_second = ( txval >> 8 ); + } + + uint16_t v = ( msb ? ( (uint16_t)spiRec(tx_first) << 8 ) : spiRec(tx_first) ); + v |= ( msb ? spiRec(tx_second) : ( (uint16_t)spiRec(tx_second) << 8 ) ); + return v; + } + + void spiRead(uint8_t*buf, uint16_t nbyte, uint8_t txval) { + for (int i = 0; i < nbyte; i++) + buf[i] = spiRec(txval); + } + + void spiSend(uint8_t b) { (void)spiTransfer((_spi_bit_order == SPI_BITORDER_MSB) ? b : _flip_bits_8(b)); } + + void spiSend16(uint16_t v) { + bool msb = (_spi_bit_order == SPI_BITORDER_MSB); + spiSend(msb ? (v >> 8) : (v&0xFF)); + spiSend(msb ? (v&0xFF) : (v >> 8)); + } + + void spiSend(const uint8_t *buf, size_t nbyte) { + for (uint16_t i = 0; i < nbyte; i++) + spiSend(buf[i]); + } + + void spiSendBlock(uint8_t token, const uint8_t *buf) { + spiSend(token); + for (uint16_t i = 0; i < 512; i++) + spiSend(buf[i]); + } + + void spiWrite(const uint8_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } + +#endif + +#endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/MarlinSPI.h b/Marlin/src/HAL/LPC1768/MarlinSPI.h deleted file mode 100644 index fab245f904e3..000000000000 --- a/Marlin/src/HAL/LPC1768/MarlinSPI.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -/** - * Marlin currently requires 3 SPI classes: - * - * SPIClass: - * This class is normally provided by frameworks and has a semi-default interface. - * This is needed because some libraries reference it globally. - * - * SPISettings: - * Container for SPI configs for SPIClass. As above, libraries may reference it globally. - * - * These two classes are often provided by frameworks so we cannot extend them to add - * useful methods for Marlin. - * - * MarlinSPI: - * Provides the default SPIClass interface plus some Marlin goodies such as a simplified - * interface for SPI DMA transfer. - * - */ - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/LPC1768/include/SPI.h b/Marlin/src/HAL/LPC1768/include/SPI.h deleted file mode 100644 index 24f4759315bd..000000000000 --- a/Marlin/src/HAL/LPC1768/include/SPI.h +++ /dev/null @@ -1,182 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "../../shared/HAL_SPI.h" - -#include -#include -#include - -//#define MSBFIRST 1 - -#define SPI_MODE0 0 -#define SPI_MODE1 1 -#define SPI_MODE2 2 -#define SPI_MODE3 3 - -#define DATA_SIZE_8BIT SSP_DATABIT_8 -#define DATA_SIZE_16BIT SSP_DATABIT_16 - -#define SPI_CLOCK_MAX_TFT 30000000UL -#define SPI_CLOCK_DIV2 8333333 //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED -#define SPI_CLOCK_DIV4 4166667 //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED -#define SPI_CLOCK_DIV8 2083333 //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED -#define SPI_CLOCK_DIV16 1000000 //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED -#define SPI_CLOCK_DIV32 500000 //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 -#define SPI_CLOCK_DIV64 250000 //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 -#define SPI_CLOCK_DIV128 125000 //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h - -#define SPI_CLOCK_MAX SPI_CLOCK_DIV2 - -#define BOARD_NR_SPI 2 - -//#define BOARD_SPI1_NSS_PIN PA4 ?! -#define BOARD_SPI1_SCK_PIN P0_15 -#define BOARD_SPI1_MISO_PIN P0_17 -#define BOARD_SPI1_MOSI_PIN P0_18 - -//#define BOARD_SPI2_NSS_PIN PB12 ?! -#define BOARD_SPI2_SCK_PIN P0_07 -#define BOARD_SPI2_MISO_PIN P0_08 -#define BOARD_SPI2_MOSI_PIN P0_09 - -class SPISettings { -public: - SPISettings(uint32_t spiRate, int inBitOrder, int inDataMode) { - init_AlwaysInline(spiRate2Clock(spiRate), inBitOrder, inDataMode, DATA_SIZE_8BIT); - } - SPISettings(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) { - if (__builtin_constant_p(inClock)) - init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize); - else - init_MightInline(inClock, inBitOrder, inDataMode, inDataSize); - } - SPISettings() { - init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); - } - - //uint32_t spiRate() const { return spi_speed; } - - static uint32_t spiRate2Clock(uint32_t spiRate) { - uint32_t Marlin_speed[7]; // CPSR is always 2 - Marlin_speed[0] = 8333333; //(SCR: 2) desired: 8,000,000 actual: 8,333,333 +4.2% SPI_FULL_SPEED - Marlin_speed[1] = 4166667; //(SCR: 5) desired: 4,000,000 actual: 4,166,667 +4.2% SPI_HALF_SPEED - Marlin_speed[2] = 2083333; //(SCR: 11) desired: 2,000,000 actual: 2,083,333 +4.2% SPI_QUARTER_SPEED - Marlin_speed[3] = 1000000; //(SCR: 24) desired: 1,000,000 actual: 1,000,000 SPI_EIGHTH_SPEED - Marlin_speed[4] = 500000; //(SCR: 49) desired: 500,000 actual: 500,000 SPI_SPEED_5 - Marlin_speed[5] = 250000; //(SCR: 99) desired: 250,000 actual: 250,000 SPI_SPEED_6 - Marlin_speed[6] = 125000; //(SCR:199) desired: 125,000 actual: 125,000 Default from HAL.h - return Marlin_speed[spiRate > 6 ? 6 : spiRate]; - } - -private: - void init_MightInline(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) { - init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize); - } - void init_AlwaysInline(uint32_t inClock, uint8_t inBitOrder, uint8_t inDataMode, uint32_t inDataSize) __attribute__((__always_inline__)) { - clock = inClock; - bitOrder = inBitOrder; - dataMode = inDataMode; - dataSize = inDataSize; - } - - //uint32_t spi_speed; - uint32_t clock; - uint32_t dataSize; - //uint32_t clockDivider; - uint8_t bitOrder; - uint8_t dataMode; - LPC_SSP_TypeDef *spi_d; - - friend class SPIClass; -}; - -/** - * @brief Wirish SPI interface. - * - * This is the same interface is available across HAL - * - * This implementation uses software slave management, so the caller - * is responsible for controlling the slave select line. - */ -class SPIClass { -public: - /** - * @param spiPortNumber Number of the SPI port to manage. - */ - SPIClass(uint8_t spiPortNumber); - - /** - * Init using pins - */ - SPIClass(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)-1); - - /** - * Select and configure the current selected SPI device to use - */ - void begin(); - - /** - * Disable the current SPI device - */ - void end(); - - void beginTransaction(const SPISettings&); - void endTransaction() {} - - // Transfer using 1 "Data Size" - uint8_t transfer(uint16_t data); - // Transfer 2 bytes in 8 bit mode - uint16_t transfer16(uint16_t data); - - void send(uint8_t data); - - uint16_t read(); - void read(uint8_t *buf, uint32_t len); - - void dmaSend(void *buf, uint16_t length, bool minc); - - /** - * @brief Sets the number of the SPI peripheral to be used by - * this HardwareSPI instance. - * - * @param spi_num Number of the SPI port. 1-2 in low density devices - * or 1-3 in high density devices. - */ - void setModule(uint8_t device); - - void setClock(uint32_t clock); - void setBitOrder(uint8_t bitOrder); - void setDataMode(uint8_t dataMode); - void setDataSize(uint32_t ds); - - inline uint32_t getDataSize() { return _currentSetting->dataSize; } - -private: - SPISettings _settings[BOARD_NR_SPI]; - SPISettings *_currentSetting; - - void updateSettings(); -}; - -extern SPIClass SPI; diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 419c99793fb8..d73f88e3f896 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -36,6 +36,8 @@ #include "../../sd/cardreader.h" +#include "../shared/ARM/HAL_NVIC.h" + extern uint32_t MSC_SD_Init(uint8_t pdrv); extern "C" { @@ -50,6 +52,8 @@ TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); void MarlinHAL::init() { + nvicBegin(); + // Init LEDs #if PIN_EXISTS(LED) SET_DIR_OUTPUT(LED_PIN); diff --git a/Marlin/src/HAL/LPC1768/spi_pins.h b/Marlin/src/HAL/LPC1768/spi_pins.h index e7d774742f42..982c6f8a245b 100644 --- a/Marlin/src/HAL/LPC1768/spi_pins.h +++ b/Marlin/src/HAL/LPC1768/spi_pins.h @@ -23,13 +23,6 @@ #include "../../core/macros.h" -#if BOTH(SDSUPPORT, HAS_MARLINUI_U8GLIB) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently - // needed due to the speed and mode required for communicating with each device being different. - // This requirement can be removed if the SPI access to these devices is updated to use - // spiBeginTransaction. -#endif - /** onboard SD card */ //#define SD_SCK_PIN P0_07 //#define SD_MISO_PIN P0_08 diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp deleted file mode 100644 index a9847b2d2fa0..000000000000 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ /dev/null @@ -1,130 +0,0 @@ -/** - * 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 . - * - */ - -#include "../../../inc/MarlinConfig.h" - -#if HAS_SPI_TFT - -#include "tft_spi.h" - -SPIClass TFT_SPI::SPIx(1); - -void TFT_SPI::Init() { - #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RESET_PIN, HIGH); - delay(100); - #endif - - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - #endif - - SET_OUTPUT(TFT_DC_PIN); - SET_OUTPUT(TFT_CS_PIN); - WRITE(TFT_DC_PIN, HIGH); - WRITE(TFT_CS_PIN, HIGH); - - /** - * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz - * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 - * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 - */ - #if 0 - #if SPI_DEVICE == 1 - #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 - #else - #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 - #endif - uint8_t clock; - uint8_t spiRate = SPI_FULL_SPEED; - switch (spiRate) { - case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break; - case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break; - case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break; - case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break; - case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break; - case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; - default: clock = SPI_CLOCK_DIV2; // Default from the SPI library - } - #endif - - #if TFT_MISO_PIN == BOARD_SPI1_MISO_PIN - SPIx.setModule(1); - #elif TFT_MISO_PIN == BOARD_SPI2_MISO_PIN - SPIx.setModule(2); - #endif - SPIx.setClock(SPI_CLOCK_MAX_TFT); - SPIx.setBitOrder(MSBFIRST); - SPIx.setDataMode(SPI_MODE0); -} - -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.setDataSize(DataSize); - SPIx.begin(); - WRITE(TFT_CS_PIN, LOW); -} - -uint32_t TFT_SPI::GetID() { - uint32_t id; - id = ReadID(LCD_READ_ID); - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = ReadID(LCD_READ_ID4); - return id; -} - -uint32_t TFT_SPI::ReadID(uint16_t Reg) { - uint32_t data = 0; - - #if PIN_EXISTS(TFT_MISO) - uint8_t d = 0; - SPIx.setDataSize(DATASIZE_8BIT); - SPIx.setClock(SPI_CLOCK_DIV64); - SPIx.begin(); - WRITE(TFT_CS_PIN, LOW); - WriteReg(Reg); - - LOOP_L_N(i, 4) { - SPIx.read((uint8_t*)&d, 1); - data = (data << 8) | d; - } - - DataTransferEnd(); - SPIx.setClock(SPI_CLOCK_MAX_TFT); - #endif - - return data >> 7; -} - -bool TFT_SPI::isBusy() { return false; } - -void TFT_SPI::Abort() { DataTransferEnd(); } - -void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); } - -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DataTransferBegin(DATASIZE_16BIT); - WRITE(TFT_DC_PIN, HIGH); - SPIx.dmaSend(Data, Count, MemoryIncrease); - DataTransferEnd(); -} - -#endif // HAS_SPI_TFT diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.h b/Marlin/src/HAL/LPC1768/tft/tft_spi.h deleted file mode 100644 index 4753fdbae9a0..000000000000 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.h +++ /dev/null @@ -1,77 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "../../../inc/MarlinConfig.h" - -#include -#include -// #include - -#ifndef LCD_READ_ID - #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) -#endif -#ifndef LCD_READ_ID4 - #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) -#endif - -#define DATASIZE_8BIT SSP_DATABIT_8 -#define DATASIZE_16BIT SSP_DATABIT_16 -#define TFT_IO_DRIVER TFT_SPI - -#define DMA_MINC_ENABLE 1 -#define DMA_MINC_DISABLE 0 - -class TFT_SPI { -private: - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); - -public: - static SPIClass SPIx; - - static void Init(); - static uint32_t GetID(); - static bool isBusy(); - static void Abort(); - - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); - static void DataTransferEnd() { OUT_WRITE(TFT_CS_PIN, HIGH); SPIx.end(); }; - static void DataTransferAbort(); - - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } - - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, uint32_t Count) { - static uint16_t Data; Data = Color; - //LPC dma can only write 0xFFF bytes at once. - #define MAX_DMA_SIZE (0xFFF - 1) - while (Count > 0) { - TransmitDMA(DMA_MINC_DISABLE, &Data, Count > MAX_DMA_SIZE ? MAX_DMA_SIZE : Count); - Count = Count > MAX_DMA_SIZE ? Count - MAX_DMA_SIZE : 0; - } - #undef MAX_DMA_SIZE - } -}; diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h deleted file mode 100644 index 7c456cf00e1b..000000000000 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ /dev/null @@ -1,83 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "../../../inc/MarlinConfig.h" - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - #include -#endif - -#ifndef TOUCH_MISO_PIN - #define TOUCH_MISO_PIN SD_MISO_PIN -#endif -#ifndef TOUCH_MOSI_PIN - #define TOUCH_MOSI_PIN SD_MOSI_PIN -#endif -#ifndef TOUCH_SCK_PIN - #define TOUCH_SCK_PIN SD_SCK_PIN -#endif -#ifndef TOUCH_CS_PIN - #define TOUCH_CS_PIN SD_SS_PIN -#endif -#ifndef TOUCH_INT_PIN - #define TOUCH_INT_PIN -1 -#endif - -#define XPT2046_DFR_MODE 0x00 -#define XPT2046_SER_MODE 0x04 -#define XPT2046_CONTROL 0x80 - -enum XPTCoordinate : uint8_t { - XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, -}; - -#ifndef XPT2046_Z1_THRESHOLD - #define XPT2046_Z1_THRESHOLD 10 -#endif - -class XPT2046 { -private: - static bool isBusy() { return false; } - - static uint16_t getRawData(const XPTCoordinate coordinate); - static bool isTouched(); - - static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); - #endif - static uint16_t SoftwareIO(uint16_t data); - static uint16_t IO(uint16_t data = 0); - -public: - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static SPIClass SPIx; - #endif - - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); -}; diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp index 07d0ceeb53d4..e4a3fd40f460 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_hw_spi.cpp @@ -84,8 +84,7 @@ uint8_t u8g_com_HAL_LPC1768_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, u8g_SetPIOutput(u8g, U8G_PI_A0); u8g_SetPIOutput(u8g, U8G_PI_RESET); u8g_Delay(5); - spiBegin(); - spiInit(LCD_SPI_SPEED); // TODO: hint the SPI pins here. + spiInit(LCD_SPI_SPEED, U8G_PI_SCK, -1, U8G_PI_MOSI, U8G_PI_CS); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ diff --git a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp index f69941ad81f5..d582700f19a2 100644 --- a/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp +++ b/Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp @@ -83,9 +83,8 @@ uint8_t u8g_com_HAL_LPC1768_ST7920_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t ar u8g_SetPILevel(u8g, U8G_PI_CS, 0); u8g_SetPIOutput(u8g, U8G_PI_CS); u8g_Delay(5); - spiBegin(); - // TODO: hint the SPI pins here. - spiInit(SPI_EIGHTH_SPEED); // ST7920 max speed is about 1.1 MHz + // ST7920 max speed is about 1.1 MHz + spiInitEx(1100000, U8G_PI_SCK, -1, U8G_PI_MOSI, U8G_PI_CS); u8g->pin_list[U8G_PI_A0_STATE] = 0; // initial RS state: command mode break; diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h deleted file mode 100644 index b5cc6f02a45a..000000000000 --- a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h index a5138e0ccbe8..93e420590fec 100644 --- a/Marlin/src/HAL/NATIVE_SIM/spi_pins.h +++ b/Marlin/src/HAL/NATIVE_SIM/spi_pins.h @@ -25,7 +25,7 @@ #include "../../inc/MarlinConfigPre.h" #if BOTH(HAS_MARLINUI_U8GLIB, SDSUPPORT) && (LCD_PINS_D4 == SD_SCK_PIN || LCD_PINS_ENABLE == SD_MOSI_PIN || DOGLCD_SCK == SD_SCK_PIN || DOGLCD_MOSI == SD_MOSI_PIN) - #define LPC_SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently + #define SOFTWARE_SPI // If the SD card and LCD adapter share the same SPI pins, then software SPI is currently // needed due to the speed and mode required for communicating with each device being different. // This requirement can be removed if the SPI access to these devices is updated to use // spiBeginTransaction. diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h index b3e622f19ac4..5a6149990c69 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/tft_spi.h @@ -34,6 +34,8 @@ #define DATASIZE_16BIT 16 #define TFT_IO_DRIVER TFT_SPI +#define TFT_SUPPORTS_8BIT + #define DMA_MINC_ENABLE 1 #define DMA_MINC_DISABLE 0 @@ -51,12 +53,13 @@ class TFT_SPI { static bool isBusy(); static void Abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT); + static void DataTransferBegin(); static void DataTransferEnd(); - static void DataTransferAbort(); static void WriteData(uint16_t Data); + static void WriteData8(uint8_t Data); static void WriteReg(uint16_t Reg); + static void WriteReg8(uint8_t Reg); static void WriteSequence(uint16_t *Data, uint16_t Count); // static void WriteMultiple(uint16_t Color, uint16_t Count); diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index 4e999f88ff98..d05af88761d4 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -20,10 +20,6 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - #include -#endif - #ifndef TOUCH_MISO_PIN #define TOUCH_MISO_PIN SD_MISO_PIN #endif @@ -64,16 +60,10 @@ class XPT2046 { static void DataTransferBegin(); static void DataTransferEnd(); - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); - #endif static uint16_t SoftwareIO(uint16_t data); static uint16_t IO(uint16_t data = 0); public: - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static SPIClass SPIx; - #endif static void Init(); static bool getRawPoint(int16_t *x, int16_t *y); diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index c374bc824608..d99f1c027b4e 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -58,6 +58,10 @@ static SPISettings spiConfig; + static uint32_t _spi_clock; + static int _spi_bitOrder; + static int _spi_clockMode; + // ------------------------ // Hardware SPI // https://github.com/arduino/ArduinoCore-samd/blob/master/libraries/SPI/SPI.h @@ -65,6 +69,14 @@ void spiBegin() { } + void spiInit(uint32_t clock, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + _spi_clock = clock; + _spi_bitOrder = MSBFIRST; + _spi_clockMode = SPI_MODE0; + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + sdSPI.begin(); + } + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Ignore all pin hints. if (spiRate == SPI_SPEED_DEFAULT) @@ -81,14 +93,39 @@ case SPI_SPEED_6: clock = 125000; break; default: clock = 4000000; break; // Default from the SPI library } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - sdSPI.begin(); + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); } void spiClose() { sdSPI.end(); } + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + _spi_bitOrder = MSBFIRST; + } + else if (bitOrder == SPI_BITORDER_LSB) { + _spi_bitOrder = LSBFIRST; + } + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); + } + + void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + _spi_clockMode = SPI_MODE0; + else if (clockMode == SPI_CLKMODE_1) + _spi_clockMode = SPI_MODE1; + else if (clockMode == SPI_CLKMODE_2) + _spi_clockMode = SPI_MODE2; + else if (clockMode == SPI_CLKMODE_3) + _spi_clockMode = SPI_MODE3; + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); + } + /** * @brief Receives a single byte from the SPI port. * @@ -96,13 +133,19 @@ * * @details */ - uint8_t spiRec() { + uint8_t spiRec(uint8_t txval) { sdSPI.beginTransaction(spiConfig); - uint8_t returnByte = sdSPI.transfer(0xFF); + uint8_t returnByte = sdSPI.transfer(txval); sdSPI.endTransaction(); return returnByte; } + uint16_t spiRec16(uint16_t txval) { + sdSPI.beginTransaction(spiConfig); + uint16_t res = sdSPI.transfer16(txval); + sdSPI.endTransaction(); + return res; + /** * @brief Receives a number of bytes from the SPI port to a buffer * @@ -110,9 +153,9 @@ * @param nbyte Number of bytes to receive. * @return Nothing */ - void spiRead(uint8_t *buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { if (nbyte == 0) return; - memset(buf, 0xFF, nbyte); + memset(buf, txval, nbyte); sdSPI.beginTransaction(spiConfig); sdSPI.transfer(buf, nbyte); sdSPI.endTransaction(); @@ -131,6 +174,12 @@ sdSPI.endTransaction(); } + void spiSend16(uint16_t v) { + sdSPI.beginTransaction(spiConfig); + sdSPI.transfer16(v); + sdSPI.endTransaction(); + } + /** * @brief Write token and then write from 512 byte buffer to SPI (for SD card) * @@ -146,9 +195,32 @@ sdSPI.endTransaction(); } - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - spiConfig = SPISettings(spiClock, (BitOrder)bitOrder, dataMode); + void spiWrite(const uint8_t *buf, uint16_t cnt) { sdSPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + sdSPI.transfer(buf[n]); + sdSPI.endTransaction(); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + sdSPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + sdSPI.transfer16(buf[n]); + sdSPI.endTransaction(); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + sdSPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + sdSPI.transfer(val); + sdSPI.endTransaction(); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + sdSPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + sdSPI.transfer16(val); + sdSPI.endTransaction(); } #endif // !SOFTWARE_SPI diff --git a/Marlin/src/HAL/SAMD51/MarlinSPI.h b/Marlin/src/HAL/SAMD51/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/SAMD51/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h index 932348c52f40..6b43e021ae3f 100644 --- a/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/SAMD51/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/SAMD51." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/SAMD51." #endif diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index aff52f597f4d..ae2f867876a9 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -48,6 +48,8 @@ #include "usbd_cdc_if.h" #endif +#include "../shared/ARM/HAL_NVIC.h" + // ------------------------ // Public Variables // ------------------------ @@ -64,6 +66,8 @@ uint16_t MarlinHAL::adc_result; // HAL initialization task void MarlinHAL::init() { + nvicBegin(); + // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp new file mode 100644 index 000000000000..ba650f2b49e4 --- /dev/null +++ b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp @@ -0,0 +1,1303 @@ +/** + * 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 + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ + +/* + HAL SPI implementation by Martin Turski, company owner of EirDev + Inclusion date: 24th of November, 2022 + Contact mail: turningtides@outlook.de + --- + + Contact Martin if there is any grave SPI design or functionality issue. + Include a link to the Marlin FW GitHub issue post. Otherwise the mail + may be ignored. This implementation has been created specifically for the + Marlin FW. It was made with performance and simplicity-of-maintenance in + mind, while keeping all the SPI requirements in check. + + Original pull request: https://github.com/MarlinFirmware/Marlin/pull/24911 +*/ + +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfig.h" + +// ------------------------ +// Public functions +// ------------------------ + + // If properly ported, use fast HW SPI implementation originally found in STM32 tft_spi.cpp +#if !ENABLED(SOFTWARE_SPI) && (defined(STM32F1xx) || defined(STM32F4xx)) && !ENABLED(HALSPI_HW_GENERIC) + +#include "pinconfig.h" + +#include "HAL_NVIC.h" + + // ------------------------ + // Hardware SPI + // STM32F1yyxx: https://www.st.com/resource/en/reference_manual/cd00171190-stm32f101xx-stm32f102xx-stm32f103xx-stm32f105xx-and-stm32f107xx-advanced-arm-based-32-bit-mcus-stmicroelectronics.pdf + // ------------------------ + +#ifdef STM32F1xx + #include "stm32f1xx_hal.h" +#elif defined(STM32F4xx) + #include "stm32f4xx_hal.h" +#else + #error Fast HW SPI is currently only supported on STM32F1 and STM32F4 hardware. +#endif + +#ifndef HALSPI_LOOPBEEP_TIMEOUT + // Timeout in milliseconds (consider that interrupts will increase the time by a lot) + #define HALSPI_LOOPBEEP_TIMEOUT 3000 +#endif + + static SPI_HandleTypeDef SPIhx; + static DMA_HandleTypeDef DMAhx; + + uint8_t _HAL_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) + { + if ( speed >= (spibasefreq / 2) ) + { + return SPI_BAUDRATEPRESCALER_2; + } + else if ( speed >= (spibasefreq / 4) ) + { + return SPI_BAUDRATEPRESCALER_4; + } + else if ( speed >= (spibasefreq / 8) ) + { + return SPI_BAUDRATEPRESCALER_8; + } + else if ( speed >= (spibasefreq / 16) ) + { + return SPI_BAUDRATEPRESCALER_16; + } + else if ( speed >= (spibasefreq / 32) ) + { + return SPI_BAUDRATEPRESCALER_32; + } + else if ( speed >= (spibasefreq / 64) ) + { + return SPI_BAUDRATEPRESCALER_64; + } + else if ( speed >= (spibasefreq / 128) ) + { + return SPI_BAUDRATEPRESCALER_128; + } + else + { + return SPI_BAUDRATEPRESCALER_256; + } + } + +extern "C" { + #include +} + + static int _spi_pin_sck = NC; + static int _spi_pin_miso = NC; + static int _spi_pin_mosi = NC; + static int _spi_pin_cs = NC; + +#ifdef HAL_SPI_SUPPORTS_ASYNC + // We optimize this to be only one CPU-core only, no scheduler. + // Only one SPI connection is supported at-a-time, current revision. + static volatile bool _spi_busy = false; + + struct spiStatusInfo + { + bool async_busy = false; + void (*asyncCompleteCallback)(void*) = nullptr; + void *async_ud = nullptr; + }; +#if 0 +#ifdef SPI1_BASE + spiStatusInfo spiStatus_1; +#endif +#ifdef SPI2_BASE + spiStatusInfo spiStatus_2; +#endif +#ifdef SPI3_BASE + spiStatusInfo spiStatus_3; +#endif +#ifdef SPI4_BASE + spiStatusInfo spiStatus_4; +#endif +#ifdef SPI5_BASE + spiStatusInfo spiStatus_5; +#endif +#ifdef SPI6_BASE + spiStatusInfo spiStatus_6; +#endif +#else + spiStatusInfo __spi_status; +#endif + + static spiStatusInfo* SPI_GetRuntimeInfo( SPI_TypeDef *instance ) + { +#if 0 +#ifdef SPI1_BASE + if (instance == SPI1) { + return spiStatus_1; + } +#endif +#ifdef SPI2_BASE + if (instance == SPI2) { + return spiStatus_2; + } +#endif +#ifdef SPI3_BASE + if (instance == SPI3) { + return spiStatus_3; + } +#endif +#ifdef SPI4_BASE + if (instance == SPI4) { + return spiStatus_4; + } +#endif +#ifdef SPI5_BASE + if (instance == SPI5) { + return spiStatus_5; + } +#endif +#ifdef SPI6_BASE + if (instance == SPI6) { + return spiStatus_6; + } +#endif + return nullptr; +#else + return &__spi_status; +#endif + } + +#if 0 + static DMA_Channel_TypeDef* DMA_Channel_GetConfig( DMA_TypeDef *DMA, unsigned int channelNum ) + { +#ifdef DMA1_BASE + if (DMA == DMA1) + { + #ifdef DMA1_Channel1_BASE + if (channelNum == 1) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel1_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel2_BASE + if (channelNum == 2) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel2_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel3_BASE + if (channelNum == 3) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel3_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel4_BASE + if (channelNum == 4) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel4_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel5_BASE + if (channelNum == 5) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel5_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel6_BASE + if (channelNum == 6) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel6_BASE - DMA1_BASE) ); + } + #endif + #ifdef DMA1_Channel7_BASE + if (channelNum == 7) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA1_Channel7_BASE - DMA1_BASE) ); + } + #endif + } +#endif +#ifdef DMA2_BASE + if (DMA == DMA2) + { + #ifdef DMA2_Channel1_BASE + if (channelNum == 1) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA2_Channel1_BASE - DMA2_BASE) ); + } + #endif + #ifdef DMA2_Channel2_BASE + if (channelNum == 2) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA2_Channel2_BASE - DMA2_BASE) ); + } + #endif + #ifdef DMA2_Channel3_BASE + if (channelNum == 3) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA2_Channel3_BASE - DMA2_BASE) ); + } + #endif + #ifdef DMA2_Channel4_BASE + if (channelNum == 4) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA2_Channel4_BASE - DMA2_BASE) ); + } + #endif + #ifdef DMA2_Channel5_BASE + if (channelNum == 5) + { + return (DMA_Channel_TypeDef*)( (uint32_t)DMA + (DMA2_Channel5_BASE - DMA2_BASE) ); + } + #endif + } +#endif + + return nullptr; + } +#endif + + // The interrupt handler. + static void _DMA_Interrupt( void ); + + static void NVIC_DMA_Interrupt_Enable(DMA_TypeDef *DMA, uint32_t channelNum) { +#ifdef DMA1_BASE + if (DMA == DMA1) { + if (channelNum >= 1 && channelNum <= 7) { + // See page 204 of STM32F1xx ref manual (interrupt table). + IRQn_Type inum = (IRQn_Type)( 10 + channelNum ); + + HAL_NVIC_EnableIRQ(inum); + HAL_NVIC_SetPriority(inum, 5, 0); + } + } +#endif +#ifdef DMA2_BASE + if (DMA == DMA2) { + if (channelNum >= 1 && channelNum <= 3) { + // See page 204 of STM32F1xx ref manual (interrupt table). + IRQn_Type inum = (IRQn_Type)( 55 + channelNum ); + + HAL_NVIC_EnableIRQ(inum); + HAL_NVIC_SetPriority(inum, 5, 0); + } + else if (channelNum == 4 || channelNum == 5) { + HAL_NVIC_EnableIRQ((IRQn_Type)59); + HAL_NVIC_SetPriority((IRQn_Type)59, 5, 0); + } + } +#endif + } + + static void NVIC_DMA_Interrupt_Disable(DMA_TypeDef *DMA, uint32_t channelNum) { +#ifdef DMA1_BASE + if (DMA == DMA1) { + if (channelNum >= 1 && channelNum <= 7) { + // See page 204 of STM32F1xx ref manual (interrupt table). + IRQn_Type inum = (IRQn_Type)( 10 + channelNum ); + + HAL_NVIC_SetPriority(inum, 255, 0); + HAL_NVIC_DisableIRQ(inum); + } + } +#endif +#ifdef DMA2_BASE + if (DMA == DMA2) { + if (channelNum >= 1 && channelNum <= 3) { + // See page 204 of STM32F1xx ref manual (interrupt table). + IRQn_Type inum = (IRQn_Type)( 55 + channelNum ); + + HAL_NVIC_SetPriority(inum, 255, 0); + HAL_NVIC_DisableIRQ(inum); + } + else if (channelNum == 4 || channelNum == 5) { + HAL_NVIC_SetPriority((IRQn_Type)59, 255, 0); + HAL_NVIC_DisableIRQ((IRQn_Type)59); + } + } +#endif + } + + static void DMA_Channel_TXCompleteInterruptSet( DMA_Channel_TypeDef *DMAch, bool enable ) + { + if (enable) + DMAch->CCR |= 0x02; + else + DMAch->CCR &= ~0x02; + } + static void DMA_Channel_TXErrorInterruptSet( DMA_Channel_TypeDef *DMAch, bool enable ) + { + if (enable) + DMAch->CCR |= 0x04; + else + DMAch->CCR &= ~0x04; + } +#if 0 + static void DMA_Channel_Enable( DMA_Channel_TypeDef *DMAch, bool enable ) + { + if (enable) + DMAch->CCR |= 0x01; + else + DMAch->CCR &= ~0x01; + } +#endif + + static void DMA_Channel_ResetTXComplete( DMA_TypeDef *DMA, unsigned int channelNum ) + { + CBI(DMA->IFCR, ( 1 + (4 * (channelNum - 1)) )); + } + static void DMA_Channel_ResetTXError( DMA_TypeDef *DMA, unsigned int channelNum ) + { + CBI(DMA->IFCR, ( 2 + (4 * (channelNum - 1)) )); + } + + static bool DMA_Channel_TXComplete( DMA_TypeDef *DMA, unsigned int channelNum ) + { + return TEST(DMA->ISR, ( 1 + (4 * (channelNum - 1)) )); + } + static bool DMA_Channel_TXError( DMA_TypeDef *DMA, unsigned int channelNum ) + { + return TEST(DMA->ISR, ( 2 + (4 * (channelNum - 1)) )); + } +#endif //HAL_SPI_SUPPORTS_ASYNC + + static bool _HAL_SPI_InitClock(int _spi_clkmode) { + bool changed = false; + if (_spi_clkmode == SPI_CLKMODE_0 || _spi_clkmode == SPI_CLKMODE_1) { + if (SPIhx.Init.CLKPolarity != SPI_POLARITY_LOW) { + SPIhx.Init.CLKPolarity = SPI_POLARITY_LOW; + changed = true; + } + } + else { + if (SPIhx.Init.CLKPolarity != SPI_POLARITY_HIGH) { + SPIhx.Init.CLKPolarity = SPI_POLARITY_HIGH; + changed = true; + } + } + + if (_spi_clkmode == SPI_CLKMODE_0 || _spi_clkmode == SPI_CLKMODE_2) { + if (SPIhx.Init.CLKPhase != SPI_PHASE_1EDGE) { + SPIhx.Init.CLKPhase = SPI_PHASE_1EDGE; + changed = true; + } + } + else { + if (SPIhx.Init.CLKPhase != SPI_PHASE_2EDGE) { + SPIhx.Init.CLKPhase = SPI_PHASE_2EDGE; + changed = true; + } + } + + return changed; + } + + struct spi_monitored_loop + { + private: +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; +#endif + public: + inline spi_monitored_loop() { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); +#endif + } + inline void update(unsigned int beep_code) { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + }; + + static void _spiOnError(unsigned int beep_code = 0) { + for (;;) { +#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + } + +#if !ENABLED(HAL_SPI_SUPPORTS_ASYNC) + static bool _spi_debug_inside_transaction = false; +#endif + + static void _SPI_Enter( SPI_TypeDef *instance ) { +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + spi_monitored_loop lw; + // During testing, this loop did take longer than 1 second on the + // MKS Robin E3D V1.1 (rarely). + while (_spi_busy) { lw.update(12); } + _spi_busy = true; +#else + if (_spi_debug_inside_transaction) + _spiOnError(11); + _spi_debug_inside_transaction = true; +#endif + } + + static void _SPI_Leave( SPI_TypeDef *instance ) { +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + _spi_busy = false; +#else + if (!_spi_debug_inside_transaction) + _spiOnError(12); + _spi_debug_inside_transaction = false; +#endif + } + + static void _SPI_AsyncBarrier() { +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + // Wait until any currently configured transfer has finished. + spi_monitored_loop lw; + while (spiInfo->async_busy) { lw.update(10); } +#endif + } + + void spiBegin() { + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + +#if !(defined(STM32F1xx) || defined(STM32F4xx)) + memset(&SPIhx, 0, sizeof(SPIhx)); +#endif + //SPIhx.Instance = spiInstance; + SPIhx.State = HAL_SPI_STATE_RESET; + SPIhx.Init.NSS = SPI_NSS_SOFT; + SPIhx.Init.Mode = SPI_MODE_MASTER; + //SPIhx.Init.Direction = (TFT_MISO_PIN != NC && TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; + //SPIhx.Init.BaudRatePrescaler = clkdiv; + //SPIhx.Init.CLKPhase = SPI_PHASE_1EDGE; + //SPIhx.Init.CLKPolarity = SPI_POLARITY_LOW; + _HAL_SPI_InitClock(SPI_CLKMODE_DEFAULT); + //SPIhx.Init.DataSize = SPI_DATASIZE_8BIT; + SPIhx.Init.FirstBit = SPI_FIRSTBIT_MSB; // default. + SPIhx.Init.TIMode = SPI_TIMODE_DISABLE; + SPIhx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; + SPIhx.Init.CRCPolynomial = 10; + +#if !(defined(STM32F1xx) || defined(STM32F4xx)) + memset(&DMAhx, 0, sizeof(DMAhx)); +#endif + DMAhx.Init.Direction = DMA_MEMORY_TO_PERIPH; // target is SPI bus. + //DMAhx.Init.MemInc = DMA_MINC_ENABLE; + DMAhx.Init.PeriphInc = DMA_PINC_DISABLE; + //DMAhx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; + //DMAhx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; + DMAhx.Init.Mode = DMA_NORMAL; + DMAhx.Init.Priority = DMA_PRIORITY_LOW; + #ifdef STM32F4xx + DMAhx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + #endif + } + + static void _HAL_SPI_Prepare(void) { + auto name_sck_pin = digitalPinToPinName(_spi_pin_sck); + + pinmap_pinout(name_sck_pin, PinMap_SPI_SCLK); + pinmap_pinout(digitalPinToPinName(_spi_pin_mosi), PinMap_SPI_MOSI); + if (_spi_pin_miso != NC && _spi_pin_miso != _spi_pin_mosi) { + pinmap_pinout(digitalPinToPinName(_spi_pin_miso), PinMap_SPI_MISO); + } + //pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_SPI_SSEL); + + pin_PullConfig(get_GPIO_Port(STM_PORT(name_sck_pin)), STM_LL_GPIO_PIN(name_sck_pin), GPIO_PULLDOWN); + + // See page 282 of the STM32F1xx manual (DMA1). + + #ifdef SPI1_BASE + if (SPIhx.Instance == SPI1) { + __HAL_RCC_SPI1_CLK_ENABLE(); + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); + #ifdef STM32F1xx + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + // See page 204 of the STM32F1xx manual (interrupt table). + nvicSetIRQHandler(DMA1_Channel3_IRQn, _DMA_Interrupt); + nvicInstallRedirect(); + NVIC_DMA_Interrupt_Enable(DMA1, 3); + #endif + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAhx.Instance = DMA1_Channel3; + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAhx.Instance = DMA2_Stream3; + DMAhx.Init.Channel = DMA_CHANNEL_3; + #endif + } + #endif + + #ifdef SPI2_BASE + if (SPIhx.Instance == SPI2) { + __HAL_RCC_SPI2_CLK_ENABLE(); + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); + #ifdef STM32F1xx + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + // See page 204 of the STM32F1xx manual (interrupt table). + nvicSetIRQHandler(DMA1_Channel5_IRQn, _DMA_Interrupt); + nvicInstallRedirect(); + NVIC_DMA_Interrupt_Enable(DMA1, 5); + #endif + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAhx.Instance = DMA1_Channel5; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAhx.Instance = DMA1_Stream4; + DMAhx.Init.Channel = DMA_CHANNEL_0; + #endif + } + #endif + + #ifdef SPI3_BASE + if (SPIhx.Instance == SPI3) { + __HAL_RCC_SPI3_CLK_ENABLE(); + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); + #ifdef STM32F1xx + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + // See page 204 of the STM32F1xx manual (interrupt table). + nvicSetIRQHandler(DMA2_Channel2_IRQn, _DMA_Interrupt); + nvicInstallRedirect(); + NVIC_DMA_Interrupt_Enable(DMA2, 2); + #endif + __HAL_RCC_DMA2_CLK_ENABLE(); + DMAhx.Instance = DMA2_Channel2; + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_ENABLE(); + DMAhx.Instance = DMA1_Stream5; + DMAhx.Init.Channel = DMA_CHANNEL_0; + #endif + } + #endif + + // TODO: there may be more than 4 SPI instances; take a look into remaining reference + // manuals to see which ones can be enabled aswell. + } + + static void _HAL_SPI_Dismantle(void) { + #ifdef SPI1_BASE + if (SPIhx.Instance == SPI1) { + __HAL_RCC_SPI1_FORCE_RESET(); + __HAL_RCC_SPI1_RELEASE_RESET(); + __HAL_RCC_SPI1_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_DISABLE(); + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + NVIC_DMA_Interrupt_Disable(DMA1, 3); + // Restore the interrupt table entry. + nvicUninstallRedirect(); + #endif + #elif defined(STM32F4xx) + __HAL_RCC_DMA2_CLK_DISABLE(); + #endif + } + #endif + + #ifdef SPI2_BASE + if (SPIhx.Instance == SPI2) { + __HAL_RCC_SPI2_FORCE_RESET(); + __HAL_RCC_SPI2_RELEASE_RESET(); + __HAL_RCC_SPI2_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA1_CLK_DISABLE(); + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + NVIC_DMA_Interrupt_Disable(DMA1, 5); + // Restore the interrupt table entry. + nvicUninstallRedirect(); + #endif + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_DISABLE(); + #endif + } + #endif + + #ifdef SPI3_BASE + if (SPIhx.Instance == SPI3) { + __HAL_RCC_SPI3_FORCE_RESET(); + __HAL_RCC_SPI3_RELEASE_RESET(); + __HAL_RCC_SPI3_CLK_DISABLE(); + #ifdef STM32F1xx + __HAL_RCC_DMA2_CLK_DISABLE(); + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + NVIC_DMA_Interrupt_Disable(DMA2, 2); + // Restore the interrupt table entry. + nvicUninstallRedirect(); + #endif + #elif defined(STM32F4xx) + __HAL_RCC_DMA1_CLK_DISABLE(); + #endif + } + #endif + } + + static void __HAL_SPI_ConfigDirection() { + if (_spi_pin_miso == NC) + SPI_1LINE_TX(&SPIhx); + else if (_spi_pin_mosi == NC) + SPI_1LINE_RX(&SPIhx); + } + + static void _spiSecureCSEnter() { + if (_spi_pin_cs != NC) { + WRITE(_spi_pin_cs, HIGH); + } + } + + static void _spiSecureCSLeave() { + if (_spi_pin_cs != NC) { + WRITE(_spi_pin_cs, LOW); + } + } + + static bool _spi_is_transmit_sequence_initialized = false; + + static void _spiSecureShutdown() { + _SPI_AsyncBarrier(); + + if (_spi_is_transmit_sequence_initialized) { + // Wait atleast until the hardware has accepted our transmission data item. + // Then we know that the BSY flag is valid. + spi_monitored_loop lw; + while (!__HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_TXE)) { lw.update(1); } + } + + spi_monitored_loop lw; + while ( __HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_BSY)) { lw.update(2); } + + _spiSecureCSEnter(); + + __HAL_SPI_DISABLE(&SPIhx); + + // Same status as just calling _spiSecureCSEnter. + } + + static bool _spi_is_initialized = false; + + static void _HAL_SPI_UpdateTransaction(uint16_t dataSize) { + bool requires_spi_reboot = false; + + if (_spi_is_initialized == false) { + SPIhx.Init.DataSize = dataSize; + HAL_SPI_Init(&SPIhx); + _spi_is_initialized = true; + requires_spi_reboot = true; + } + else if (SPIhx.Init.DataSize != dataSize) { + _spiSecureShutdown(); + HAL_SPI_DeInit(&SPIhx); + SPIhx.Init.DataSize = dataSize; + HAL_SPI_Init(&SPIhx); + requires_spi_reboot = true; + } + + if (requires_spi_reboot) { + __HAL_SPI_ConfigDirection(); + __HAL_SPI_ENABLE(&SPIhx); + + _spi_is_transmit_sequence_initialized = false; + + _spiSecureCSLeave(); + } + } + + static void _HAL_SPI_EndOfTransaction() { + if (_spi_is_initialized) { + HAL_SPI_DeInit(&SPIhx); + _spi_is_initialized = false; + } + } + + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + int use_pin_sck, use_pin_miso, use_pin_mosi, use_pin_cs; + if (hint_sck != NC && hint_mosi != NC) + { + use_pin_sck = hint_sck; + use_pin_miso = hint_miso; + use_pin_mosi = hint_mosi; + } + else + { + use_pin_sck = SD_SCK_PIN; + use_pin_miso = SD_MISO_PIN; + use_pin_mosi = SD_MOSI_PIN; + } + use_pin_cs = hint_cs; + + PinName name_sck_pin = digitalPinToPinName(use_pin_sck); + + SPI_TypeDef *spiInstance = (SPI_TypeDef*)pinmap_peripheral(name_sck_pin, PinMap_SPI_SCLK); + + if (spiInstance != pinmap_peripheral(digitalPinToPinName(use_pin_mosi), PinMap_SPI_MOSI)) + _spiOnError(); + if (use_pin_miso != NC && spiInstance != pinmap_peripheral(digitalPinToPinName(use_pin_miso), PinMap_SPI_MISO)) + _spiOnError(); + + // Barrier. + _SPI_Enter( spiInstance ); + + _spi_pin_sck = use_pin_sck; + _spi_pin_miso = use_pin_miso; + _spi_pin_mosi = use_pin_mosi; + _spi_pin_cs = use_pin_cs; + + SPIhx.Instance = spiInstance; + + // chip-select is assumed to be handled by the software to be LOW during operations (if passed as -1 to spiInitEx) + // the pin is being adjusted to HIGH when SPI is doing critical maintenance operations + // (changing frame width, bit-ordering, etc). + + SPIhx.Init.Direction = (_spi_pin_miso == NC || _spi_pin_mosi == NC) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; + + uint8_t clkdiv; + if (maxClockFreq > 0) { + spi_t tmp_spi; + tmp_spi.pin_sclk = name_sck_pin; + uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); + clkdiv = _HAL_GetClockDivider( spibasefreq, maxClockFreq ); + } + else + { + bool has_clkdiv = false; + +#ifdef SPI1_BASE + if (spiInstance == SPI1) + { + clkdiv = SPI_BAUDRATEPRESCALER_4; + has_clkdiv = true; + } +#endif + + if (!has_clkdiv) + { + clkdiv = SPI_BAUDRATEPRESCALER_2; + } + } + + SPIhx.Init.BaudRatePrescaler = clkdiv; + + _HAL_SPI_Prepare(); + + _spi_is_initialized = false; + _spi_is_transmit_sequence_initialized = false; + } + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + void spiClose() { + // Shutdown the SPI peripheral. + _spiSecureShutdown(); + + // Close down hardware-related resources. + _HAL_SPI_EndOfTransaction(); + _HAL_SPI_Dismantle(); + _SPI_Leave( SPIhx.Instance ); + } + + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + if (SPIhx.Init.FirstBit == SPI_FIRSTBIT_MSB) return; + SPIhx.Init.FirstBit = SPI_FIRSTBIT_MSB; + } + else if (bitOrder == SPI_BITORDER_LSB) { + if (SPIhx.Init.FirstBit == SPI_FIRSTBIT_LSB) return; + SPIhx.Init.FirstBit = SPI_FIRSTBIT_LSB; + } + + // If the SPI is already enabled, then update it. + // When the SPI is initialized, the chip-select must be high aswell. + if (_spi_is_initialized) + { + _spiSecureShutdown(); + + auto tmp_SPI_CR1 = SPIhx.Instance->CR1; + + if (bitOrder == SPI_BITORDER_MSB) + tmp_SPI_CR1 &= ~_BV(7); + else + tmp_SPI_CR1 |= _BV(7); + + SPIhx.Instance->CR1 = tmp_SPI_CR1; + + __HAL_SPI_ConfigDirection(); + __HAL_SPI_ENABLE(&SPIhx); + + _spi_is_transmit_sequence_initialized = false; + + _spiSecureCSLeave(); + } + } + + void spiSetClockMode(int mode) { + bool changed = _HAL_SPI_InitClock(mode); + + if (!changed) return; + + if (_spi_is_initialized) { + _spiSecureShutdown(); + + auto tmp_SPI_CR1 = SPIhx.Instance->CR1; + + if (mode == SPI_CLKMODE_0) { + tmp_SPI_CR1 &= ~0x03; + } + else if (mode == SPI_CLKMODE_1) { + tmp_SPI_CR1 &= ~0x02; + tmp_SPI_CR1 |= 0x01; + } + else if (mode == SPI_CLKMODE_2) { + tmp_SPI_CR1 &= ~0x01; + tmp_SPI_CR1 |= 0x02; + } + else if (mode == SPI_CLKMODE_3) { + tmp_SPI_CR1 |= 0x03; + } + + SPIhx.Instance->CR1 = tmp_SPI_CR1; + + __HAL_SPI_ConfigDirection(); + __HAL_SPI_ENABLE(&SPIhx); + + _spi_is_transmit_sequence_initialized = false; + + _spiSecureCSLeave(); + } + } + +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + static void _DMA_Interrupt( void ) + { + DMA_TypeDef *DMA = DMAhx.DmaBaseAddress; + uint32_t channelIndex = ((DMAhx.ChannelIndex>>2)+1); + + // DMA completed successfully? + if (DMA_Channel_TXComplete(DMA, channelIndex)) { + + // Reset TCIF. + DMA_Channel_ResetTXComplete(DMA, channelIndex); + + // Disable the TX Complete interrupt. + DMA_Channel_TXCompleteInterruptSet(DMAhx.Instance, false); + + auto cb = DMAhx.XferCpltCallback; + + // Terminate the peripherals. + HAL_DMA_DeInit( &DMAhx ); + + // Wait until the SPI is finished. + spi_monitored_loop lw; + while ( __HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_BSY)) { lw.update(3); } + + __HAL_SPI_CLEAR_OVRFLAG(&SPIhx); + + auto *info = SPI_GetRuntimeInfo( SPIhx.Instance ); + info->async_busy = false; + + // Execute any transfer-complete callback. + if (cb) + { + cb( &DMAhx ); + } + } + // Error during transfer? + else if (DMA_Channel_TXError(DMA, channelIndex)) { + + // Reset TEIF. + DMA_Channel_ResetTXError(DMA, channelIndex); + + // Disable the TX error interrupt. + DMA_Channel_TXErrorInterruptSet(DMAhx.Instance, false); + + // Terminate the peripherals. + HAL_DMA_DeInit( &DMAhx ); + + _HAL_SPI_Dismantle(); + + auto *info = SPI_GetRuntimeInfo( SPIhx.Instance ); + info->async_busy = false; + } + } +#endif + + static void _HAL_SPI_CheckTransactionalError() { + if (TEST(SPIhx.Instance->SR, 3)) { + // Underrun. + _spiOnError(1); + } + if (TEST(SPIhx.Instance->SR, 4)) { + // CRC error. + _spiOnError(2); + } + if (TEST(SPIhx.Instance->SR, 5)) { + // Mode fault. + _spiOnError(3); + } + if (TEST(SPIhx.Instance->SR, 6)) { + // Overrun. + _spiOnError(4); + } + if (TEST(SPIhx.Instance->CR1, 6) == false) { + // SPI disabled??? + _spiOnError(10); + } + } + + // Operates in both 8bit and 16bit modes. + template + static void _HAL_SPI_TransmitOnly(transmitType val) { + + __IO transmitType *DR = (__IO transmitType*)&SPIhx.Instance->DR; + + if (_spi_is_transmit_sequence_initialized) + { + spi_monitored_loop lw; + while (!__HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_TXE)) { lw.update(4); } + } + + *DR = val; + + _spi_is_transmit_sequence_initialized = true; + } + + template + static void _HAL_SPI_Transmit(transmitType val) { + _HAL_SPI_TransmitOnly ( val ); + +#ifndef SPI_ENABLE_OPTIMIZATIONS + // Perform the regular transactional pattern. + if (SPIhx.Init.Direction == SPI_DIRECTION_2LINES) { + __IO transmitType *DR = (__IO transmitType*)&SPIhx.Instance->DR; + + spi_monitored_loop lw; + while (!__HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_RXNE)) { lw.update(5); } + + transmitType tmp = *DR; + (void)tmp; + } +#else + // Do some OVRFLAG stuff that is regularly found on the internet. + if (SPIhx.Init.Direction == SPI_DIRECTION_2LINES) + __HAL_SPI_CLEAR_OVRFLAG(&SPIhx); // Clear overrun flag in 2 Lines communication mode because received data is not read +#endif + + _HAL_SPI_CheckTransactionalError(); + } + + template + static transmitType _HAL_SPI_Receive(transmitType txval) { + + __IO transmitType *DR = (__IO transmitType*)&SPIhx.Instance->DR; + + if (SPIhx.Init.Direction == SPI_DIRECTION_2LINES) + { + _HAL_SPI_TransmitOnly ( txval ); + } + + spi_monitored_loop lw; + while (!__HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_RXNE)) { lw.update(6); } + + transmitType result = *DR; + + _HAL_SPI_CheckTransactionalError(); + + return result; + } + + void spiSend(uint8_t b) { + if (_spi_pin_mosi == NC) return; + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + _HAL_SPI_Transmit (b); + } + + void spiSend16(uint16_t v) { + if (_spi_pin_mosi == NC) return; + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_16BIT); + _HAL_SPI_Transmit (v); + } + + uint8_t spiRec(uint8_t txval) { + if (_spi_pin_miso == NC) return 0; + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + uint8_t res = _HAL_SPI_Receive (txval); + return res; + } + + uint16_t spiRec16(uint16_t txval) { + if (_spi_pin_miso == NC) return 0; + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_16BIT); + uint16_t res = _HAL_SPI_Receive (txval); + return res; + } + + void spiRead(uint8_t *buf, uint16_t bufsize, uint8_t txval) { + if (_spi_pin_miso == NC) { + memset(buf, 0, bufsize); + } + else { + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + for (uint16_t n = 0; n < bufsize; n++) + buf[n] = _HAL_SPI_Receive (txval); + } + } + + void spiSendBlock(uint8_t token, const uint8_t *block) { + if (_spi_pin_mosi == NC) return; + _SPI_AsyncBarrier(); + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + _HAL_SPI_Transmit (token); + for (uint16_t n = 0; n < 512; n++) + _HAL_SPI_Transmit ( block[n] ); + } + + static void _HAL_DMA_ConfigureTransfer( bool memInc, uint16_t dataSize ) { + DMAhx.Init.MemInc = ( memInc ? DMA_MINC_ENABLE : DMA_MINC_DISABLE ); // if true send one number many times, else an array. + DMAhx.Init.PeriphDataAlignment = (dataSize == SPI_DATASIZE_8BIT) ? DMA_PDATAALIGN_BYTE : DMA_PDATAALIGN_HALFWORD; + DMAhx.Init.MemDataAlignment = (dataSize == SPI_DATASIZE_8BIT) ? DMA_MDATAALIGN_BYTE : DMA_MDATAALIGN_HALFWORD; + HAL_DMA_Init(&DMAhx); + } + + // Blocking. + static void _HAL_DMA_Transfer( const void *buf, uint32_t bufcnt, bool memInc, uint16_t dataSize ) { + _HAL_SPI_UpdateTransaction(dataSize); + + _HAL_DMA_ConfigureTransfer(memInc, dataSize); + + HAL_DMA_Start(&DMAhx, (uint32_t)buf, (uint32_t)&(SPIhx.Instance->DR), bufcnt); + + SET_BIT(SPIhx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + + HAL_DMA_PollForTransfer(&DMAhx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); + + HAL_DMA_DeInit(&DMAhx); + + spi_monitored_loop lw; + while ( __HAL_SPI_GET_FLAG(&SPIhx, SPI_FLAG_BSY)) { lw.update(8); } + + // Since we have only transmitted data it is sure that we got the OVRFLAG. + // Thus clear it. + if (SPIhx.Init.Direction == SPI_DIRECTION_2LINES && TEST(SPIhx.Instance->SR, 6)) + __HAL_SPI_CLEAR_OVRFLAG(&SPIhx); + + _spi_is_transmit_sequence_initialized = true; + } + + void spiWrite(const uint8_t *buf, uint16_t bufcnt) { + if (_spi_pin_mosi == NC) return; + if (bufcnt == 0) return; + _SPI_AsyncBarrier(); + _HAL_DMA_Transfer( buf, bufcnt, true, SPI_DATASIZE_8BIT ); + } + + void spiWrite16(const uint16_t *buf, uint16_t bufcnt) { + if (_spi_pin_mosi == NC) return; + if (bufcnt == 0) return; + _SPI_AsyncBarrier(); + _HAL_DMA_Transfer( buf, bufcnt, true, SPI_DATASIZE_16BIT ); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + if (_spi_pin_mosi == NC) return; + if (repcnt == 0) return; + _SPI_AsyncBarrier(); + // If async then we would need a static variable here. + _HAL_DMA_Transfer( &val, repcnt, false, SPI_DATASIZE_8BIT ); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + if (_spi_pin_mosi == NC) return; + if (repcnt == 0) return; + _SPI_AsyncBarrier(); + // If async then we would need a static variable here. + _HAL_DMA_Transfer( &val, repcnt, false, SPI_DATASIZE_16BIT ); + } + +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + + static void _DMA_CompleteCallback( DMA_HandleTypeDef *_ ) { + + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + if (auto *cb = spiInfo->asyncCompleteCallback) { + cb( spiInfo->async_ud ); + } + } + + void spiWriteAsync(const uint8_t *buf, uint16_t nbyte, void (*completeCallback)(void*), void *ud) { + + if (_spi_pin_mosi == NC) return; + + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + _SPI_AsyncBarrier(); + spiInfo->async_busy = true; + + spiInfo->asyncCompleteCallback = completeCallback; + spiInfo->async_ud = ud; + + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + DMAhx.XferCpltCallback = _DMA_CompleteCallback; + _HAL_DMA_ConfigureTransfer(true, SPI_DATASIZE_8BIT); + + HAL_DMA_Start_IT(&DMAhx, (uint32_t)buf, (uint32_t)&(SPIhx.Instance->DR), nbyte); + + SET_BIT(SPIhx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + + if (nbyte > 0) + _spi_is_transmit_sequence_initialized = true; + } + + void spiWriteAsync16(const uint16_t *buf, uint16_t ndata, void (*completeCallback)(void*), void *ud) { + + if (_spi_pin_mosi == NC) return; + + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + _SPI_AsyncBarrier(); + spiInfo->async_busy = true; + + spiInfo->asyncCompleteCallback = completeCallback; + spiInfo->async_ud = ud; + + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_16BIT); + DMAhx.XferCpltCallback = _DMA_CompleteCallback; + _HAL_DMA_ConfigureTransfer(true, SPI_DATASIZE_16BIT); + + HAL_DMA_Start_IT(&DMAhx, (uint32_t)buf, (uint32_t)&(SPIhx.Instance->DR), ndata); + + SET_BIT(SPIhx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request + + if (ndata > 0) + _spi_is_transmit_sequence_initialized = true; + } + + void spiAsyncAbort() { + + cli(); + + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + if (spiInfo->async_busy) + { + HAL_DMA_Abort(&DMAhx); + HAL_DMA_DeInit(&DMAhx); + + sei(); + + spiInfo->async_busy = false; + } + else + sei(); + } + + void spiAsyncJoin() { + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + spi_monitored_loop lw; + while (spiInfo->async_busy) { lw.update(11); } + } + + bool spiAsyncIsRunning() { + auto *spiInfo = SPI_GetRuntimeInfo(SPIhx.Instance); + + return spiInfo->async_busy; + } + +#endif // HAL_SPI_SUPPORTS_ASYNC + + // DMA async semantics are actually really dangerous, here is why: + // - you need to wait for DMA transfers to finish, which devs might forget + // - it is invalid to reuse the memory while DMA is operating on it, which devs might forget + // Thus code depending on DMA needs very special attention to get it right. + +#endif + +#endif // HAL_STM32 \ No newline at end of file diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp new file mode 100644 index 000000000000..566c98890343 --- /dev/null +++ b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp @@ -0,0 +1,202 @@ +/** + * 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 + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfig.h" + +// ------------------------ +// Public functions +// ------------------------ + + // If properly ported, use fast HW SPI implementation originally found in STM32 tft_spi.cpp +#if !ENABLED(SOFTWARE_SPI) && (!(defined(STM32F1xx) || defined(STM32F4xx)) || ENABLED(HALSPI_HW_GENERIC)) + + #include + + /** + * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz + */ + + static SPISettings spiConfig; + + /** + * @brief Begin SPI port setup + * + * @return Nothing + * + * @details Only configures SS pin since stm32duino creates and initialize the SPI object + */ + void spiBegin() { + #if PIN_EXISTS(SD_SS) + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + } + + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + _spi_clock = maxClockFreq; + spiConfig = SPISettings(maxClockFreq, MSBFIRST, SPI_MODE0); + + SPI.setMISO((hint_miso != -1) ? hint_miso : SD_MISO_PIN); + SPI.setMOSI((hint_mosi != -1) ? hint_mosi : SD_MOSI_PIN); + SPI.setSCLK((hint_sck != -1) ? hint_sck : SD_SCK_PIN); + + SPI.begin(); + SPI.beginTransaction(spiConfig); + } + + // Configure SPI for specified SPI speed + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Ignore chip-select because the software manages it already. + + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + void spiClose() { + // Terminates SPI activity. + SPI.endTransaction(); + SPI.end(); + } + + void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + SPI.setBitOrder(MSBFIRST); + } + else if (bitOrder == SPI_BITORDER_LSB) { + SPI.setBitOrder(LSBFIRST); + } + } + + void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + SPI.setDataMode(SPI_MODE0); + else if (clockMode == SPI_CLKMODE_1) + SPI.setDataMode(SPI_MODE1); + else if (clockMode == SPI_CLKMODE_2) + SPI.setDataMode(SPI_MODE2); + else if (clockMode == SPI_CLKMODE_3) + SPI.setDataMode(SPI_MODE3); + } + + /** + * @brief Receives a single byte from the SPI port. + * + * @return Byte received + * + * @details + */ + uint8_t spiRec(uint8_t txval) { + uint8_t returnByte = SPI.transfer(txval); + return returnByte; + } + + uint16_t spiRec16(uint16_t txval) { + return SPI.transfer16(txval); + } + + /** + * @brief Receive a number of bytes from the SPI port to a buffer + * + * @param buf Pointer to starting address of buffer to write to. + * @param nbyte Number of bytes to receive. + * @return Nothing + * + * @details Uses DMA + */ + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + if (nbyte == 0) return; + memset(buf, txval, nbyte); + SPI.transfer(buf, nbyte); + } + + /** + * @brief Send a single byte on SPI port + * + * @param b Byte to send + * + * @details + */ + void spiSend(uint8_t b) { + SPI.transfer(b); + } + + void spiSend16(uint16_t v) { + SPI.transfer16(v); + } + + void spiWrite(const uint8_t *buf, uint16_t numbytes) { + void *inout_buf = malloc(numbytes); + if (inout_buf == nullptr) + _spi_on_error(); + memcpy(inout_buf, buf, numbytes); + // Generic transfer, non-DMA. + SPI.transfer(inout_buf, numbytes); + free(inout_buf); + } + + void spiWrite16(const uint16_t *buf, uint16_t numtx) { + for (uint32_t n = 0; n < numbytes; n++) { + SPI.transfer16(buf[n]); + } + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer16(val); + } + + /** + * @brief Write token and then write from 512 byte buffer to SPI (for SD card) + * + * @param buf Pointer with buffer start address + * @return Nothing + * + * @details Use DMA + */ + void spiSendBlock(uint8_t token, const uint8_t *buf) { + uint8_t rxBuf[512]; + SPI.transfer(token); + SPI.transfer((uint8_t*)buf, rxBuf, 512); + } + +#endif // !FAST HW SPI, SOFTWARE_SPI + +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp similarity index 57% rename from Marlin/src/HAL/STM32/HAL_SPI.cpp rename to Marlin/src/HAL/STM32/HAL_SPI_SW.cpp index aac889a7e57d..b7d8cd6b379a 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp @@ -26,24 +26,20 @@ #include "../../inc/MarlinConfig.h" -#include - -// ------------------------ -// Public Variables -// ------------------------ - -static SPISettings spiConfig; - // ------------------------ // Public functions // ------------------------ #if ENABLED(SOFTWARE_SPI) + #include + // ------------------------ // Software SPI // ------------------------ + // TODO: this software SPI is really bad... it tries to use SPI clock-mode 3 only...?????? + #include "../shared/Delay.h" void spiBegin(void) { @@ -59,7 +55,7 @@ static SPISettings spiConfig; // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here #define CALLING_COST_NS (3U * 1000000000U) / (F_CPU) - void (*delaySPIFunc)(); + static void (*delaySPIFunc)(); void delaySPI_125() { DELAY_NS(125 - CALLING_COST_NS); } void delaySPI_250() { DELAY_NS(250 - CALLING_COST_NS); } void delaySPI_500() { DELAY_NS(500 - CALLING_COST_NS); } @@ -67,6 +63,8 @@ static SPISettings spiConfig; void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); } void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); } + static int _spi_bit_order = SPI_BITORDER_DEFAULT; + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Use datarates Marlin uses switch (spiRate) { @@ -86,41 +84,101 @@ static SPISettings spiConfig; SPI.begin(); } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint8_t spiRate; + if (maxClockFreq >= 20000000) { + spiRate = SPI_FULL_SPEED; + } + else if (maxClockFreq >= 5000000) { + spiRate = SPI_HALF_SPEED; + } + else if (maxClockFreq >= 2500000) { + spiRate = SPI_QUARTER_SPEED; + } + else if (maxClockFreq >= 1250000) { + spiRate = SPI_EIGHTH_SPEED; + } + else if (maxClockFreq >= 625000) { + spiRate = SPI_SPEED_5; + } + else if (maxClockFreq >= 300000) { + spiRate = SPI_SPEED_6; + } + else + spiRate = SPI_SPEED_6; + + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); + } + void spiClose() { SPI.end(); } - // Begin SPI transaction, set clock, bit order, data mode - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ } + void spiSetBitOrder(int bitOrder) { + _spi_bit_order = bitOrder; + } + + void spiSetClockMode(int clockMode) { + if (clockMode != SPI_CLKMODE_3) + _spi_on_error(); + } uint8_t HAL_SPI_STM32_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3 - for (uint8_t bits = 8; bits--;) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + uint8_t result = 0; + for (uint8_t bits = 0; bits < 8; bits++) { + int bitidx = ( msb ? 7-bits : bits ); + WRITE(SD_SCK_PIN, LOW); + WRITE(SD_MOSI_PIN, (b & ( 1 << bitidx )) != 0); + + delaySPIFunc(); + WRITE(SD_SCK_PIN, HIGH); + delaySPIFunc(); + + result |= ( (READ(SD_MISO_PIN) != 0) << bitidx ); + } + DELAY_NS(125); + return b; + } + + uint16_t HAL_SPI_STM32_SpiTransfer_Mode_3_16bits(uint16_t v) { // using Mode 3 + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + uint16_t result = 0; + for (uint8_t bits = 0; bits < 16; bits++) { + int bitidx = ( msb ? 15-bits : bits ); WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, b & 0x80); + WRITE(SD_MOSI_PIN, (b & ( 1 << bitidx )) != 0); delaySPIFunc(); WRITE(SD_SCK_PIN, HIGH); delaySPIFunc(); - b <<= 1; // little setup time - b |= (READ(SD_MISO_PIN) != 0); + result |= ( (READ(SD_MISO_PIN) != 0) << bitidx ); } DELAY_NS(125); return b; } // Soft SPI receive byte - uint8_t spiRec() { + uint8_t spiRec(uint8_t txval) { hal.isr_off(); // No interrupts during byte receive - const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF); + const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(txval); hal.isr_on(); // Enable interrupts return data; } + uint16_t spiRec16(uint16_t txval) { + hal.isr_off(); + uint16_t data = HAL_SPI_STM32_SpiTransfer_Mode_3_16bits(txval); + hal.isr_on(); + return data; + } + // Soft SPI read data - void spiRead(uint8_t *buf, uint16_t nbyte) { + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { for (uint16_t i = 0; i < nbyte; i++) - buf[i] = spiRec(); + buf[i] = spiRec(txval); } // Soft SPI send byte @@ -130,6 +188,12 @@ static SPISettings spiConfig; hal.isr_on(); // Enable interrupts } + void spiSend16(uint16_t data) { + hal.isr_off(); + HAL_SPI_STM32_SpiTransfer_Mode_3_16bits(data); + hal.isr_on(); + } + // Soft SPI send block void spiSendBlock(uint8_t token, const uint8_t *buf) { spiSend(token); @@ -137,111 +201,26 @@ static SPISettings spiConfig; spiSend(buf[i]); } -#else - - // ------------------------ - // Hardware SPI - // ------------------------ - - /** - * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz - */ - - /** - * @brief Begin SPI port setup - * - * @return Nothing - * - * @details Only configures SS pin since stm32duino creates and initialize the SPI object - */ - void spiBegin() { - #if PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); - #endif + void spiWrite(const uint8_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); } - // Configure SPI for specified SPI speed - void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - // Ignore chip-select because the software manages it already. - - // Use datarates Marlin uses - uint32_t clock; - switch (spiRate) { - case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 - case SPI_HALF_SPEED: clock = 5000000; break; - case SPI_QUARTER_SPEED: clock = 2500000; break; - case SPI_EIGHTH_SPEED: clock = 1250000; break; - case SPI_SPEED_5: clock = 625000; break; - case SPI_SPEED_6: clock = 300000; break; - default: - clock = 4000000; // Default from the SPI library - } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - - SPI.setMISO(SD_MISO_PIN); - SPI.setMOSI(SD_MOSI_PIN); - SPI.setSCLK(SD_SCK_PIN); - - SPI.beginTransaction(spiConfig); + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); } - void spiClose() { - // Terminates SPI activity. - SPI.end(); + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); } - /** - * @brief Receives a single byte from the SPI port. - * - * @return Byte received - * - * @details - */ - uint8_t spiRec() { - uint8_t returnByte = SPI.transfer(0xFF); - return returnByte; - } - - /** - * @brief Receive a number of bytes from the SPI port to a buffer - * - * @param buf Pointer to starting address of buffer to write to. - * @param nbyte Number of bytes to receive. - * @return Nothing - * - * @details Uses DMA - */ - void spiRead(uint8_t *buf, uint16_t nbyte) { - if (nbyte == 0) return; - memset(buf, 0xFF, nbyte); - SPI.transfer(buf, nbyte); - } - - /** - * @brief Send a single byte on SPI port - * - * @param b Byte to send - * - * @details - */ - void spiSend(uint8_t b) { - SPI.transfer(b); - } - - /** - * @brief Write token and then write from 512 byte buffer to SPI (for SD card) - * - * @param buf Pointer with buffer start address - * @return Nothing - * - * @details Use DMA - */ - void spiSendBlock(uint8_t token, const uint8_t *buf) { - uint8_t rxBuf[512]; - SPI.transfer(token); - SPI.transfer((uint8_t*)buf, &rxBuf, 512); + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); } -#endif // SOFTWARE_SPI +#endif -#endif // HAL_STM32 +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp deleted file mode 100644 index 0c9e107b2d22..000000000000 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ /dev/null @@ -1,178 +0,0 @@ -/** - * 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 . - * - */ - -#include "../platforms.h" - -#if defined(HAL_STM32) && !defined(STM32H7xx) - -#include "MarlinSPI.h" - -static void spi_init(spi_t *obj, uint32_t speed, spi_mode_e mode, uint8_t msb, uint32_t dataSize) { - spi_init(obj, speed, mode, msb); - // spi_init set 8bit always - // TODO: copy the code from spi_init and handle data size, to avoid double init always!! - if (dataSize != SPI_DATASIZE_8BIT) { - obj->handle.Init.DataSize = dataSize; - HAL_SPI_Init(&obj->handle); - __HAL_SPI_ENABLE(&obj->handle); - } -} - -void MarlinSPI::setClockDivider(uint8_t _div) { - _speed = spi_getClkFreq(&_spi);// / _div; - _clockDivider = _div; -} - -void MarlinSPI::begin(void) { - //TODO: only call spi_init if any parameter changed!! - spi_init(&_spi, _speed, _dataMode, _bitOrder, _dataSize); -} - -void MarlinSPI::end(void) { - spi_deinit(&_spi); -} - -void MarlinSPI::setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc) { - _dmaHandle.Init.Direction = direction; - _dmaHandle.Init.PeriphInc = DMA_PINC_DISABLE; - _dmaHandle.Init.Mode = DMA_NORMAL; - _dmaHandle.Init.Priority = DMA_PRIORITY_LOW; - _dmaHandle.Init.MemInc = minc ? DMA_MINC_ENABLE : DMA_MINC_DISABLE; - - if (_dataSize == DATA_SIZE_8BIT) { - _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; - } - else { - _dmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - _dmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; - } - #ifdef STM32F4xx - _dmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - #endif - - // start DMA hardware - // TODO: check if hardware is already enabled - #ifdef SPI1_BASE - if (_spiHandle.Instance == SPI1) { - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel3 : DMA1_Channel2; - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_ENABLE(); - _dmaHandle.Init.Channel = DMA_CHANNEL_3; - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Stream3 : DMA2_Stream0; - #endif - } - #endif - #ifdef SPI2_BASE - if (_spiHandle.Instance == SPI2) { - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Channel5 : DMA1_Channel4; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - _dmaHandle.Init.Channel = DMA_CHANNEL_0; - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream4 : DMA1_Stream3; - #endif - } - #endif - #ifdef SPI3_BASE - if (_spiHandle.Instance == SPI3) { - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_ENABLE(); - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA2_Channel2 : DMA2_Channel1; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - _dmaHandle.Init.Channel = DMA_CHANNEL_0; - _dmaHandle.Instance = (direction == DMA_MEMORY_TO_PERIPH) ? DMA1_Stream5 : DMA1_Stream2; - #endif - } - #endif - - HAL_DMA_Init(&_dmaHandle); -} - -byte MarlinSPI::transfer(uint8_t _data) { - uint8_t rxData = 0xFF; - HAL_SPI_TransmitReceive(&_spi.handle, &_data, &rxData, 1, HAL_MAX_DELAY); - return rxData; -} - -__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx) { SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); } -__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx) { SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); } - -uint8_t MarlinSPI::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) { - const uint8_t ff = 0xFF; - - //if (!LL_SPI_IsEnabled(_spi.handle)) // only enable if disabled - __HAL_SPI_ENABLE(&_spi.handle); - - if (receiveBuf) { - setupDma(_spi.handle, _dmaRx, DMA_PERIPH_TO_MEMORY, true); - HAL_DMA_Start(&_dmaRx, (uint32_t)&(_spi.handle.Instance->DR), (uint32_t)receiveBuf, length); - LL_SPI_EnableDMAReq_RX(_spi.handle.Instance); // Enable Rx DMA Request - } - - // check for 2 lines transfer - bool mincTransmit = true; - if (transmitBuf == nullptr && _spi.handle.Init.Direction == SPI_DIRECTION_2LINES && _spi.handle.Init.Mode == SPI_MODE_MASTER) { - transmitBuf = &ff; - mincTransmit = false; - } - - if (transmitBuf) { - setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, mincTransmit); - HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); - LL_SPI_EnableDMAReq_TX(_spi.handle.Instance); // Enable Tx DMA Request - } - - if (transmitBuf) { - HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - HAL_DMA_Abort(&_dmaTx); - HAL_DMA_DeInit(&_dmaTx); - } - - // while ((_spi.handle.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} - - if (receiveBuf) { - HAL_DMA_PollForTransfer(&_dmaRx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - HAL_DMA_Abort(&_dmaRx); - HAL_DMA_DeInit(&_dmaRx); - } - - return 1; -} - -uint8_t MarlinSPI::dmaSend(const void * transmitBuf, uint16_t length, bool minc) { - setupDma(_spi.handle, _dmaTx, DMA_MEMORY_TO_PERIPH, minc); - HAL_DMA_Start(&_dmaTx, (uint32_t)transmitBuf, (uint32_t)&(_spi.handle.Instance->DR), length); - __HAL_SPI_ENABLE(&_spi.handle); - LL_SPI_EnableDMAReq_TX(_spi.handle.Instance); // Enable Tx DMA Request - HAL_DMA_PollForTransfer(&_dmaTx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - HAL_DMA_Abort(&_dmaTx); - // DeInit objects - HAL_DMA_DeInit(&_dmaTx); - return 1; -} - -#endif // HAL_STM32 && !STM32H7xx diff --git a/Marlin/src/HAL/STM32/MarlinSPI.h b/Marlin/src/HAL/STM32/MarlinSPI.h deleted file mode 100644 index 81430eff2be8..000000000000 --- a/Marlin/src/HAL/STM32/MarlinSPI.h +++ /dev/null @@ -1,107 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "HAL.h" -#include - -extern "C" { - #include -} - -/** - * Marlin currently requires 3 SPI classes: - * - * SPIClass: - * This class is normally provided by frameworks and has a semi-default interface. - * This is needed because some libraries reference it globally. - * - * SPISettings: - * Container for SPI configs for SPIClass. As above, libraries may reference it globally. - * - * These two classes are often provided by frameworks so we cannot extend them to add - * useful methods for Marlin. - * - * MarlinSPI: - * Provides the default SPIClass interface plus some Marlin goodies such as a simplified - * interface for SPI DMA transfer. - * - */ - -#define DATA_SIZE_8BIT SPI_DATASIZE_8BIT -#define DATA_SIZE_16BIT SPI_DATASIZE_16BIT - -class MarlinSPI { -public: - MarlinSPI() : MarlinSPI(NC, NC, NC, NC) {} - - MarlinSPI(pin_t mosi, pin_t miso, pin_t sclk, pin_t ssel = (pin_t)NC) : _mosiPin(mosi), _misoPin(miso), _sckPin(sclk), _ssPin(ssel) { - _spi.pin_miso = digitalPinToPinName(_misoPin); - _spi.pin_mosi = digitalPinToPinName(_mosiPin); - _spi.pin_sclk = digitalPinToPinName(_sckPin); - _spi.pin_ssel = digitalPinToPinName(_ssPin); - _dataSize = DATA_SIZE_8BIT; - _bitOrder = MSBFIRST; - _dataMode = SPI_MODE_0; - _spi.handle.State = HAL_SPI_STATE_RESET; - setClockDivider(SPI_SPEED_CLOCK_DIV2_MHZ); - } - - void begin(void); - void end(void); - - byte transfer(uint8_t _data); - uint8_t dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length); - uint8_t dmaSend(const void * transmitBuf, uint16_t length, bool minc = true); - - /* These methods are deprecated and kept for compatibility. - * Use SPISettings with SPI.beginTransaction() to configure SPI parameters. - */ - void setBitOrder(BitOrder _order) { _bitOrder = _order; } - - void setDataMode(uint8_t _mode) { - switch (_mode) { - case SPI_MODE0: _dataMode = SPI_MODE_0; break; - case SPI_MODE1: _dataMode = SPI_MODE_1; break; - case SPI_MODE2: _dataMode = SPI_MODE_2; break; - case SPI_MODE3: _dataMode = SPI_MODE_3; break; - } - } - - void setClockDivider(uint8_t _div); - -private: - void setupDma(SPI_HandleTypeDef &_spiHandle, DMA_HandleTypeDef &_dmaHandle, uint32_t direction, bool minc = false); - - spi_t _spi; - DMA_HandleTypeDef _dmaTx; - DMA_HandleTypeDef _dmaRx; - BitOrder _bitOrder; - spi_mode_e _dataMode; - uint8_t _clockDivider; - uint32_t _speed; - uint32_t _dataSize; - pin_t _mosiPin; - pin_t _misoPin; - pin_t _sckPin; - pin_t _ssPin; -}; diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index 3df982e48b8e..0630712086d1 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -71,7 +71,7 @@ void TFT_FSMC::Init() { Timing.DataLatency = 17; Timing.AccessMode = FSMC_ACCESS_MODE_A; // Write Timing - // Can be decreases from 8-15-8 to 0-0-1 with risk of stability loss + // Can be decreased from 8-15-8 to 0-0-1 with risk of stability loss ExtTiming.AddressSetupTime = 8; ExtTiming.AddressHoldTime = 15; ExtTiming.DataSetupTime = 8; diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.h b/Marlin/src/HAL/STM32/tft/tft_fsmc.h index 2200abaa10e8..6e0df8b0d2e9 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.h +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.h @@ -38,8 +38,6 @@ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) #endif -#define DATASIZE_8BIT SPI_DATASIZE_8BIT -#define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_FSMC #define TFT_DATASIZE TERN(TFT_INTERFACE_FSMC_8BIT, DATASIZE_8BIT, DATASIZE_16BIT) @@ -67,7 +65,7 @@ class TFT_FSMC { static bool isBusy(); static void Abort() { __HAL_DMA_DISABLE(&DMAtx); } - static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} + static void DataTransferBegin() {} static void DataTransferEnd() {}; static void WriteData(uint16_t Data) { Transmit(tft_data_t(Data)); } @@ -78,7 +76,7 @@ class TFT_FSMC { 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); + TransmitDMA(DMA_PINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; } } diff --git a/Marlin/src/HAL/STM32/tft/tft_ltdc.h b/Marlin/src/HAL/STM32/tft/tft_ltdc.h index 7b63d6929b31..9f589220f855 100644 --- a/Marlin/src/HAL/STM32/tft/tft_ltdc.h +++ b/Marlin/src/HAL/STM32/tft/tft_ltdc.h @@ -29,8 +29,6 @@ #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 @@ -57,8 +55,8 @@ class TFT_LTDC { static bool isBusy(); static void Abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ } - static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {} - static void DataTransferEnd() {}; + static void DataTransferBegin() {} + static void DataTransferEnd() {} static void WriteData(uint16_t Data); static void WriteReg(uint16_t Reg); @@ -68,7 +66,7 @@ class TFT_LTDC { 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); + TransmitDMA(DMA_PINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; } } diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp deleted file mode 100644 index ba9016cfc18a..000000000000 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ /dev/null @@ -1,506 +0,0 @@ -/** - * 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 . - * - */ - -#include "../../platforms.h" - -#ifdef HAL_STM32 - -#include "../../../inc/MarlinConfig.h" - -#if HAS_SPI_TFT - -#include "tft_spi.h" -#include "pinconfig.h" - -SPI_HandleTypeDef TFT_SPI::SPIx; -DMA_HandleTypeDef TFT_SPI::DMAtx; - -uint8_t TFT_SPI::clkdiv_write; -#if PIN_EXISTS(TFT_MISO) -uint8_t TFT_SPI::clkdiv_read; -#endif - -bool TFT_SPI::active_transfer; -bool TFT_SPI::active_dma; - -uint8_t TFT_SPI::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) -{ - if ( speed >= (spibasefreq / 2) ) - { - return SPI_BAUDRATEPRESCALER_2; - } - else if ( speed >= (spibasefreq / 4) ) - { - return SPI_BAUDRATEPRESCALER_4; - } - else if ( speed >= (spibasefreq / 8) ) - { - return SPI_BAUDRATEPRESCALER_8; - } - else if ( speed >= (spibasefreq / 16) ) - { - return SPI_BAUDRATEPRESCALER_16; - } - else if ( speed >= (spibasefreq / 32) ) - { - return SPI_BAUDRATEPRESCALER_32; - } - else if ( speed >= (spibasefreq / 64) ) - { - return SPI_BAUDRATEPRESCALER_64; - } - else if ( speed >= (spibasefreq / 128) ) - { - return SPI_BAUDRATEPRESCALER_128; - } - else - { - return SPI_BAUDRATEPRESCALER_256; - } -} - -extern "C" { - #include -} - -void TFT_SPI::Init() { - - SPI_TypeDef *spiInstance; - - OUT_WRITE(TFT_A0_PIN, HIGH); - OUT_WRITE(TFT_CS_PIN, HIGH); - - if ((spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK)) == NP) return; - - if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI)) return; - - #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN - if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO)) return; - #endif - - // SPI can have different baudrates depending on read or write functionality. - -#if PIN_EXISTS(TFT_MISO) - // static clkdiv_read variable. - bool has_clkdiv_read = false; -#endif - // static clkdiv_write variable. - bool has_clkdiv_write = false; - -#if (PIN_EXISTS(TFT_MISO) && defined(TFT_BAUDRATE_READ)) || defined(TFT_BAURDATE_WRITE) - spi_t tmp_spi; - tmp_spi.pin_sclk = digitalPinToPinName(TFT_SCK_PIN); - uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); - -#if PIN_EXISTS(TFT_MISO) && TFT_BAUDRATE_READ - clkdiv_read = _GetClockDivider(spibasefreq, TFT_BAUDRATE_READ); - has_clkdiv_read = true; -#endif - -#ifdef TFT_BAUDRATE_WRITE - clkdiv_write = _GetClockDivider(spibasefreq, TFT_BAUDRATE_WRITE); - has_clkdiv_write = true; -#endif - -#endif - - if ( !has_clkdiv_write ) - { -#ifdef SPI1_BASE - if (spiInstance == SPI1) - { - clkdiv_write = SPI_BAUDRATEPRESCALER_4; - has_clkdiv_write = true; - } -#endif - - if ( !has_clkdiv_write ) - { - clkdiv_write = SPI_BAUDRATEPRESCALER_2; - } - } - -#if PIN_EXISTS(TFT_MISO) - if ( !has_clkdiv_read ) - { - clkdiv_read = clkdiv_write; - } -#endif - - SPIx.Instance = spiInstance; - SPIx.State = HAL_SPI_STATE_RESET; - SPIx.Init.NSS = SPI_NSS_SOFT; - SPIx.Init.Mode = SPI_MODE_MASTER; - SPIx.Init.Direction = (TFT_MISO_PIN != NC && TFT_MISO_PIN == TFT_MOSI_PIN) ? SPI_DIRECTION_1LINE : SPI_DIRECTION_2LINES; - //SPIx.Init.BaudRatePrescaler = clkdiv; - SPIx.Init.CLKPhase = SPI_PHASE_1EDGE; - SPIx.Init.CLKPolarity = SPI_POLARITY_LOW; - //SPIx.Init.DataSize = SPI_DATASIZE_8BIT; - SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB; - SPIx.Init.TIMode = SPI_TIMODE_DISABLE; - SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; - SPIx.Init.CRCPolynomial = 10; - - DMAtx.Init.Direction = DMA_MEMORY_TO_PERIPH; - DMAtx.Init.PeriphInc = DMA_PINC_DISABLE; - DMAtx.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; - DMAtx.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; - DMAtx.Init.Mode = DMA_NORMAL; - DMAtx.Init.Priority = DMA_PRIORITY_LOW; - #ifdef STM32F4xx - DMAtx.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - #endif - - active_transfer = false; - active_dma = false; -} - -// Call before any HAL initialization (DMA or SPI). -void TFT_SPI::HALPrepare(eSPIMode spiMode) -{ - uint8_t clkdiv = 1; -#if PIN_EXISTS(TFT_MISO) - if (spiMode == eSPIMode::READ) - { - clkdiv = clkdiv_read; - } -#endif - if (spiMode == eSPIMode::WRITE) - { - clkdiv = clkdiv_write; - } - - SPIx.Init.BaudRatePrescaler = clkdiv; - - pinmap_pinout(digitalPinToPinName(TFT_SCK_PIN), PinMap_SPI_SCLK); - pinmap_pinout(digitalPinToPinName(TFT_MOSI_PIN), PinMap_SPI_MOSI); - #if PIN_EXISTS(TFT_MISO) && TFT_MISO_PIN != TFT_MOSI_PIN - pinmap_pinout(digitalPinToPinName(TFT_MISO_PIN), PinMap_SPI_MISO); - #endif - //pinmap_pinout(digitalPinToPinName(TFT_CS_PIN), PinMap_SPI_SSEL); - - pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TFT_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TFT_SCK_PIN)), GPIO_PULLDOWN); - - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_CLK_ENABLE(); - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Channel3; - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Stream3; - DMAtx.Init.Channel = DMA_CHANNEL_3; - #endif - } - #endif - - #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_CLK_ENABLE(); - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Channel5; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Stream4; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } - #endif - - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_CLK_ENABLE(); - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Channel2; - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_ENABLE(); - DMAtx.Instance = DMA1_Stream5; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } - #endif - - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_CLK_ENABLE(); - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Channel4; - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_ENABLE(); - DMAtx.Instance = DMA2_Stream5; - DMAtx.Init.Channel = DMA_CHANNEL_0; - #endif - } - #endif -} - -void TFT_SPI::HALDismantle(void) -{ - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - __HAL_RCC_SPI1_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_DISABLE(); - #endif - } - #endif - - #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - __HAL_RCC_SPI2_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA1_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_DISABLE(); - #endif - } - #endif - - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - __HAL_RCC_SPI3_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA1_CLK_DISABLE(); - #endif - } - #endif - - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - __HAL_RCC_SPI4_CLK_DISABLE(); - #ifdef STM32F1xx - __HAL_RCC_DMA2_CLK_DISABLE(); - #elif defined(STM32F4xx) - __HAL_RCC_DMA2_CLK_DISABLE(); - #endif - #endif -} - -void TFT_SPI::DataTransferBegin(uint16_t DataSize, eSPIMode spiMode) { - HALPrepare(spiMode); - SPIx.Init.DataSize = ( DataSize == DATASIZE_8BIT ) ? SPI_DATASIZE_8BIT : SPI_DATASIZE_16BIT; - HAL_SPI_Init(&SPIx); - WRITE(TFT_CS_PIN, LOW); - active_transfer = true; -} - -void TFT_SPI::DataTransferEnd(void) -{ - // TODO: apply strong integrity to the active_transfer variable! - HAL_SPI_DeInit(&SPIx); - HALDismantle(); - WRITE(TFT_CS_PIN, HIGH); - active_transfer = false; -} - -#ifdef TFT_DEFAULT_DRIVER - #include "../../../lcd/tft_io/tft_ids.h" -#endif - -uint32_t TFT_SPI::GetID() { - uint32_t id; - id = ReadID(LCD_READ_ID); - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { - id = ReadID(LCD_READ_ID4); - #ifdef TFT_DEFAULT_DRIVER - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = TFT_DEFAULT_DRIVER; - #endif - } - return id; -} - -uint32_t TFT_SPI::ReadID(uint16_t Reg) { - uint32_t Data = 0; - #if PIN_EXISTS(TFT_MISO) - uint32_t i; - - DataTransferBegin(DATASIZE_8BIT, eSPIMode::READ); - WriteReg(Reg); - - if (SPIx.Init.Direction == SPI_DIRECTION_1LINE) SPI_1LINE_RX(&SPIx); - __HAL_SPI_ENABLE(&SPIx); - - for (i = 0; i < 4; i++) { - #if TFT_MISO_PIN != TFT_MOSI_PIN - //if (hspi->Init.Direction == SPI_DIRECTION_2LINES) { - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} - SPIx.Instance->DR = 0; - //} - #endif - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_RXNE)) {} - Data = (Data << 8) | SPIx.Instance->DR; - } - - __HAL_SPI_DISABLE(&SPIx); - DataTransferEnd(); - #endif - - return Data >> 7; -} - -bool TFT_SPI::isBusy() { - if (active_dma) - { - #ifdef STM32F1xx - volatile bool dmaEnabled = (DMAtx.Instance->CCR & DMA_CCR_EN) != RESET; - #elif defined(STM32F4xx) - volatile bool dmaEnabled = DMAtx.Instance->CR & DMA_SxCR_EN; - #endif - #if 0 - if (dmaEnabled) { - if (__HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TC_FLAG_INDEX(&DMAtx)) != 0 || __HAL_DMA_GET_FLAG(&DMAtx, __HAL_DMA_GET_TE_FLAG_INDEX(&DMAtx)) != 0) - Abort(); - } - else - Abort(); - #endif - return dmaEnabled; - } - else - { - #if 0 - Abort(); - #endif - return false; - } -} - -void TFT_SPI::Abort() { - if (active_transfer) - { - // Wait for any running spi - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) { } - while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) { } - if (active_dma) - { - // First, abort any running dma - HAL_DMA_Abort(&DMAtx); - HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - // DeInit objects - HAL_DMA_DeInit(&DMAtx); - active_dma = false; - } - // Deselect CS - DataTransferEnd(); - } -} - -void TFT_SPI::Transmit(uint16_t Data) { -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif - - __HAL_SPI_ENABLE(&SPIx); - - SPIx.Instance->DR = Data; - - while (!__HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_TXE)) {} - while ( __HAL_SPI_GET_FLAG(&SPIx, SPI_FLAG_BSY)) {} - -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN != TFT_MOSI_PIN) - __HAL_SPI_CLEAR_OVRFLAG(&SPIx); // Clear overrun flag in 2 Lines communication mode because received is not read -#endif -} - -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - - // Wait last dma finish, to start another - while (isBusy()) { /* nada */ } - -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif - - DataTransferBegin(); - - DMAtx.Init.MemInc = MemoryIncrease; - HAL_DMA_Init(&DMAtx); - active_dma = true; - - HAL_DMA_Start(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); - - __HAL_SPI_ENABLE(&SPIx); - - SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request - - HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY); - - Abort(); -} - -#if ENABLED(USE_SPI_DMA_TC) - - void TFT_SPI::TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - -#if PIN_EXISTS(TFT_MISO) - if (TFT_MISO_PIN == TFT_MOSI_PIN) - SPI_1LINE_TX(&SPIx); -#endif - - DataTransferBegin(); - - DMAtx.Init.MemInc = MemoryIncrease; - HAL_DMA_Init(&DMAtx); - active_dma = true; - - HAL_NVIC_SetPriority(DMA2_Stream3_IRQn, 5, 0); - HAL_NVIC_EnableIRQ(DMA2_Stream3_IRQn); - HAL_DMA_Start_IT(&DMAtx, (uint32_t)Data, (uint32_t)&(SPIx.Instance->DR), Count); - __HAL_SPI_ENABLE(&SPIx); - - SET_BIT(SPIx.Instance->CR2, SPI_CR2_TXDMAEN); // Enable Tx DMA Request - } - - extern "C" void DMA2_Stream3_IRQHandler(void) { HAL_DMA_IRQHandler(&TFT_SPI::DMAtx); } - -#endif - -#endif // HAS_SPI_TFT -#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp deleted file mode 100644 index f4edb3af2942..000000000000 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ /dev/null @@ -1,332 +0,0 @@ -/** - * 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 . - * - */ - -#include "../../platforms.h" - -#ifdef HAL_STM32 - -#include "../../../inc/MarlinConfig.h" - -#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS - -#include "xpt2046.h" -#include "pinconfig.h" - -uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } - -SPI_HandleTypeDef XPT2046::SPIx; - -uint8_t XPT2046::_GetClockDivider( uint32_t spibasefreq, uint32_t speed ) -{ - if ( speed >= (spibasefreq / 2) ) - { - return SPI_BAUDRATEPRESCALER_2; - } - else if ( speed >= (spibasefreq / 4) ) - { - return SPI_BAUDRATEPRESCALER_4; - } - else if ( speed >= (spibasefreq / 8) ) - { - return SPI_BAUDRATEPRESCALER_8; - } - else if ( speed >= (spibasefreq / 16) ) - { - return SPI_BAUDRATEPRESCALER_16; - } - else if ( speed >= (spibasefreq / 32) ) - { - return SPI_BAUDRATEPRESCALER_32; - } - else if ( speed >= (spibasefreq / 64) ) - { - return SPI_BAUDRATEPRESCALER_64; - } - else if ( speed >= (spibasefreq / 128) ) - { - return SPI_BAUDRATEPRESCALER_128; - } - else - { - return SPI_BAUDRATEPRESCALER_256; - } -} - -extern "C" { - #include -} - -void XPT2046::Init() { - SPI_TypeDef *spiInstance; - - OUT_WRITE(TOUCH_CS_PIN, HIGH); - - #if PIN_EXISTS(TOUCH_INT) - // Optional Pendrive interrupt pin - SET_INPUT(TOUCH_INT_PIN); - #endif - - spiInstance = (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); - if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI)) spiInstance = NP; - if (spiInstance != (SPI_TypeDef *)pinmap_peripheral(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO)) spiInstance = NP; - - SPIx.Instance = spiInstance; - - if (spiInstance) { - uint8_t clkdiv; -#ifdef TOUCH_BAUDRATE - spi_t tmp_spi; - tmp_spi.pin_sclk = digitalPinToPinName(TOUCH_SCK_PIN); - uint32_t spibasefreq = spi_getClkFreq(&tmp_spi); - - clkdiv = _GetClockDivider(spibasefreq, TOUCH_BAUDRATE); -#else - bool has_clkdiv = false; - - #ifdef SPI1_BASE - if (spiInstance == SPI1) - { - clkdiv = SPI_BAUDRATEPRESCALER_16; - has_clkdiv = true; - } - #endif - if ( !has_clkdiv ) - { - clkdiv = SPI_BAUDRATEPRESCALER_8; - } -#endif - - SPIx.State = HAL_SPI_STATE_RESET; - SPIx.Init.NSS = SPI_NSS_SOFT; - SPIx.Init.Mode = SPI_MODE_MASTER; - SPIx.Init.Direction = SPI_DIRECTION_2LINES; - SPIx.Init.BaudRatePrescaler = clkdiv; - SPIx.Init.CLKPhase = SPI_PHASE_2EDGE; - SPIx.Init.CLKPolarity = SPI_POLARITY_HIGH; - SPIx.Init.DataSize = SPI_DATASIZE_8BIT; - SPIx.Init.FirstBit = SPI_FIRSTBIT_MSB; - SPIx.Init.TIMode = SPI_TIMODE_DISABLE; - SPIx.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; - SPIx.Init.CRCPolynomial = 10; - } - else { - SET_INPUT(TOUCH_MISO_PIN); - SET_OUTPUT(TOUCH_MOSI_PIN); - SET_OUTPUT(TOUCH_SCK_PIN); - } - - getRawData(XPT2046_Z1); -} - -void XPT2046::HALPrepare(void) -{ - pinmap_pinout(digitalPinToPinName(TOUCH_SCK_PIN), PinMap_SPI_SCLK); - pinmap_pinout(digitalPinToPinName(TOUCH_MOSI_PIN), PinMap_SPI_MOSI); - pinmap_pinout(digitalPinToPinName(TOUCH_MISO_PIN), PinMap_SPI_MISO); - - pin_PullConfig(get_GPIO_Port(STM_PORT(digitalPinToPinName(TOUCH_SCK_PIN))), STM_LL_GPIO_PIN(digitalPinToPinName(TOUCH_SCK_PIN)), GPIO_PULLDOWN); - - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_CLK_ENABLE(); - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - } - #endif - #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_CLK_ENABLE(); - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - } - #endif - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_CLK_ENABLE(); - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - } - #endif - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_CLK_ENABLE(); - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - } - #endif - #ifdef SPI5_BASE - if (SPIx.Instance == SPI5) { - __HAL_RCC_SPI5_CLK_ENABLE(); - __HAL_RCC_SPI5_FORCE_RESET(); - __HAL_RCC_SPI5_RELEASE_RESET(); - } - #endif - #ifdef SPI6_BASE - if (SPIx.Instance == SPI6) { - __HAL_RCC_SPI6_CLK_ENABLE(); - __HAL_RCC_SPI6_FORCE_RESET(); - __HAL_RCC_SPI6_RELEASE_RESET(); - } - #endif -} - -void XPT2046::HALDismantle(void) -{ - #ifdef SPI1_BASE - if (SPIx.Instance == SPI1) { - __HAL_RCC_SPI1_FORCE_RESET(); - __HAL_RCC_SPI1_RELEASE_RESET(); - __HAL_RCC_SPI1_CLK_DISABLE(); - } - #endif - #ifdef SPI2_BASE - if (SPIx.Instance == SPI2) { - __HAL_RCC_SPI2_FORCE_RESET(); - __HAL_RCC_SPI2_RELEASE_RESET(); - __HAL_RCC_SPI2_CLK_DISABLE(); - } - #endif - #ifdef SPI3_BASE - if (SPIx.Instance == SPI3) { - __HAL_RCC_SPI3_FORCE_RESET(); - __HAL_RCC_SPI3_RELEASE_RESET(); - __HAL_RCC_SPI3_CLK_DISABLE(); - } - #endif - #ifdef SPI4_BASE - if (SPIx.Instance == SPI4) { - __HAL_RCC_SPI4_FORCE_RESET(); - __HAL_RCC_SPI4_RELEASE_RESET(); - __HAL_RCC_SPI4_CLK_DISABLE(); - } - #endif - #ifdef SPI5_BASE - if (SPIx.Instance == SPI5) { - __HAL_RCC_SPI5_FORCE_RESET(); - __HAL_RCC_SPI5_RELEASE_RESET(); - __HAL_RCC_SPI5_CLK_DISABLE(); - } - #endif - #ifdef SPI6_BASE - if (SPIx.Instance == SPI6) { - __HAL_RCC_SPI6_FORCE_RESET(); - __HAL_RCC_SPI6_RELEASE_RESET(); - __HAL_RCC_SPI6_CLK_DISABLE(); - } - #endif -} - -void XPT2046::DataTransferBegin(void) - { - if (SPIx.Instance) - { - HALPrepare(); - HAL_SPI_Init(&SPIx); - } - WRITE(TOUCH_CS_PIN, LOW); -} - -void XPT2046::DataTransferEnd(void) -{ - WRITE(TOUCH_CS_PIN, HIGH); - if (SPIx.Instance) - { - HAL_SPI_DeInit(&SPIx); - HALDismantle(); - } -} - -bool XPT2046::isTouched() { - return isBusy() ? false : ( - #if PIN_EXISTS(TOUCH_INT) - READ(TOUCH_INT_PIN) != HIGH - #else - getRawData(XPT2046_Z1) >= XPT2046_Z1_THRESHOLD - #endif - ); -} - -bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { - if (isBusy()) return false; - if (!isTouched()) return false; - *x = getRawData(XPT2046_X); - *y = getRawData(XPT2046_Y); - return isTouched(); -} - -uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { - uint16_t data[3]; - - DataTransferBegin(); - - for (uint16_t i = 0; i < 3 ; i++) { - IO(coordinate); - data[i] = (IO() << 4) | (IO() >> 4); - } - - DataTransferEnd(); - - uint16_t delta01 = delta(data[0], data[1]); - uint16_t delta02 = delta(data[0], data[2]); - uint16_t delta12 = delta(data[1], data[2]); - - if (delta01 > delta02 || delta01 > delta12) { - if (delta02 > delta12) - data[0] = data[2]; - else - data[1] = data[2]; - } - - return (data[0] + data[1]) >> 1; -} - -uint16_t XPT2046::HardwareIO(uint16_t data) { - __HAL_SPI_ENABLE(&SPIx); - while ((SPIx.Instance->SR & SPI_FLAG_TXE) != SPI_FLAG_TXE) {} - SPIx.Instance->DR = data; - while ((SPIx.Instance->SR & SPI_FLAG_RXNE) != SPI_FLAG_RXNE) {} - __HAL_SPI_DISABLE(&SPIx); - - return SPIx.Instance->DR; -} - -uint16_t XPT2046::SoftwareIO(uint16_t data) { - uint16_t result = 0; - - for (uint8_t j = 0x80; j > 0; j >>= 1) { - WRITE(TOUCH_SCK_PIN, LOW); - __DSB(); - WRITE(TOUCH_MOSI_PIN, data & j ? HIGH : LOW); - __DSB(); - if (READ(TOUCH_MISO_PIN)) result |= j; - __DSB(); - WRITE(TOUCH_SCK_PIN, HIGH); - __DSB(); - } - WRITE(TOUCH_SCK_PIN, LOW); - __DSB(); - - return result; -} - -#endif // HAS_TFT_XPT2046 -#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp deleted file mode 100644 index a2dc7486d2d9..000000000000 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ /dev/null @@ -1,176 +0,0 @@ -/** - * 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 - * Copyright (c) 2017 Victor Perez - * - * 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 . - * - */ - -/** - * Software SPI functions originally from Arduino Sd2Card Library - * Copyright (c) 2009 by William Greiman - * Adapted to the STM32F1 HAL - */ - -#ifdef __STM32F1__ - -#include "../../inc/MarlinConfig.h" -#include - -// ------------------------ -// Public functions -// ------------------------ - -#if ENABLED(SOFTWARE_SPI) - - // ------------------------ - // Software SPI - // ------------------------ - #error "Software SPI not supported for STM32F1. Use hardware SPI." - -#else - -// ------------------------ -// Hardware SPI -// ------------------------ - -/** - * VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz - */ - -/** - * @brief Begin SPI port setup - * - * @return Nothing - * - * @details Only configures SS pin since libmaple creates and initialize the SPI object - */ -void spiBegin() { - #if PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); - #endif -} - -/** - * @brief Initialize SPI port to required speed rate and transfer mode (MSB, SPI MODE 0) - * - * @param spiRate Rate as declared in HAL.h (speed do not match AVR) - * @return Nothing - * - * @details - */ -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - // TODO: maybe use the more generic STM32 SPI stuff instead, ignore the pins here. - /** - * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz - * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 - * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 - */ - #if SPI_DEVICE == 1 - #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 - #else - #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 - #endif - uint8_t clock; - switch (spiRate) { - case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break; - case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break; - case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break; - case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break; - case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break; - case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; - default: clock = SPI_CLOCK_DIV2; // Default from the SPI library - } - SPI.setModule(SPI_DEVICE); - SPI.begin(); - SPI.setClockDivider(clock); - SPI.setBitOrder(MSBFIRST); - SPI.setDataMode(SPI_MODE0); -} - -void spiClose() { - SPI.end(); -} - -/** - * @brief Receive a single byte from the SPI port. - * - * @return Byte received - * - * @details - */ -uint8_t spiRec() { - uint8_t returnByte = SPI.transfer(0xFF); - return returnByte; -} - -/** - * @brief Receive a number of bytes from the SPI port to a buffer - * - * @param buf Pointer to starting address of buffer to write to. - * @param nbyte Number of bytes to receive. - * @return Nothing - * - * @details Uses DMA - */ -void spiRead(uint8_t *buf, uint16_t nbyte) { - SPI.dmaTransfer(0, const_cast(buf), nbyte); -} - -/** - * @brief Send a single byte on SPI port - * - * @param b Byte to send - * - * @details - */ -void spiSend(uint8_t b) { - SPI.send(b); -} - -/** - * @brief Write token and then write from 512 byte buffer to SPI (for SD card) - * - * @param buf Pointer with buffer start address - * @return Nothing - * - * @details Use DMA - */ -void spiSendBlock(uint8_t token, const uint8_t *buf) { - SPI.send(token); - SPI.dmaSend(const_cast(buf), 512); -} - -#if ENABLED(SPI_EEPROM) - -// Read single byte from specified SPI channel -uint8_t spiRec(uint32_t chan) { return SPI.transfer(0xFF); } - -// Write single byte to specified SPI channel -void spiSend(uint32_t chan, byte b) { SPI.send(b); } - -// Write buffer to specified SPI channel -void spiSend(uint32_t chan, const uint8_t *buf, size_t n) { - for (size_t p = 0; p < n; p++) spiSend(chan, buf[p]); -} - -#endif // SPI_EEPROM - -#endif // SOFTWARE_SPI - -#endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/MarlinSPI.h b/Marlin/src/HAL/STM32F1/MarlinSPI.h deleted file mode 100644 index fab245f904e3..000000000000 --- a/Marlin/src/HAL/STM32F1/MarlinSPI.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -/** - * Marlin currently requires 3 SPI classes: - * - * SPIClass: - * This class is normally provided by frameworks and has a semi-default interface. - * This is needed because some libraries reference it globally. - * - * SPISettings: - * Container for SPI configs for SPIClass. As above, libraries may reference it globally. - * - * These two classes are often provided by frameworks so we cannot extend them to add - * useful methods for Marlin. - * - * MarlinSPI: - * Provides the default SPIClass interface plus some Marlin goodies such as a simplified - * interface for SPI DMA transfer. - * - */ - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp deleted file mode 100644 index f447cec81107..000000000000 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * 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 . - * - */ - -#include "../../../inc/MarlinConfig.h" - -#if HAS_SPI_TFT - -#include "tft_spi.h" - -SPIClass TFT_SPI::SPIx(1); - -void TFT_SPI::Init() { - #if PIN_EXISTS(TFT_RESET) - OUT_WRITE(TFT_RESET_PIN, HIGH); - delay(100); - #endif - - #if PIN_EXISTS(TFT_BACKLIGHT) - OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH); - #endif - - OUT_WRITE(TFT_DC_PIN, HIGH); - OUT_WRITE(TFT_CS_PIN, HIGH); - - /** - * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz - * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 - * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 - */ - #if SPI_DEVICE == 1 - #define SPI_CLOCK_MAX SPI_CLOCK_DIV4 - #else - #define SPI_CLOCK_MAX SPI_CLOCK_DIV2 - #endif - uint8_t clock; - uint8_t spiRate = SPI_FULL_SPEED; - switch (spiRate) { - case SPI_FULL_SPEED: clock = SPI_CLOCK_MAX ; break; - case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4 ; break; - case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8 ; break; - case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break; - case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break; - case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; - default: clock = SPI_CLOCK_DIV2; // Default from the SPI library - } - SPIx.setModule(1); - SPIx.setClockDivider(clock); - SPIx.setBitOrder(MSBFIRST); - SPIx.setDataMode(SPI_MODE0); -} - -void TFT_SPI::DataTransferBegin(uint16_t DataSize) { - SPIx.setDataSize(DataSize); - SPIx.begin(); - OUT_WRITE(TFT_CS_PIN, LOW); -} - -#ifdef TFT_DEFAULT_DRIVER - #include "../../../lcd/tft_io/tft_ids.h" -#endif - -uint32_t TFT_SPI::GetID() { - uint32_t id; - id = ReadID(LCD_READ_ID); - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { - id = ReadID(LCD_READ_ID4); - #ifdef TFT_DEFAULT_DRIVER - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) - id = TFT_DEFAULT_DRIVER; - #endif - } - return id; -} - -uint32_t TFT_SPI::ReadID(uint16_t Reg) { - #if !PIN_EXISTS(TFT_MISO) - return 0; - #else - uint8_t d = 0; - uint32_t data = 0; - SPIx.setClockDivider(SPI_CLOCK_DIV16); - DataTransferBegin(DATASIZE_8BIT); - WriteReg(Reg); - - LOOP_L_N(i, 4) { - SPIx.read((uint8_t*)&d, 1); - data = (data << 8) | d; - } - - DataTransferEnd(); - SPIx.setClockDivider(SPI_CLOCK_MAX); - - return data >> 7; - #endif -} - -bool TFT_SPI::isBusy() { return false; } - -void TFT_SPI::Abort() { DataTransferEnd(); } - -void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); } - -void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) { - DataTransferBegin(); - OUT_WRITE(TFT_DC_PIN, HIGH); - SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE); - DataTransferEnd(); -} - -#endif // HAS_SPI_TFT diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.h b/Marlin/src/HAL/STM32F1/tft/tft_spi.h deleted file mode 100644 index da9a8e0c223e..000000000000 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.h +++ /dev/null @@ -1,72 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "../../../inc/MarlinConfig.h" - -#include - -#ifndef LCD_READ_ID - #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) -#endif -#ifndef LCD_READ_ID4 - #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) -#endif - -#define DATASIZE_8BIT DATA_SIZE_8BIT -#define DATASIZE_16BIT DATA_SIZE_16BIT -#define TFT_IO_DRIVER TFT_SPI - -#define DMA_MINC_ENABLE 1 -#define DMA_MINC_DISABLE 0 - -class TFT_SPI { -private: - static uint32_t ReadID(uint16_t Reg); - static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); - -public: - static SPIClass SPIx; - - static void Init(); - static uint32_t GetID(); - static bool isBusy(); - static void Abort(); - - static void DataTransferBegin(uint16_t DataWidth = DATA_SIZE_16BIT); - static void DataTransferEnd() { WRITE(TFT_CS_PIN, HIGH); SPIx.end(); }; - static void DataTransferAbort(); - - static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } - - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } - static void WriteMultiple(uint16_t Color, 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; - } - } -}; diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp deleted file mode 100644 index ac9ad072aa05..000000000000 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ /dev/null @@ -1,144 +0,0 @@ -/** - * 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 . - * - */ - -#include "../../../inc/MarlinConfig.h" - -#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS - -#include "xpt2046.h" -#include - -uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - #include - - SPIClass XPT2046::SPIx(TOUCH_BUTTONS_HW_SPI_DEVICE); - - static void touch_spi_init(uint8_t spiRate) { - /** - * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz - * STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1 - * so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2 - */ - uint8_t clock; - switch (spiRate) { - case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV4; break; - case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4; break; - case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8; break; - case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break; - case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break; - case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break; - default: clock = SPI_CLOCK_DIV2; // Default from the SPI library - } - XPT2046::SPIx.setModule(TOUCH_BUTTONS_HW_SPI_DEVICE); - XPT2046::SPIx.setClockDivider(clock); - XPT2046::SPIx.setBitOrder(MSBFIRST); - XPT2046::SPIx.setDataMode(SPI_MODE0); - } -#endif // TOUCH_BUTTONS_HW_SPI - -void XPT2046::Init() { - SET_INPUT(TOUCH_MISO_PIN); - SET_OUTPUT(TOUCH_MOSI_PIN); - SET_OUTPUT(TOUCH_SCK_PIN); - OUT_WRITE(TOUCH_CS_PIN, HIGH); - - #if PIN_EXISTS(TOUCH_INT) - // Optional Pendrive interrupt pin - SET_INPUT(TOUCH_INT_PIN); - #endif - - TERN_(TOUCH_BUTTONS_HW_SPI, touch_spi_init(SPI_SPEED_6)); - - // Read once to enable pendrive status pin - getRawData(XPT2046_X); -} - -bool XPT2046::isTouched() { - return isBusy() ? false : ( - #if PIN_EXISTS(TOUCH_INT) - READ(TOUCH_INT_PIN) != HIGH - #else - getRawData(XPT2046_Z1) >= XPT2046_Z1_THRESHOLD - #endif - ); -} - -bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { - if (isBusy()) return false; - if (!isTouched()) return false; - *x = getRawData(XPT2046_X); - *y = getRawData(XPT2046_Y); - return isTouched(); -} - -uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { - uint16_t data[3]; - - DataTransferBegin(); - TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.begin()); - - for (uint16_t i = 0; i < 3 ; i++) { - IO(coordinate); - data[i] = (IO() << 4) | (IO() >> 4); - } - - TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.end()); - DataTransferEnd(); - - uint16_t delta01 = delta(data[0], data[1]), - delta02 = delta(data[0], data[2]), - delta12 = delta(data[1], data[2]); - - if (delta01 > delta02 || delta01 > delta12) - data[delta02 > delta12 ? 0 : 1] = data[2]; - - return (data[0] + data[1]) >> 1; -} - -uint16_t XPT2046::IO(uint16_t data) { - return TERN(TOUCH_BUTTONS_HW_SPI, HardwareIO, SoftwareIO)(data); -} - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - uint16_t XPT2046::HardwareIO(uint16_t data) { - uint16_t result = SPIx.transfer(data); - return result; - } -#endif - -uint16_t XPT2046::SoftwareIO(uint16_t data) { - uint16_t result = 0; - - for (uint8_t j = 0x80; j; j >>= 1) { - WRITE(TOUCH_SCK_PIN, LOW); - WRITE(TOUCH_MOSI_PIN, data & j ? HIGH : LOW); - if (READ(TOUCH_MISO_PIN)) result |= j; - WRITE(TOUCH_SCK_PIN, HIGH); - } - WRITE(TOUCH_SCK_PIN, LOW); - - return result; -} - -#endif // HAS_TFT_XPT2046 diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h deleted file mode 100644 index 7c456cf00e1b..000000000000 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ /dev/null @@ -1,83 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include "../../../inc/MarlinConfig.h" - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - #include -#endif - -#ifndef TOUCH_MISO_PIN - #define TOUCH_MISO_PIN SD_MISO_PIN -#endif -#ifndef TOUCH_MOSI_PIN - #define TOUCH_MOSI_PIN SD_MOSI_PIN -#endif -#ifndef TOUCH_SCK_PIN - #define TOUCH_SCK_PIN SD_SCK_PIN -#endif -#ifndef TOUCH_CS_PIN - #define TOUCH_CS_PIN SD_SS_PIN -#endif -#ifndef TOUCH_INT_PIN - #define TOUCH_INT_PIN -1 -#endif - -#define XPT2046_DFR_MODE 0x00 -#define XPT2046_SER_MODE 0x04 -#define XPT2046_CONTROL 0x80 - -enum XPTCoordinate : uint8_t { - XPT2046_X = 0x10 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Y = 0x50 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Z1 = 0x30 | XPT2046_CONTROL | XPT2046_DFR_MODE, - XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, -}; - -#ifndef XPT2046_Z1_THRESHOLD - #define XPT2046_Z1_THRESHOLD 10 -#endif - -class XPT2046 { -private: - static bool isBusy() { return false; } - - static uint16_t getRawData(const XPTCoordinate coordinate); - static bool isTouched(); - - static void DataTransferBegin() { WRITE(TOUCH_CS_PIN, LOW); }; - static void DataTransferEnd() { WRITE(TOUCH_CS_PIN, HIGH); }; - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static uint16_t HardwareIO(uint16_t data); - #endif - static uint16_t SoftwareIO(uint16_t data); - static uint16_t IO(uint16_t data = 0); - -public: - #if ENABLED(TOUCH_BUTTONS_HW_SPI) - static SPIClass SPIx; - #endif - - static void Init(); - static bool getRawPoint(int16_t *x, int16_t *y); -}; diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index cb4dd4d0d16e..3e60670a74ef 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -29,6 +29,9 @@ #include "spi_pins.h" static SPISettings spiConfig; +static uint32_t _spi_clock; +static int _spi_bitOrder; +static int _spi_clockMode; /** * Standard SPI functions @@ -46,8 +49,16 @@ void spiBegin() { } // Configure SPI for specified SPI speed -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInitEx(uint32_t clock, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Ignore the pin hints, there is nothing we can do (see arduino core). + _spi_clock = clock; + _spi_bitOrder = MSBFIRST; + _spi_clockMode = SPI_MODE0; + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + SPI.begin(); +} + +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Use data rates Marlin uses uint32_t clock; switch (spiRate) { @@ -59,18 +70,43 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi case SPI_SPEED_6: clock = 312500; break; default: clock = 4000000; // Default from the SPI library } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - SPI.begin(); + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); } void spiClose() { SPI.end(); } +void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + _spi_bitOrder = MSBFIRST; + } + else if (bitOrder == SPI_BITORDER_LSB) { + _spi_bitOrder = LSBFIRST; + } + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + +void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + _spi_clockMode = SPI_MODE0; + else if (clockMode == SPI_CLKMODE_1) + _spi_clockMode = SPI_MODE1; + else if (clockMode == SPI_CLKMODE_2) + _spi_clockMode = SPI_MODE2; + else if (clockMode == SPI_CLKMODE_3) + _spi_clockMode = SPI_MODE3; + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + // SPI receive a byte -uint8_t spiRec() { +uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); - const uint8_t returnByte = SPI.transfer(0xFF); + const uint8_t returnByte = SPI.transfer(txval); SPI.endTransaction(); return returnByte; //SPDR = 0xFF; @@ -78,8 +114,16 @@ uint8_t spiRec() { //return SPDR; } +uint16_t spiRec16(uint16_t txval) { + SPI.beginTransaction(spiConfig); + uint16_t res = SPI.transfer16(txval); + SPI.endTransaction(); + return res; +} + // SPI read data -void spiRead(uint8_t *buf, uint16_t nbyte) { +void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + memset(buf, txval, nbyte); SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -103,9 +147,19 @@ void spiSend(uint8_t b) { //while (!TEST(SPSR, SPIF)) { /* nada */ } } +void spiSend16(uint16_t v) { + SPI.beginTransaction(spiConfig); + SPI.transfer16(v); + SPI.endTransaction(); +} + // SPI send block void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); + SPI.transfer(token); + for (uint16_t n = 0; n < 512; n++) + SPI.transfer(buf[n]); +#if 0 SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { while (!TEST(SPSR, SPIF)) { /* nada */ }; @@ -114,14 +168,36 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = buf[i + 1]; } while (!TEST(SPSR, SPIF)) { /* nada */ }; +#endif + SPI.endTransaction(); +} + +void spiWrite(const uint8_t *buf, uint16_t cnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer(buf[n]); SPI.endTransaction(); } +void spiWrite16(const uint16_t *buf, uint16_t cnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer16(buf[n]); + SPI.endTransaction(); +} -// Begin SPI transaction, set clock, bit order, data mode -void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - spiConfig = SPISettings(spiClock, bitOrder, dataMode); +void spiWriteRepeat(uint8_t val, uint16_t repcnt) { SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer(val); + SPI.endTransaction(); +} + +void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer16(val); + SPI.endTransaction(); } #endif // __MK20DX256__ diff --git a/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h b/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/TEENSY31_32/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h index 54ec16664354..a7030f800e59 100644 --- a/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY31_32/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY31_32." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/TEENSY31_32." #endif diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 0d165749ef73..9115d0f2d59f 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -34,6 +34,9 @@ #include "spi_pins.h" static SPISettings spiConfig; +static uint32_t _spi_clock; +static int _spi_bitOrder; +static int _spi_clockMode; void spiBegin() { #if PIN_EXISTS(SD_SS) @@ -44,9 +47,16 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInitEx(uint32_t clock, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Ignore the SPI pin hints. + _spi_clock = clock; + _spi_bitOrder = MSBFIRST; + _spi_clockMode = SPI_MODE0; + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + SPI.begin(); +} +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Use Marlin data-rates uint32_t clock; switch (spiRate) { @@ -59,17 +69,42 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi default: clock = 4000000; // Default from the SPI library } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - SPI.begin(); + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); } void spiClose() { SPI.end(); } -uint8_t spiRec() { +void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + _spi_bitOrder = MSBFIRST; + } + else if (bitOrder == SPI_BITORDER_LSB) { + _spi_bitOrder = LSBFIRST; + } + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + +void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + _spi_clockMode = SPI_MODE0; + else if (clockMode == SPI_CLKMODE_1) + _spi_clockMode = SPI_MODE1; + else if (clockMode == SPI_CLKMODE_2) + _spi_clockMode = SPI_MODE2; + else if (clockMode == SPI_CLKMODE_3) + _spi_clockMode = SPI_MODE3; + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + +uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); - uint8_t returnByte = SPI.transfer(0xFF); + uint8_t returnByte = SPI.transfer(txval); SPI.endTransaction(); return returnByte; //SPDR = 0xFF; @@ -77,7 +112,15 @@ uint8_t spiRec() { //return SPDR; } -void spiRead(uint8_t *buf, uint16_t nbyte) { +uint16_t spiRec16(uint16_t txval) { + SPI.beginTransaction(spiConfig); + uint16_t res = SPI.transfer16(txval); + SPI.endTransaction(); + return res; +} + +void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + memset(buf, txval, nbyte); SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -100,8 +143,18 @@ void spiSend(uint8_t b) { //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } +void spiSend16(uint16_t v) { + SPI.beginTransaction(spiConfig); + SPI.transfer16(v); + SPI.endTransaction(); +} + void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); + SPI.transfer(token); + for (uint16_t n = 0; n < 512; n++) + SPI.transfer(buf[n]); +#if 0 SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { while (!TEST(SPSR, SPIF)) { /* nada */ }; @@ -110,13 +163,36 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = buf[i + 1]; } while (!TEST(SPSR, SPIF)) { /* nada */ }; +#endif + SPI.endTransaction(); +} + +void spiWrite(const uint8_t *buf, uint16_t cnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer(buf[n]); SPI.endTransaction(); } -// Begin SPI transaction, set clock, bit order, data mode -void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - spiConfig = SPISettings(spiClock, bitOrder, dataMode); +void spiWrite16(const uint16_t *buf, uint16_t cnt) { SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer16(buf[n]); + SPI.endTransaction(); +} + +void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer(val); + SPI.endTransaction(); +} + +void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer16(val); + SPI.endTransaction(); } #endif // __MK64FX512__ || __MK66FX1M0__ diff --git a/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h b/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/TEENSY35_36/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h index 632ee533acac..e4db1a09cfe3 100644 --- a/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY35_36/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY35_36." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/TEENSY35_36." #endif diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 1adf8a04a9dc..03418a2ca00e 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -50,6 +50,10 @@ static SPISettings spiConfig; // Hardware SPI // ------------------------ +static uint32_t _spi_clock; +static int _spi_bitOrder; +static int _spi_clockMode; + void spiBegin() { #if PIN_EXISTS(SD_SS) OUT_WRITE(SD_SS_PIN, HIGH); @@ -59,9 +63,14 @@ void spiBegin() { //SET_OUTPUT(SD_MOSI_PIN); } -void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { +void spiInitEx(uint32_t clock, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Ignore the SPI pin hints. + _spi_clock = clock; + spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); + SPI.begin(); +} +void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Use Marlin data-rates uint32_t clock; switch (spiRate) { @@ -74,17 +83,42 @@ void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hi default: clock = 4000000; // Default from the SPI library } - spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - SPI.begin(); + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); } void spiClose() { SPI.end(); } -uint8_t spiRec() { +void spiSetBitOrder(int bitOrder) { + if (bitOrder == SPI_BITORDER_MSB) { + _spi_bitOrder = MSBFIRST; + } + else if (bitOrder == SPI_BITORDER_LSB) { + _spi_bitOrder = LSBFIRST; + } + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + +void spiSetClockMode(int clockMode) { + if (clockMode == SPI_CLKMODE_0) + _spi_clockMode = SPI_MODE0; + else if (clockMode == SPI_CLKMODE_1) + _spi_clockMode = SPI_MODE1; + else if (clockMode == SPI_CLKMODE_2) + _spi_clockMode = SPI_MODE2; + else if (clockMode == SPI_CLKMODE_3) + _spi_clockMode = SPI_MODE3; + else return; + + spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); +} + +uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); - uint8_t returnByte = SPI.transfer(0xFF); + uint8_t returnByte = SPI.transfer(txval); SPI.endTransaction(); return returnByte; //SPDR = 0xFF; @@ -92,7 +126,15 @@ uint8_t spiRec() { //return SPDR; } -void spiRead(uint8_t *buf, uint16_t nbyte) { +uint16_t spiRec16(uint16_t txval) { + SPI.beginTransaction(spiConfig); + uint16_t res = SPI.transfer16(txval); + SPI.endTransaction(); + return res; +} + +void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + memset(buf, txval, nbyte); SPI.beginTransaction(spiConfig); SPI.transfer(buf, nbyte); SPI.endTransaction(); @@ -115,8 +157,18 @@ void spiSend(uint8_t b) { //while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } } +void spiSend16(uint16_t v) { + SPI.beginTransaction(spiConfig); + SPI.transfer16(v); + SPI.endTransaction(); +} + void spiSendBlock(uint8_t token, const uint8_t *buf) { SPI.beginTransaction(spiConfig); + SPI.transfer(token); + for (uint16_t n = 0; n < 512; n++) + SPI.transfer(buf[n]); +#if 0 SPDR = token; for (uint16_t i = 0; i < 512; i += 2) { while (!TEST(SPSR, SPIF)) { /* nada */ }; @@ -125,13 +177,36 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { SPDR = buf[i + 1]; } while (!TEST(SPSR, SPIF)) { /* nada */ }; +#endif + SPI.endTransaction(); +} + +void spiWrite(const uint8_t *buf, uint16_t cnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer(buf[n]); SPI.endTransaction(); } -// Begin SPI transaction, set clock, bit order, data mode -void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - spiConfig = SPISettings(spiClock, bitOrder, dataMode); +void spiWrite16(const uint16_t *buf, uint16_t cnt) { SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < cnt; n++) + SPI.transfer16(buf[n]); + SPI.endTransaction(); +} + +void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer(val); + SPI.endTransaction(); +} + +void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + SPI.beginTransaction(spiConfig); + for (uint16_t n = 0; n < repcnt; n++) + SPI.transfer16(val); + SPI.endTransaction(); } #endif // SOFTWARE_SPI diff --git a/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h b/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h deleted file mode 100644 index 0c447ba4cb3d..000000000000 --- a/Marlin/src/HAL/TEENSY40_41/MarlinSPI.h +++ /dev/null @@ -1,26 +0,0 @@ -/** - * 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 . - * - */ -#pragma once - -#include - -using MarlinSPI = SPIClass; diff --git a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h index 6a8540927b97..4884d07d7cd3 100644 --- a/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/TEENSY40_41/inc/Conditionals_LCD.h @@ -21,6 +21,6 @@ */ #pragma once -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/TEENSY40_41." +#if HAS_FSMC_TFT + #error "Sorry! FSMC displays are not available for HAL/TEENSY40_41." #endif diff --git a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp new file mode 100644 index 000000000000..40957969f37d --- /dev/null +++ b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp @@ -0,0 +1,177 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 . + * + */ + +#include "../../../inc/MarlinConfig.h" +#include "HAL_NVIC.h" + +#if defined(STM32F1xx) + #ifdef STM32F1xx_CONNECTIVITY_LINE + // See STM32F1xx reference manual page 198 + #define VECTOR_TABLE_SIZE 83 + #else + // See STM32F1xx reference manual page 204 + #define VECTOR_TABLE_SIZE 75 + #endif + // Defined by GCC. + // The vector is located in flash memory, thus there may be no memory bus for write access + // wired into the CPU (hard fault at attempt). + extern void (*const g_pfnVectors[VECTOR_TABLE_SIZE])(); +#define _NVIC_HAS_DEFAULT_VECTOR +#elif defined(TARGET_LPC1768) + // See NXP UM10360 page 75ff + #define VECTOR_TABLE_SIZE 51 + #define IRQ_VECTOR_ALIGNMENT (1<<10) +#else + #error Unknown NVIC constants for platform. Please inspect hardware reference manuals and update the code! +#endif +#define IRQ_START_IDX 16 + +// The interrupt table used by installment. +alignas(IRQ_VECTOR_ALIGNMENT) static void (*_isrv_redirect[VECTOR_TABLE_SIZE])(); + +// From the ARM Cortex M3 reference manual. +struct vtor_reg_t { + uint32_t reserved1 : 9; + uint32_t TBLOFF : 21; + uint32_t reserved2 : 2; +}; + +// For debugging ;) +static bool _NVIC_IsVectorInCorrectAddressSpace(const void *vectaddr) { + uint32_t valaddr = (uint32_t)vectaddr; + return (valaddr >= (1<<9) && valaddr < (1<<30)); +} + +static void _NVIC_OnError() { + for (;;) { +#if PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(600); + OUT_WRITE(BEEPER_PIN, LOW); + delay(600); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } +} + +static vtor_reg_t& _SCB_VTOR = *(vtor_reg_t*)0xE000ED08; + +static unsigned int _vtor_refcount = 0; + +static void (*const* _NVIC_GetCurrentVector())() { + return (void (*const*)())( _SCB_VTOR.TBLOFF << 9 ); +} + +#ifndef _NVIC_HAS_DEFAULT_VECTOR +static void (*const*_nvic_default_vector)() = nullptr; +#endif + +static void (*const*_NVIC_GetDefaultVector())() { +#ifdef STM32F1xx + return g_pfnVectors; +#else + return _nvic_default_vector; +#endif +} + +static void _nvicFetchVectorEntriesFromDefault() { + memcpy(_isrv_redirect, _NVIC_GetDefaultVector(), sizeof(void*)*VECTOR_TABLE_SIZE); +} + +void nvicBegin() { + if (_NVIC_IsVectorInCorrectAddressSpace(_isrv_redirect) == false) + _NVIC_OnError(); +#ifndef _NVIC_HAS_DEFAULT_VECTOR + _nvic_default_vector = _NVIC_GetCurrentVector(); +#endif + _nvicFetchVectorEntriesFromDefault(); +} + +void nvicResetVector() { + _nvicFetchVectorEntriesFromDefault(); +} + +void nvicUpdateVector() { + if (_vtor_refcount == 0) { + memcpy(_isrv_redirect, (const void*)_NVIC_GetCurrentVector(), sizeof(_isrv_redirect)); + } +} + +void nvicSetHandler(uint32_t idx, void (*callback)()) { + if (idx >= VECTOR_TABLE_SIZE) + _NVIC_OnError(); + + _isrv_redirect[idx] = callback; + __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) +} + +void nvicSetIRQHandler(IRQn_Type irqn, void (*callback)()) { + nvicSetHandler(IRQ_START_IDX + (uint32_t)irqn, callback); +} + +void (*nvicGetHandler(uint32_t idx))() { + if (idx >= VECTOR_TABLE_SIZE) + _NVIC_OnError(); + + return _isrv_redirect[idx]; +} + +void nvicResetHandler(uint32_t idx) { + if (idx >= VECTOR_TABLE_SIZE) + _NVIC_OnError(); + + _isrv_redirect[idx] = _NVIC_GetDefaultVector()[idx]; +} + +void nvicResetIRQHandler(IRQn_Type irqn) { + nvicResetHandler(IRQ_START_IDX + (uint32_t)irqn); +} + +uint32_t nvicGetMaxHandlerCount() { + return VECTOR_TABLE_SIZE; +} + +void nvicInstallRedirect() { + _vtor_refcount++; + if (_vtor_refcount == 1) + { + _SCB_VTOR.TBLOFF = ( (uint32_t)&_isrv_redirect[0] >> 9 ); + __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) + } +} + +void nvicUninstallRedirect() { + if (_vtor_refcount == 1) + { + _SCB_VTOR.TBLOFF = ( (uint32_t)_NVIC_GetDefaultVector() >> 9 ); + __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) + } + _vtor_refcount--; +} \ No newline at end of file diff --git a/Marlin/src/HAL/DUE/MarlinSPI.h b/Marlin/src/HAL/shared/ARM/HAL_NVIC.h similarity index 57% rename from Marlin/src/HAL/DUE/MarlinSPI.h rename to Marlin/src/HAL/shared/ARM/HAL_NVIC.h index 0c447ba4cb3d..86ecc5f5bb3d 100644 --- a/Marlin/src/HAL/DUE/MarlinSPI.h +++ b/Marlin/src/HAL/shared/ARM/HAL_NVIC.h @@ -1,9 +1,6 @@ /** * 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 + * Copyright (c) 2022 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * 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 @@ -19,8 +16,19 @@ * along with this program. If not, see . * */ + #pragma once -#include +#include "../../platforms.h" -using MarlinSPI = SPIClass; +void nvicBegin(); +void nvicResetVector(); +void nvicUpdateVector(); +void nvicSetIRQHandler(IRQn_Type irqn, void (*callback)()); +void nvicSetHandler(uint32_t idx, void (*callback)()); +void (*nvicGetHandler(uint32_t idx))(); // for exception_arm.cpp +void nvicResetHandler(uint32_t idx); +void nvicResetIRQHandler(IRQn_Type irqn); +uint32_t nvicGetMaxHandlerCount(); // for exception_arm.cpp +void nvicInstallRedirect(); +void nvicUninstallRedirect(); \ No newline at end of file diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 60c188b7900d..1b8bc6f99bc5 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -55,44 +55,96 @@ #define SPI_SPEED_6 6 // Set SCK rate to 1/64 of max rate #define SPI_SPEED_DEFAULT 255 // Let the framework decide (usually recommended value) +// Transmission order for binary polynomes (8bit, 16bit). +// This is significant because numbers are sent bit-by-bit. +#define SPI_BITORDER_MSB 0 // most-significant bit first +#define SPI_BITORDER_LSB 1 // least-significant bit first +#define SPI_BITORDER_DEFAULT SPI_BITORDER_MSB + +#define SPI_CLKMODE_0 0 // data latched on first edge, clock starts LOW +#define SPI_CLKMODE_1 1 // data latched on the second edge, clock starts LOW +#define SPI_CLKMODE_2 2 // data latched on the first edge, clock starts HIGH +#define SPI_CLKMODE_3 3 // data latched on the second edge, clock starts HIGH +#define SPI_CLKMODE_DEFAULT SPI_CLKMODE_0 + // // Standard SPI functions // -// Initialize SPI bus +// Initialize SPI bus (global). void spiBegin(); +// Configure SPI based on maximum clock frequency/rate. +// Pass 0 for maxClockFreq to get a recommended default. +void spiInitEx(uint32_t maxClockFreq, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); + // Configure SPI for specified SPI speed void spiInit(uint8_t spiRate, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); // Terminates SPI connection. void spiClose(); -// Write single byte to SPI +// Specifies the bit-order, either LSB or MSB. +void spiSetBitOrder(int bitOrder); + +// Specifies the CLKMODE. +void spiSetClockMode(int mode); + +// Write single byte to SPI. +// The byte is sent in the requested bit-order. void spiSend(uint8_t b); +// Write a 16bit number to SPI. +// The number is sent in the requested bit-order. +void spiSend16(uint16_t v); + // Read single byte from SPI -uint8_t spiRec(); +// The byte is received in the requested bit-order. +uint8_t spiRec(uint8_t txval = 0xFF); + +// Read 16bit number from SPI. +// The number is received in the requested bit-order. +uint16_t spiRec16(uint16_t txval = 0xFFFF); // Read from SPI into buffer -void spiRead(uint8_t *buf, uint16_t nbyte); +// Each 8bit polynome is transmitted in the requested bit-order. +// Do not be confused with treating the buffer as an array of bits: +// the whole array is not ordered but each invidual byte is. +void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval = 0xFF); // Write token and then write from 512 byte buffer to SPI (for SD card) +// Similar to writing each byte by itself. void spiSendBlock(uint8_t token, const uint8_t *buf); -// Begin SPI transaction, set clock, bit order, data mode -// DEPRECATED: use spiInit -> spiSend/spiRead -> spiClose instead -//void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode); +// Send a buffer of 8bit numbers, in the correct bit-order, through SPI. +// Can be transmitted through DMA for optimal performance. +void spiWrite(const uint8_t *buf, uint16_t nbyte); -// -// Extended SPI functions taking a channel number (Hardware SPI only) -// +// Send a buffer of 16bit numbers, in the correct bit-order, through SPI. +// Similar to spiWrite but supports more data size. +void spiWrite16(const uint16_t *buf, uint16_t nbyte); + +// Send a repetition of 8bit numbers. +void spiWriteRepeat(uint8_t val, uint16_t repcnt); + +// Send a repetition of 16bit numbers. +void spiWriteRepeat16(uint16_t val, uint16_t repcnt); + +#if (defined(ESP_PLATFORM) || defined(STM32F1xx) || defined(STM32F4xx) || defined(TARGET_LPC1768)) && !defined(SOFTWARE_SPI) && defined(USE_SPI_DMA_TC) + +#define HAL_SPI_SUPPORTS_ASYNC + +// Requests asynchronous SPI transfer to peripheral (DMA). +void spiWriteAsync(const uint8_t *buf, uint16_t nbyte, void (*completeCallback)(void*) = nullptr, void *ud = nullptr); +void spiWriteAsync16(const uint16_t *buf, uint16_t ndata, void (*completeCallback)(void*) = nullptr, void *ud = nullptr); + +// Aborts a running async SPI transfer. +void spiAsyncAbort(); -// Write single byte to specified SPI channel -void spiSend(uint32_t chan, byte b); +// Waits for a running async SPI transfer. +void spiAsyncJoin(); -// Write buffer to specified SPI channel -void spiSend(uint32_t chan, const uint8_t *buf, size_t n); +// Returns true if the DMA transfer is still running. +bool spiAsyncIsRunning(); -// Read single byte from specified SPI channel -uint8_t spiRec(uint32_t chan); +#endif // async support \ No newline at end of file diff --git a/Marlin/src/HAL/shared/SPI/bufmgmt.h b/Marlin/src/HAL/shared/SPI/bufmgmt.h new file mode 100644 index 000000000000..f2a8d283c281 --- /dev/null +++ b/Marlin/src/HAL/shared/SPI/bufmgmt.h @@ -0,0 +1,65 @@ +/** + * 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 . + * + */ + +#pragma once + +namespace bufmgmt { + +template +inline uint16_t GetNumberIndexFromTotalByteIndex(uint16_t bidx) { + return (bidx / sizeof(numberType)); +} +template +inline uint16_t GetLocalByteIndexFromTotalByteIndex(uint16_t bidx) { + return (bidx % sizeof(numberType)); +} + +template +inline uint8_t GetByteFromNumber(numberType num, uint32_t byteNum, bool not_reverse) { + uint32_t bitNum; + if (not_reverse) { + // LSBFIRST + bitNum = (byteNum * 8); + } + else { + // MSBFIRST + bitNum = (((sizeof(numberType)-1) - byteNum) * 8); + } + return (num >> bitNum) & 0xFF; +} + +template +inline void WriteByteToNumber(numberType& num, uint32_t byteNum, uint8_t byteVal, bool not_reverse) { + uint32_t bitNum; + if (not_reverse) { + // LSBFIRST + bitNum = (byteNum * 8); + } + else { + // MSBFIRST + bitNum = (((sizeof(numberType)-1) - byteNum) * 8); + } + num &= ~((numberType)0xFF << bitNum); + num |= ((numberType)byteVal << bitNum); +} + +} // namespace bufmgmt \ No newline at end of file diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index e54661c77071..ff9361ade77c 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -164,6 +164,28 @@ struct __attribute__((packed)) ContextSavedFrame { } \ } while (0) +static void _except_infobeep(uint32_t code) { +#if ENABLED(BEEP_ON_SYSTEM_EXCEPTION) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(600); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(250); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code-1) + delay(250); + } + if (code > 0) + delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(700); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif +} + // Resume from a fault (if possible) so we can still use interrupt based code for serial output // In that case, we will not jump back to the faulty code, but instead to a dumping code and then a // basic loop with watchdog calling or manual resetting @@ -174,6 +196,8 @@ bool resume_from_fault() { // Reinit the serial link (might only work if implemented in each of your boards) MinSerial::init(); + _except_infobeep(lastCause); + MinSerial::TX("\n\n## Software Fault detected ##\n"); MinSerial::TX("Cause: "); MinSerial::TX(causestr[min(lastCause, (uint8_t)16)]); MinSerial::TX('\n'); @@ -192,6 +216,25 @@ bool resume_from_fault() { // Hard Fault Status Register MinSerial::TX("HFSR : "); MinSerial::TXHex(savedFrame.HFSR); MinSerial::TX('\n'); + if (false) + { + struct hfsr_t { + uint32_t reserved1 : 1; + uint32_t VECTTBL : 1; + uint32_t reserved2 : 28; + uint32_t FORCED : 1; + uint32_t DEBUGEVT : 1; + }; + union { + uint32_t HFSR_val; + hfsr_t HFSR; + }; + HFSR_val = savedFrame.HFSR; + + _except_infobeep(HFSR.VECTTBL); + _except_infobeep(HFSR.FORCED); + _except_infobeep(HFSR.DEBUGEVT); + } // Debug Fault Status Register MinSerial::TX("DFSR : "); MinSerial::TXHex(savedFrame.DFSR); MinSerial::TX('\n'); @@ -204,6 +247,85 @@ bool resume_from_fault() { // MemManage Fault Address Register MinSerial::TX("MMAR : "); MinSerial::TXHex(savedFrame.MMAR); MinSerial::TX('\n'); + // Bus Fault Status Register + if (false) + { + struct bfsr_t { + uint8_t IBUSERR : 1; + uint8_t PRECISERR : 1; + uint8_t IMPRECISERR : 1; + uint8_t UNSTKERR : 1; + uint8_t STKERR : 1; + uint8_t LSPERR : 1; + uint8_t BFARVALID : 1; + }; + union { + uint8_t BFSR_val; + bfsr_t BFSR; + }; + BFSR_val = (savedFrame.CFSR >> 8) & 0xFF; + + _except_infobeep(BFSR.IBUSERR); + _except_infobeep(BFSR.PRECISERR); + _except_infobeep(BFSR.IMPRECISERR); + _except_infobeep(BFSR.UNSTKERR); + _except_infobeep(BFSR.STKERR); + _except_infobeep(BFSR.LSPERR); + _except_infobeep(BFSR.BFARVALID); + } + + // MemManage Fault Status Register + if (false) + { + struct mmfsr_t { + uint8_t IACCVIOL : 1; + uint8_t DACCVIOL : 1; + uint8_t reserved1 : 1; + uint8_t MUNSTKERR : 1; + uint8_t MSTKERR : 1; + uint8_t reserved2 : 1; + uint8_t MMARVALID : 1; + }; + union { + uint8_t MMFSR_val; + mmfsr_t MMFSR; + }; + MMFSR_val = (savedFrame.CFSR) & 0xFF; + + _except_infobeep(MMFSR.IACCVIOL); + _except_infobeep(MMFSR.DACCVIOL); + _except_infobeep(MMFSR.MUNSTKERR); + _except_infobeep(MMFSR.MSTKERR); + _except_infobeep(MMFSR.MMARVALID); + } + + // Usage Fault Status Register + if (false) + { + struct ufsr_t { + uint16_t UNDEFINSTR : 1; + uint16_t INVSTATE : 1; + uint16_t INVPC : 1; + uint16_t NOCP : 1; + uint16_t reserved1 : 4; + uint16_t UNALIGNED : 1; + uint16_t DIVBYZERO : 1; + uint16_t reserved2 : 6; + }; + union { + uint16_t UFSR_val; + ufsr_t UFSR; + }; + UFSR_val = (savedFrame.CFSR >> 16) & 0xFFFF; + + _except_infobeep(UFSR.UNDEFINSTR); + _except_infobeep(UFSR.INVSTATE); + _except_infobeep(UFSR.INVPC); + _except_infobeep(UFSR.NOCP); + _except_infobeep(UFSR.UNALIGNED); + _except_infobeep(UFSR.DIVBYZERO); + } + // Bus Fault Address Register MinSerial::TX("BFAR : "); MinSerial::TXHex(savedFrame.BFAR); MinSerial::TX('\n'); @@ -243,6 +365,17 @@ extern "C" __attribute__((optimize("O0"))) void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long cause) { +#if ENABLED(BEEP_ON_SYSTEM_EXCEPTION) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); +#endif + // If you are using it'll stop here HALT_IF_DEBUGGING(); @@ -294,6 +427,10 @@ void CommonHandler_C(ContextStateFrame * frame, unsigned long lr, unsigned long resume_from_fault(); } +#if ENABLED(DYNAMIC_VECTORTABLE) +#include "../ARM/HAL_NVIC.h" +#endif + void hook_cpu_exceptions() { #if ENABLED(DYNAMIC_VECTORTABLE) // On ARM 32bits CPU, the vector table is like this: @@ -320,59 +457,28 @@ void hook_cpu_exceptions() { // So we'll simply mask the top 8 bits of the first handler as an hint of being in the flash or not -that's poor and will // probably break if the flash happens to be more than 128MB, but in this case, we are not magician, we need help from outside. - unsigned long *vecAddr = (unsigned long*)get_vtor(); - SERIAL_ECHOPGM("Vector table addr: "); - SERIAL_PRINTLN(get_vtor(), PrintBase::Hex); - - #ifdef VECTOR_TABLE_SIZE - uint32_t vec_size = VECTOR_TABLE_SIZE; - alignas(128) static unsigned long vectable[VECTOR_TABLE_SIZE] ; - #else - #ifndef IS_IN_FLASH - #define IS_IN_FLASH(X) (((unsigned long)X & 0xFF000000) == 0x08000000) - #endif - - // When searching for the end of the vector table, this acts as a limit not to overcome - #ifndef VECTOR_TABLE_SENTINEL - #define VECTOR_TABLE_SENTINEL 80 - #endif - - // Find the vector table size - uint32_t vec_size = 1; - while (IS_IN_FLASH(vecAddr[vec_size]) && vec_size < VECTOR_TABLE_SENTINEL) - vec_size++; - - // We failed to find a valid vector table size, let's abort hooking up - if (vec_size == VECTOR_TABLE_SENTINEL) return; - // Poor method that's wasting RAM here, but allocating with malloc and alignment would be worst - // 128 bytes alignment is required for writing the VTOR register - alignas(128) static unsigned long vectable[VECTOR_TABLE_SENTINEL]; - - SERIAL_ECHOPGM("Detected vector table size: "); - SERIAL_PRINTLN(vec_size, PrintBase::Hex); - #endif - - uint32_t defaultFaultHandler = vecAddr[(unsigned)7]; - // Copy the current vector table into the new table + // Undocumented!!! Use with caution!!! (peeking into reserved vector entries) + auto defaultFaultHandler = nvicGetHandler(7u); + // Replace all default handlers with our own handler. + uint32_t vec_size = nvicGetMaxHandlerCount(); for (uint32_t i = 0; i < vec_size; i++) { - vectable[i] = vecAddr[i]; // Replace all default handler by our own handler - if (vectable[i] == defaultFaultHandler) - vectable[i] = (unsigned long)&CommonHandler_ASM; + if (nvicGetHandler(i) == defaultFaultHandler) + nvicSetHandler(i, CommonHandler_ASM); } // Let's hook now with our functions - vectable[(unsigned long)hook_get_hardfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; - vectable[(unsigned long)hook_get_memfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; - vectable[(unsigned long)hook_get_busfault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; - vectable[(unsigned long)hook_get_usagefault_vector_address(0)] = (unsigned long)&CommonHandler_ASM; + nvicSetHandler((unsigned long)hook_get_hardfault_vector_address(0), CommonHandler_ASM); + nvicSetHandler((unsigned long)hook_get_memfault_vector_address(0), CommonHandler_ASM); + nvicSetHandler((unsigned long)hook_get_busfault_vector_address(0), CommonHandler_ASM); + nvicSetHandler((unsigned long)hook_get_usagefault_vector_address(0), CommonHandler_ASM); // Finally swap with our own vector table // This is supposed to be atomic, but let's do that with interrupt disabled - HW_REG(0xE000ED08) = (unsigned long)vectable | _BV32(29); // 29th bit is for telling the CPU the table is now in SRAM (should be present already) + nvicInstallRedirect(); // reference counted. - SERIAL_ECHOLNPGM("Installed fault handlers"); + SERIAL_ECHOLNPGM("Dynamically installed fault handlers"); #endif } diff --git a/Marlin/src/HAL/shared/tft/tft_spi.cpp b/Marlin/src/HAL/shared/tft/tft_spi.cpp new file mode 100644 index 000000000000..9823e019a278 --- /dev/null +++ b/Marlin/src/HAL/shared/tft/tft_spi.cpp @@ -0,0 +1,155 @@ +/** + * 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 . + * + */ + +#include "../../platforms.h" + +#include "../../../inc/MarlinConfig.h" + +#if HAS_SPI_TFT + +#include "tft_spi.h" + +// SPI can have different baudrates depending on read or write functionality. +#ifndef TFT_BAUDRATE_READ + // Default. + #define TFT_BAUDRATE_READ 0 +#endif + +#ifndef TFT_BAUDRATE_WRITE + #define TFT_BAUDRATE_WRITE TFT_BAUDRATE_READ +#endif + +void TFT_SPI::Init() { + + OUT_WRITE(TFT_A0_PIN, HIGH); + OUT_WRITE(TFT_CS_PIN, HIGH); +} + +void TFT_SPI::DataTransferBegin(eSPIMode spiMode) { + int pin_miso = -1; +#if PIN_EXISTS(TFT_MISO) + pin_miso = TFT_MISO_PIN; +#endif + spiInitEx((spiMode == eSPIMode::READ) ? TFT_BAUDRATE_READ : TFT_BAUDRATE_WRITE, TFT_SCK_PIN, pin_miso, TFT_MOSI_PIN, TFT_CS_PIN); +} + +void TFT_SPI::DataTransferEnd(void) { + spiClose(); +} + +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + +uint32_t TFT_SPI::GetID() { + uint32_t id; + id = ReadID(LCD_READ_ID); + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { + id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } + return id; +} + +uint32_t TFT_SPI::ReadID(uint16_t Reg) { + #if PIN_EXISTS(TFT_MISO) + uint32_t Data = 0; + + DataTransferBegin(eSPIMode::READ); + WriteReg8(Reg); + + spiRead( &Data, 4 ); + DataTransferEnd(); + + return Data >> 7; + #else + return 0; + #endif +} + +bool TFT_SPI::isBusy() { +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + return spiAsyncIsRunning(); +#else + return false; +#endif +} + +void TFT_SPI::Abort() { +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + spiAsyncAbort(); +#endif +} + +void TFT_SPI::Transmit(uint16_t Data) { + spiSend16(Data); +} + +void TFT_SPI::Transmit8(uint8_t Data) { + spiSend(Data); +} + +void TFT_SPI::TransmitDMA(const uint16_t *Data, uint16_t Count) { + DataTransferBegin(eSPIMode::WRITE); + spiWrite16(Data, Count); + DataTransferEnd(); +} + +void TFT_SPI::TransmitRepeat(const uint16_t Data, uint16_t Count) { + + DataTransferBegin(eSPIMode::WRITE); + spiWriteRepeat16(Data, Count); + DataTransferEnd(); +} + +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + +static void (*_txcomplete_callback)(void*) = nullptr; +void *_txcomplete_ud = nullptr; + +void TFT_SPI::_TXComplete( void *ud ) +{ + auto cb = _txcomplete_callback; + auto _ud = _txcomplete_ud; + + DataTransferEnd(); + + if (cb) { + cb( _ud ); + } +} + +void TFT_SPI::TransmitDMA_Async(const uint16_t *Data, uint16_t Count, void (*completeCallback)(void*), void *ud) { + DataTransferBegin(eSPIMode::WRITE); + + _txcomplete_callback = completeCallback; + _txcomplete_ud = ud; + + spiWriteAsync16(Data, Count, TFT_SPI::_TXComplete, nullptr); +} + +#endif + +#endif // HAS_SPI_TFT \ No newline at end of file diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.h b/Marlin/src/HAL/shared/tft/tft_spi.h similarity index 50% rename from Marlin/src/HAL/STM32/tft/tft_spi.h rename to Marlin/src/HAL/shared/tft/tft_spi.h index ce853c968880..c081e540e1c1 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.h +++ b/Marlin/src/HAL/shared/tft/tft_spi.h @@ -21,14 +21,6 @@ */ #pragma once -#ifdef STM32F1xx - #include "stm32f1xx_hal.h" -#elif defined(STM32F4xx) - #include "stm32f4xx_hal.h" -#else - #error SPI TFT is currently only supported on STM32F1 and STM32F4 hardware. -#endif - #ifndef LCD_READ_ID #define LCD_READ_ID 0x04 // Read display identification information (0xD3 on ILI9341) #endif @@ -36,10 +28,10 @@ #define LCD_READ_ID4 0xD3 // Read display identification information (0xD3 on ILI9341) #endif -#define DATASIZE_8BIT SPI_DATASIZE_8BIT -#define DATASIZE_16BIT SPI_DATASIZE_16BIT #define TFT_IO_DRIVER TFT_SPI +#define TFT_SUPPORTS_8BIT + class TFT_SPI { enum class eSPIMode @@ -49,55 +41,43 @@ class TFT_SPI { }; private: - static SPI_HandleTypeDef SPIx; - static uint32_t ReadID(uint16_t Reg); static void Transmit(uint16_t Data); - static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); - #if ENABLED(USE_SPI_DMA_TC) - static void TransmitDMA_IT(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count); + static void Transmit8(uint8_t Data); + static void TransmitDMA(const uint16_t *Data, uint16_t Count); + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + static void _TXComplete(void *ud); + static void TransmitDMA_Async(const uint16_t *Data, uint16_t Count, void (*completeCallback)(void*) = nullptr, void *ud = nullptr); #endif - - static void HALPrepare(eSPIMode spiMode); - static void HALDismantle(void); - - static uint8_t _GetClockDivider( uint32_t spibasefreq, uint32_t speed ); - -#if PIN_EXISTS(TFT_MISO) - static uint8_t clkdiv_read; -#endif - static uint8_t clkdiv_write; - - static bool active_transfer; - static bool active_dma; + static void TransmitRepeat(uint16_t val, uint16_t repcnt); public: - static DMA_HandleTypeDef DMAtx; - static void Init(); static uint32_t GetID(); static bool isBusy(); static void Abort(); - static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT, eSPIMode spiMode = eSPIMode::WRITE); + static void DataTransferBegin(eSPIMode spiMode = eSPIMode::WRITE); static void DataTransferEnd(); - static void DataTransferAbort(); + // Call DataTransferBegin for these two methods. static void WriteData(uint16_t Data) { Transmit(Data); } - static void WriteReg(uint16_t Reg) { WRITE(TFT_A0_PIN, LOW); Transmit(Reg); WRITE(TFT_A0_PIN, HIGH); } + static void WriteData8(uint8_t Data) { Transmit8(Data); } + static void WriteReg(uint16_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } + static void WriteReg8(uint8_t Reg) { OUT_WRITE(TFT_A0_PIN, LOW); Transmit8(Reg); OUT_WRITE(TFT_A0_PIN, HIGH); } - static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); } + // Do not call DataTransferBegin for the following methods. + static void WriteSequence(const uint16_t *Data, uint16_t Count) { TransmitDMA(Data, Count); } - #if ENABLED(USE_SPI_DMA_TC) - static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { TransmitDMA_IT(DMA_MINC_ENABLE, Data, Count); } + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + static void WriteSequenceAsync(const uint16_t *Data, uint16_t Count, void (*completeCallback)(void*) = nullptr, void *ud = nullptr) { TransmitDMA_Async(Data, Count, completeCallback, ud); } #endif - static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } + static void WriteMultiple(uint16_t Color, uint16_t Count) { TransmitRepeat(Color, 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); + TransmitRepeat(Color, Count > 0xFFFF ? 0xFFFF : Count); Count = Count > 0xFFFF ? Count - 0xFFFF : 0; } } diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/shared/tft/xpt2046.cpp similarity index 50% rename from Marlin/src/HAL/LPC1768/tft/xpt2046.cpp rename to Marlin/src/HAL/shared/tft/xpt2046.cpp index 9c1e158981da..ebc671ae6e7a 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/shared/tft/xpt2046.cpp @@ -20,44 +20,62 @@ * */ +#include "../../platforms.h" + #include "../../../inc/MarlinConfig.h" #if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS #include "xpt2046.h" -#include - -uint16_t delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - #include - - SPIClass XPT2046::SPIx(TOUCH_BUTTONS_HW_SPI_DEVICE); - static void touch_spi_init(uint8_t spiRate) { - XPT2046::SPIx.setModule(TOUCH_BUTTONS_HW_SPI_DEVICE); - XPT2046::SPIx.setClock(SPI_CLOCK_DIV128); - XPT2046::SPIx.setBitOrder(MSBFIRST); - XPT2046::SPIx.setDataMode(SPI_MODE0); - XPT2046::SPIx.setDataSize(DATA_SIZE_8BIT); - } +#ifndef TOUCH_BAUDRATE + // Default. + #define TOUCH_BAUDRATE 0 #endif void XPT2046::Init() { - SET_INPUT(TOUCH_MISO_PIN); - SET_OUTPUT(TOUCH_MOSI_PIN); - SET_OUTPUT(TOUCH_SCK_PIN); OUT_WRITE(TOUCH_CS_PIN, HIGH); +#if 0 + // DEBUG PIN. + while (true) { + OUT_WRITE(EXP1_01_PIN, HIGH); + delay(1000); + OUT_WRITE(EXP1_01_PIN, LOW); + + // HIGH + OUT_WRITE(TOUCH_CS_PIN, HIGH); + delay(10000); + + OUT_WRITE(EXP1_01_PIN, HIGH); + delay(500); + OUT_WRITE(EXP1_01_PIN, LOW); + delay(500); + OUT_WRITE(EXP1_01_PIN, HIGH); + delay(500); + OUT_WRITE(EXP1_01_PIN, LOW); + + // LOW + OUT_WRITE(TOUCH_CS_PIN, LOW); + delay(10000); + } +#endif + #if PIN_EXISTS(TOUCH_INT) // Optional Pendrive interrupt pin SET_INPUT(TOUCH_INT_PIN); #endif - TERN_(TOUCH_BUTTONS_HW_SPI, touch_spi_init(SPI_SPEED_6)); + getRawData(XPT2046_Z1); +} + +void XPT2046::DataTransferBegin(void) { + spiInitEx(TOUCH_BAUDRATE, TOUCH_SCK_PIN, TOUCH_MISO_PIN, TOUCH_MOSI_PIN, TOUCH_CS_PIN); + spiSetClockMode(SPI_CLKMODE_3); +} - // Read once to enable pendrive status pin - getRawData(XPT2046_X); +void XPT2046::DataTransferEnd(void) { + spiClose(); } bool XPT2046::isTouched() { @@ -78,54 +96,37 @@ bool XPT2046::getRawPoint(int16_t *x, int16_t *y) { return isTouched(); } +inline uint16_t _delta(uint16_t a, uint16_t b) { return a > b ? a - b : b - a; } + uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { uint16_t data[3]; DataTransferBegin(); - TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.begin()); - for (uint16_t i = 0; i < 3 ; i++) { - IO(coordinate); - data[i] = (IO() << 4) | (IO() >> 4); + // Perform a burst-read of 3 values of the coordinate, then + // send a good approximation. + + for (int i = 0; i < 3; i++) { + spiSend(coordinate); + uint16_t res = (uint16_t)spiRec(0) << 4; + res |= (uint16_t)spiRec(0) >> 4; + data[i] = res; } - TERN_(TOUCH_BUTTONS_HW_SPI, SPIx.end()); DataTransferEnd(); - uint16_t delta01 = delta(data[0], data[1]), - delta02 = delta(data[0], data[2]), - delta12 = delta(data[1], data[2]); + uint16_t delta01 = _delta(data[0], data[1]); + uint16_t delta02 = _delta(data[0], data[2]); + uint16_t delta12 = _delta(data[1], data[2]); - if (delta01 > delta02 || delta01 > delta12) - data[delta02 > delta12 ? 0 : 1] = data[2]; - - return (data[0] + data[1]) >> 1; -} - -uint16_t XPT2046::IO(uint16_t data) { - return TERN(TOUCH_BUTTONS_HW_SPI, HardwareIO, SoftwareIO)(data); -} - -extern uint8_t spiTransfer(uint8_t b); - -#if ENABLED(TOUCH_BUTTONS_HW_SPI) - uint16_t XPT2046::HardwareIO(uint16_t data) { - return SPIx.transfer(data & 0xFF); - } -#endif - -uint16_t XPT2046::SoftwareIO(uint16_t data) { - uint16_t result = 0; - - for (uint8_t j = 0x80; j; j >>= 1) { - WRITE(TOUCH_SCK_PIN, LOW); - WRITE(TOUCH_MOSI_PIN, data & j ? HIGH : LOW); - if (READ(TOUCH_MISO_PIN)) result |= j; - WRITE(TOUCH_SCK_PIN, HIGH); + if (delta01 > delta02 || delta01 > delta12) { + if (delta02 > delta12) + data[0] = data[2]; + else + data[1] = data[2]; } - WRITE(TOUCH_SCK_PIN, LOW); - return result; + return (data[0] + data[1]) >> 1; } -#endif // HAS_TFT_XPT2046 +#endif // HAS_TFT_XPT2046 \ No newline at end of file diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/shared/tft/xpt2046.h similarity index 77% rename from Marlin/src/HAL/STM32/tft/xpt2046.h rename to Marlin/src/HAL/shared/tft/xpt2046.h index 87f09063f683..e6a7363ff018 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/shared/tft/xpt2046.h @@ -21,16 +21,8 @@ */ #pragma once -#ifdef STM32F1xx - #include -#elif defined(STM32F4xx) - #include -#endif - #include "../../../inc/MarlinConfig.h" -// Not using regular SPI interface by default to avoid SPI mode conflicts with other SPI devices - #if !PIN_EXISTS(TOUCH_MISO) #error "TOUCH_MISO_PIN is not defined." #elif !PIN_EXISTS(TOUCH_MOSI) @@ -62,10 +54,6 @@ enum XPTCoordinate : uint8_t { class XPT2046 { private: - static SPI_HandleTypeDef SPIx; - - static uint8_t _GetClockDivider(uint32_t spibasefreq, uint32_t speed); - static bool isBusy() { return false; } static uint16_t getRawData(const XPTCoordinate coordinate); @@ -73,12 +61,6 @@ class XPT2046 { static void DataTransferBegin(); static void DataTransferEnd(); - static uint16_t HardwareIO(uint16_t data); - static uint16_t SoftwareIO(uint16_t data); - static uint16_t IO(uint16_t data = 0) { return SPIx.Instance ? HardwareIO(data) : SoftwareIO(data); } - - static void HALPrepare(void); - static void HALDismantle(void); public: static void Init(); diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 142a1daee579..9e8ff62872bd 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1138,6 +1138,8 @@ void setup() { FASTIO_INIT(); #endif + spiBegin(); + #ifdef BOARD_PREINIT BOARD_PREINIT(); // Low-level init (before serial init) #endif diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index 772bb68de42e..e5f3711623af 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -24,7 +24,7 @@ void dac084s085::begin() { SET_OUTPUT(DAC1_SYNC_PIN); #endif cshigh(); - spiBegin(); + spiInitEx(5000000); //init onboard DAC DELAY_US(2); @@ -50,6 +50,8 @@ void dac084s085::begin() { WRITE(DAC1_SYNC_PIN, HIGH); #endif + spiClose(); + return; } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index a96f3100ca20..5e2f004b4d5d 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -88,15 +88,18 @@ class TMCMarlin : public TMC, public TMCStorage { TMCMarlin(const uint16_t cs_pin, const float RS) : TMC(cs_pin, RS) {} - TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t axis_chain_index) : + TMCMarlin(const uint16_t cs_pin, const float RS, const int8_t axis_chain_index) : TMC(cs_pin, RS, axis_chain_index) {} TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : TMC(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index, bool softSPI) : + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const int8_t axis_chain_index, bool softSPI) : TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index, softSPI) {} + TMCMarlin(const uint16_t CS, const float RS, TMCSPIInterface *const spiMan, const int8_t axis_chain_index) : + TMC(CS, RS, spiMan, axis_chain_index) + {} uint16_t rms_current() { return TMC::rms_current(); } void rms_current(uint16_t mA) { this->val_mA = mA; @@ -287,15 +290,18 @@ class TMCMarlin : public TMC220 template class TMCMarlin : public TMC2660Stepper, public TMCStorage { public: - TMCMarlin(const uint16_t cs_pin, const float RS, const uint8_t) : + TMCMarlin(const uint16_t cs_pin, const float RS, const int8_t) : TMC2660Stepper(cs_pin, RS) {} TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, bool softSPI) : TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) {} - TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t, bool softSPI) : + TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const int8_t, bool softSPI) : TMC2660Stepper(CS, RS, pinMOSI, pinMISO, pinSCK, softSPI) {} + TMCMarlin(const uint16_t CS, const float RS, TMCSPIInterface *const spiMan, const int8_t) : + TMC2660Stepper(CS, RS, spiMan) + {} uint16_t rms_current() { return TMC2660Stepper::rms_current(); } void rms_current(const uint16_t mA) { this->val_mA = mA; diff --git a/Marlin/src/gcode/control/M993_M994.cpp b/Marlin/src/gcode/control/M993_M994.cpp index 598a73fab756..28bd7812575c 100644 --- a/Marlin/src/gcode/control/M993_M994.cpp +++ b/Marlin/src/gcode/control/M993_M994.cpp @@ -52,6 +52,7 @@ void GcodeSuite::M993() { if (addr % (COUNT(buf) * 10) == 0) SERIAL_CHAR('.'); } SERIAL_ECHOLNPGM(" done"); + W25QXX.close(); card.closefile(); } @@ -81,6 +82,7 @@ void GcodeSuite::M994() { if (addr % (COUNT(buf) * 10) == 0) SERIAL_CHAR('.'); } SERIAL_ECHOLNPGM(" done"); + W25QXX.close(); card.closefile(); } diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index a2af15397015..58f829f4a4f0 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -37,7 +37,7 @@ #endif #if ENABLED(TFTGLCD_PANEL_SPI) - #include + #include "../../HAL/shared/HAL_SPI.h" #else #include #endif @@ -46,6 +46,8 @@ #include "../marlinui.h" #include "../../libs/numtostr.h" +#include "../../HAL/shared/HAL_SPI.h" + #include "../../sd/cardreader.h" #include "../../module/temperature.h" #include "../../module/printcounter.h" @@ -137,25 +139,12 @@ static uint8_t cour_line; static uint8_t picBits, ledBits, hotBits; static uint8_t PanelDetected = 0; -// Different platforms use different SPI methods -#if ANY(__AVR__, TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) - #define SPI_SEND_ONE(V) SPI.transfer(V); - #define SPI_SEND_TWO(V) SPI.transfer16(V); -#elif EITHER(STM32F4xx, STM32F1xx) - #define SPI_SEND_ONE(V) SPI.transfer(V, SPI_CONTINUE); - #define SPI_SEND_TWO(V) SPI.transfer16(V, SPI_CONTINUE); -#elif defined(ARDUINO_ARCH_ESP32) - #define SPI_SEND_ONE(V) SPI.write(V); - #define SPI_SEND_TWO(V) SPI.write16(V); -#endif +// Shared SPI methods thanks to HAL SPI. +#define SPI_SEND_ONE(V) spiSend(V) +#define SPI_SEND_TWO(V) spiSend16(V) -#if ANY(__AVR__, ARDUINO_ARCH_SAM, __SAMD51__, __MK20DX256__, __MK64FX512__) - #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L); -#elif EITHER(STM32F4xx, STM32F1xx) - #define SPI_SEND_SOME(V,L,Z) SPI.transfer(&V[Z], L, SPI_CONTINUE); -#elif ANY(TARGET_LPC1768, __STM32F1__, ARDUINO_ARCH_ESP32) - #define SPI_SEND_SOME(V,L,Z) do{ for (uint16_t i = 0; i < L; i++) SPI_SEND_ONE(V[(Z)+i]); }while(0) -#endif +// We have got a buffer-transfer helper in the HAL SPI aswell. +#define SPI_SEND_SOME(V,L,Z) spiWrite(&V[Z], L) // Constructor TFTGLCD::TFTGLCD() {} @@ -167,12 +156,29 @@ void TFTGLCD::clear_buffer() { picBits = ledBits = 0; } +#if ENABLED(TFTGLCD_PANEL_SPI) +void TFTGLCD::_spi_prepare(void) { + int pin_sck = -1; + #ifdef TFTGLCD_SCK + pin_sck = TFTGLCD_SCK; + #endif + int pin_miso = -1; + #ifdef TFTGLCD_MISO + pin_miso = TFTGLCD_MISO; + #endif + int pin_mosi = -1; + #ifdef TFTGLCD_MOSI + pin_mosi = TFTGLCD_MOSI; + #endif + spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED), pin_sck, pin_miso, pin_mosi, TFTGLCD_CS); +} +#endif + // Clear panel's screen void TFTGLCD::clr_screen() { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(CLR_SCREEN); WRITE(TFTGLCD_CS, HIGH); @@ -204,8 +210,7 @@ void TFTGLCD::print(const char *line) { void TFTGLCD::print_line() { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(LCD_PUT); SPI_SEND_ONE(cour_line); @@ -228,8 +233,7 @@ void TFTGLCD::print_screen() { framebuffer[FBSIZE - 1] = ledBits; #if ENABLED(TFTGLCD_PANEL_SPI) // Send all framebuffer to panel - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(LCD_WRITE); SPI_SEND_SOME(framebuffer, FBSIZE, 0); @@ -259,8 +263,7 @@ void TFTGLCD::print_screen() { void TFTGLCD::setContrast(uint16_t contrast) { if (!PanelDetected) return; #if ENABLED(TFTGLCD_PANEL_SPI) - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(CONTRAST); SPI_SEND_ONE((uint8_t)contrast); @@ -281,8 +284,7 @@ uint8_t MarlinUI::read_slow_buttons() { if (!PanelDetected) return 0; #if ENABLED(TFTGLCD_PANEL_SPI) uint8_t b = 0; - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(READ_ENCODER); #ifndef STM32F4xx @@ -318,8 +320,7 @@ void MarlinUI::buzz(const long duration, const uint16_t freq) { if (!PanelDetected) return; if (!sound_on) return; #if ENABLED(TFTGLCD_PANEL_SPI) - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(BUZZER); SPI_SEND_TWO((uint16_t)duration); @@ -345,9 +346,7 @@ void MarlinUI::init_lcd() { // SPI speed must be less 10MHz SET_OUTPUT(TFTGLCD_CS); WRITE(TFTGLCD_CS, HIGH); - // TODO: hint the SPI pins here. - spiBegin(); - spiInit(TERN(__STM32F1__, SPI_QUARTER_SPEED, SPI_FULL_SPEED)); + _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(GET_LCD_ROW); t = SPI_SEND_ONE(GET_SPI_DATA); diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h index c399b907e460..8534384c0a68 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.h @@ -42,6 +42,9 @@ // Create LCD class instance and chipset-specific information class TFTGLCD { private: +#if ENABLED(TFTGLCD_PANEL_SPI) + void _spi_prepare(void); +#endif public: TFTGLCD(); void clear_buffer(); diff --git a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp index f1bf9d032ec8..6d3c08e05c2e 100644 --- a/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp +++ b/Marlin/src/lcd/dogm/u8g_dev_tft_upscale_from_128x64.cpp @@ -469,18 +469,24 @@ uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_p break; case U8G_COM_MSG_WRITE_BYTE: - tftio.DataTransferBegin(DATASIZE_8BIT); + tftio.DataTransferBegin(); + #if ENABLED(TFT_SUPPORTS_8BIT) + if (isCommand) + tftio.WriteReg8(arg_val); + else + tftio.WriteData8(arg_val); + #else if (isCommand) tftio.WriteReg(arg_val); else - tftio.WriteData((uint16_t)arg_val); + tftio.WriteData(arg_val); + #endif tftio.DataTransferEnd(); break; case U8G_COM_MSG_WRITE_SEQ: - tftio.DataTransferBegin(DATASIZE_16BIT); - for (uint8_t i = 0; i < arg_val; i += 2) - tftio.WriteData(*(uint16_t *)(((uintptr_t)arg_ptr) + i)); + tftio.DataTransferBegin(); + tftio.WriteSequence((uint16_t*)arg_ptr, arg_val); tftio.DataTransferEnd(); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 30f778e9f51c..5ba2901992fe 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -30,12 +30,11 @@ namespace FTDI { #ifndef CLCD_USE_SOFT_SPI #ifdef CLCD_SPI_BUS - SPIClass EVE_SPI(CLCD_SPI_BUS); + #error CLCD_SPI_BUS not implemented here (please map to pins instead and pass them to spiInitEx below). #endif #ifndef CLCD_HW_SPI_SPEED #define CLCD_HW_SPI_SPEED 8000000 >> SD_SPI_SPEED #endif - SPISettings SPI::spi_settings(CLCD_HW_SPI_SPEED, MSBFIRST, SPI_MODE0); #endif void SPI::spi_init() { @@ -63,8 +62,6 @@ namespace FTDI { WRITE(CLCD_SOFT_SPI_SCLK, 0); SET_INPUT_PULLUP(CLCD_SOFT_SPI_MISO); - #else - SPI_OBJ.begin(); #endif } @@ -116,7 +113,7 @@ namespace FTDI { // CLCD SPI - Chip Select void SPI::spi_ftdi_select() { #ifndef CLCD_USE_SOFT_SPI - SPI_OBJ.beginTransaction(spi_settings); + spiInitEx(CLCD_HW_SPI_SPEED); // TODO: can we define any pins here? #endif WRITE(CLCD_SPI_CS, 0); #ifdef CLCD_SPI_EXTRA_CS @@ -132,7 +129,7 @@ namespace FTDI { WRITE(CLCD_SPI_EXTRA_CS, 1); #endif #ifndef CLCD_USE_SOFT_SPI - SPI_OBJ.endTransaction(); + spiClose(); #endif } @@ -140,7 +137,7 @@ namespace FTDI { // Serial SPI Flash SPI - Chip Select void SPI::spi_flash_select() { #ifndef CLCD_USE_SOFT_SPI - SPI_OBJ.beginTransaction(spi_settings); + spiInitEx(CLCD_HW_SPI_SPEED); // TODO: can we define any pins here? #endif WRITE(SPI_FLASH_SS, 0); delayMicroseconds(1); @@ -150,7 +147,7 @@ namespace FTDI { void SPI::spi_flash_deselect() { WRITE(SPI_FLASH_SS, 1); #ifndef CLCD_USE_SOFT_SPI - SPI_OBJ.endTransaction(); + spiClose(); #endif } #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h index 7adf7e9c53a2..f4a9af4f6179 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.h @@ -23,23 +23,12 @@ #pragma once #ifndef CLCD_USE_SOFT_SPI - #include + #include "../../../../../HAL/shared/HAL_SPI.h" #endif namespace FTDI { - #if !defined(CLCD_SPI_BUS) || defined(CLCD_USE_SOFT_SPI) - #define SPI_OBJ ::SPI - #else - extern SPIClass EVE_SPI; - #define SPI_OBJ EVE_SPI - #endif - namespace SPI { - #ifndef CLCD_USE_SOFT_SPI - extern SPISettings spi_settings; - #endif - uint8_t _soft_spi_xfer (uint8_t val); void _soft_spi_send (uint8_t val); @@ -55,7 +44,7 @@ namespace FTDI { #ifdef CLCD_USE_SOFT_SPI return _soft_spi_xfer(0x00); #else - return SPI_OBJ.transfer(0x00); + return spiRec(0x00); #endif }; @@ -63,7 +52,7 @@ namespace FTDI { #ifdef CLCD_USE_SOFT_SPI _soft_spi_send(val); #else - SPI_OBJ.transfer(val); + spiSend(val); #endif }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 6b2dc9eb4498..9a4ad5ca2e97 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -32,7 +32,11 @@ #include #ifndef CLCD_USE_SOFT_SPI +#ifdef __MARLIN_FIRMWARE__ + #include "../../../../HAL/shared/HAL_SPI.h" +#else #include +#endif #endif namespace fast_io { diff --git a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp index 42abd4bf6453..6d0e80f5bfd0 100644 --- a/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp +++ b/Marlin/src/lcd/extui/mks_ui/SPI_TFT.cpp @@ -30,8 +30,6 @@ #include "../../../inc/MarlinConfig.h" -#include - #include "draw_ui.h" TFT SPI_TFT; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 6a8333fd66df..7b51a6a68736 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -32,7 +32,7 @@ #include "draw_ui.h" -#include +#include "../../../HAL/shared/HAL_SPI.h" #include "../../../MarlinCore.h" // for marlin_state #include "../../../sd/cardreader.h" @@ -243,6 +243,7 @@ void update_spi_flash() { W25QXX.SPI_FLASH_SectorErase(VAR_INF_ADDR); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&gCfgItems, VAR_INF_ADDR, sizeof(gCfgItems)); W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); + W25QXX.close(); } void update_gcode_command(int addr, uint8_t *s) { @@ -262,11 +263,13 @@ void update_gcode_command(int addr, uint8_t *s) { default: break; } W25QXX.SPI_FLASH_BufferWrite((uint8_t *)&command_buf, GCODE_COMMAND_ADDR, sizeof(command_buf)); + W25QXX.close(); } void get_gcode_command(int addr, uint8_t *d) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead((uint8_t *)d, addr, 100); + W25QXX.close(); } lv_style_t tft_style_scr; @@ -636,6 +639,7 @@ char *creat_title_text() { W25QXX.init(SPI_QUARTER_SPEED); if (row < 20) W25QXX.SPI_FLASH_SectorErase(BAK_VIEW_ADDR_TFT35 + row * 4096); W25QXX.SPI_FLASH_BufferWrite(bmp_public_buf, BAK_VIEW_ADDR_TFT35 + row * 400, 400); + W25QXX.close(); #endif row++; card.abortFilePrintNow(); @@ -678,11 +682,12 @@ char *creat_title_text() { void draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { int index; int y_off = 0; - W25QXX.init(SPI_QUARTER_SPEED); for (index = 0; index < 10; index++) { // 200*200 #if HAS_BAK_VIEW_IN_FLASH if (sel == 1) { + W25QXX.init(SPI_QUARTER_SPEED); flash_view_Read(bmp_public_buf, 8000); // 20k + W25QXX.close(); } else { default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k @@ -696,7 +701,6 @@ char *creat_title_text() { y_off++; } - W25QXX.init(SPI_QUARTER_SPEED); } void disp_pre_gcode(int xpos_pixel, int ypos_pixel) { @@ -1374,7 +1378,7 @@ void print_time_count() { void LV_TASK_HANDLER() { - if (TERN1(USE_SPI_DMA_TC, !get_lcd_dma_lock())) + if (TERN1(HAL_SPI_SUPPORTS_ASYNC, !get_lcd_dma_lock())) lv_task_handler(); #if BOTH(MKS_TEST, SDSUPPORT) diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index c618127980bb..1a85adafd7c2 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -256,6 +256,7 @@ uint32_t lv_get_pic_addr(uint8_t *Pname) { return addr; } } + W25QXX.close(); return addr; } @@ -275,6 +276,7 @@ void spiFlashErase_PIC() { hal.watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase((pic_sectorcnt + 1) * 64 * 1024); } + W25QXX.close(); } #if HAS_SPI_FLASH_FONT @@ -285,6 +287,7 @@ void spiFlashErase_PIC() { hal.watchdog_refresh(); W25QXX.SPI_FLASH_BlockErase(FONTINFOADDR + Font_sectorcnt * 64 * 1024); } + W25QXX.close(); } #endif @@ -479,6 +482,8 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) { } while (pbr >= BMP_WRITE_BUF_LEN); } + W25QXX.close(); + file.close(); #if ENABLED(MARLIN_DEV_MODE) @@ -584,6 +589,7 @@ void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size) { #else W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead((uint8_t *)P_Rbuff, addr, size); + W25QXX.close(); #endif } @@ -591,6 +597,7 @@ void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size) { void get_spi_flash_data(const char *rec_buf, int addr, int size) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead((uint8_t *)rec_buf, UNIGBK_FLASH_ADDR + addr, size); + W25QXX.close(); } #endif @@ -598,6 +605,7 @@ uint32_t logo_addroffset = 0; void Pic_Logo_Read(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead(Logo_Rbuff, PIC_LOGO_ADDR + logo_addroffset, LogoReadsize); + W25QXX.close(); logo_addroffset += LogoReadsize; if (logo_addroffset >= LOGO_MAX_SIZE_TFT35) logo_addroffset = 0; @@ -607,6 +615,7 @@ uint32_t default_view_addroffset = 0; void default_view_Read(uint8_t *default_view_Rbuff, uint32_t default_view_Readsize) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead(default_view_Rbuff, DEFAULT_VIEW_ADDR_TFT35 + default_view_addroffset, default_view_Readsize); + W25QXX.close(); default_view_addroffset += default_view_Readsize; if (default_view_addroffset >= DEFAULT_VIEW_MAX_SIZE) default_view_addroffset = 0; @@ -617,6 +626,7 @@ void default_view_Read(uint8_t *default_view_Rbuff, uint32_t default_view_Readsi void flash_view_Read(uint8_t *flash_view_Rbuff, uint32_t flash_view_Readsize) { W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead(flash_view_Rbuff, BAK_VIEW_ADDR_TFT35 + flash_view_addroffset, flash_view_Readsize); + W25QXX.close(); flash_view_addroffset += flash_view_Readsize; if (flash_view_addroffset >= FLASH_VIEW_MAX_SIZE) flash_view_addroffset = 0; diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index b31977e7ca4c..87bbb0393413 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -38,7 +38,7 @@ #include "../../../MarlinCore.h" #include "../../../inc/MarlinConfig.h" -#include HAL_PATH(../../../HAL, tft/xpt2046.h) +#include "../../../HAL/shared/tft/xpt2046.h" #include "../../marlinui.h" XPT2046 touch; @@ -63,8 +63,6 @@ XPT2046 touch; #include "wifi_module.h" #endif -#include - #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif @@ -119,8 +117,6 @@ void SysTick_Callback() { void tft_lvgl_init() { - W25QXX.init(SPI_QUARTER_SPEED); - gCfgItems_init(); ui_cfg_init(); disp_language_init(); @@ -253,17 +249,14 @@ void tft_lvgl_init() { static lv_disp_drv_t* disp_drv_p; -#if ENABLED(USE_SPI_DMA_TC) +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) bool lcd_dma_trans_lock = false; -#endif -void dmc_tc_handler(struct __DMA_HandleTypeDef * hdma) { - #if ENABLED(USE_SPI_DMA_TC) + void async_dma_complete(void *ud) { lv_disp_flush_ready(disp_drv_p); lcd_dma_trans_lock = false; - TFT_SPI::Abort(); - #endif -} + } +#endif void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) { uint16_t width = area->x2 - area->x1 + 1, @@ -273,19 +266,16 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co SPI_TFT.setWindow((uint16_t)area->x1, (uint16_t)area->y1, width, height); - #if ENABLED(USE_SPI_DMA_TC) + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) lcd_dma_trans_lock = true; - SPI_TFT.tftio.WriteSequenceIT((uint16_t*)color_p, width * height); - TFT_SPI::DMAtx.XferCpltCallback = dmc_tc_handler; + SPI_TFT.tftio.WriteSequenceAsync((uint16_t*)color_p, width * height, async_dma_complete, nullptr); #else SPI_TFT.tftio.WriteSequence((uint16_t*)color_p, width * height); lv_disp_flush_ready(disp_drv_p); // Indicate you are ready with the flushing #endif - - W25QXX.init(SPI_QUARTER_SPEED); } -#if ENABLED(USE_SPI_DMA_TC) +#if ENABLED(HAL_SPI_SUPPORTS_ASYNC) bool get_lcd_dma_lock() { return lcd_dma_trans_lock; } #endif @@ -295,7 +285,6 @@ void lv_fill_rect(lv_coord_t x1, lv_coord_t y1, lv_coord_t x2, lv_coord_t y2, lv height = y2 - y1 + 1; SPI_TFT.setWindow((uint16_t)x1, (uint16_t)y1, width, height); SPI_TFT.tftio.WriteMultiple(bk_color.full, width * height); - W25QXX.init(SPI_QUARTER_SPEED); } #define TICK_CYCLE 1 @@ -382,6 +371,7 @@ lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * pa lv_fs_res_t spi_flash_close_cb (lv_fs_drv_t * drv, void * file_p) { lv_fs_res_t res = LV_FS_RES_OK; /* Add your code here */ + W25QXX.close(); pic_read_addr_offset = pic_read_base_addr; return res; } diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index 294666e35621..a09b64ef5f11 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -168,7 +168,7 @@ MenuItem_static::draw(1, GET_TEXT_F(MSG_LEVEL_BED_WAITING)); // Color UI needs a control to detect a touch #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) - touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } if (ui.use_click()) { diff --git a/Marlin/src/lcd/menu/menu_x_twist.cpp b/Marlin/src/lcd/menu/menu_x_twist.cpp index a069b427c6bf..3f481ec98546 100644 --- a/Marlin/src/lcd/menu/menu_x_twist.cpp +++ b/Marlin/src/lcd/menu/menu_x_twist.cpp @@ -171,7 +171,7 @@ void xatc_wizard_homing_done() { // Color UI needs a control to detect a touch #if BOTH(TOUCH_SCREEN, HAS_GRAPHICAL_TFT) - touch.add_control(CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::CLICK, 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif } diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index e8b89bad7060..3d4e9554aecc 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -45,7 +45,11 @@ void CANVAS::Continue() { } bool CANVAS::ToScreen() { - tft.write_sequence(buffer, width * (endLine - startLine)); + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + tft.write_sequence_async(buffer, width * (endLine - startLine)); + #else + tft.write_sequence(buffer, width * (endLine - startLine)); + #endif return endLine == height; } diff --git a/Marlin/src/lcd/tft/tft.h b/Marlin/src/lcd/tft/tft.h index 67cec2ee1c7e..0731a4d601a3 100644 --- a/Marlin/src/lcd/tft/tft.h +++ b/Marlin/src/lcd/tft/tft.h @@ -65,10 +65,8 @@ #endif #endif -#if TFT_BUFFER_SIZE > 65535 - // DMA Count parameter is uint16_t - #error "TFT_BUFFER_SIZE can not exceed 65535" -#endif +// DMA Count parameter is uint16_t +static_assert(TFT_BUFFER_SIZE < (1<<(sizeof(uint16_t)*8)), "TFT_BUFFER_SIZE can not exceed 65535"); class TFT { private: @@ -90,6 +88,10 @@ class TFT { static void write_sequence(uint16_t *Data, uint16_t Count) { io.WriteSequence(Data, Count); } static void set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ymax) { io.set_window(Xmin, Ymin, Xmax, Ymax); } + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + static void write_sequence_async(const uint16_t *Data, uint16_t Count, void (*completeCallback)(void*) = nullptr, void *ud = nullptr) { io.WriteSequenceAsync(Data, Count, completeCallback, ud); } + #endif + static void fill(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint16_t color) { queue.fill(x, y, width, height, color); } static void canvas(uint16_t x, uint16_t y, uint16_t width, uint16_t height) { queue.canvas(x, y, width, height); } static void set_background(uint16_t color) { queue.set_background(color); } diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 824b2699247b..4a051d7b28a9 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -47,7 +47,7 @@ millis_t Touch::last_touch_ms = 0, Touch::time_to_hold, Touch::repeat_delay, Touch::touch_time; -TouchControlType Touch::touch_control_type = NONE; +TouchControlType Touch::touch_control_type = TouchControlType::NONE; #if HAS_TOUCH_SLEEP millis_t Touch::next_sleep_ms; // = 0 #endif @@ -90,7 +90,7 @@ void Touch::idle() { #if HAS_RESUME_CONTINUE // UI is waiting for a click anywhere? if (wait_for_user) { - touch_control_type = CLICK; + touch_control_type = TouchControlType::CLICK; ui.lcd_clicked = true; if (ui.external_control) wait_for_user = false; return; @@ -101,7 +101,7 @@ void Touch::idle() { if (touch_time) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) - if (touch_control_type == NONE && ELAPSED(last_touch_ms, touch_time + TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS) && ui.on_status_screen()) + if (touch_control_type == TouchControlType::NONE && ELAPSED(last_touch_ms, touch_time + TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS) && ui.on_status_screen()) ui.goto_screen(touch_screen_calibration); #endif return; @@ -124,7 +124,7 @@ void Touch::idle() { } else { for (i = 0; i < controls_count; i++) { - if ((WITHIN(x, controls[i].x, controls[i].x + controls[i].width) && WITHIN(y, controls[i].y, controls[i].y + controls[i].height)) || (TERN(TOUCH_SCREEN_CALIBRATION, controls[i].type == CALIBRATE, false))) { + if ((WITHIN(x, controls[i].x, controls[i].x + controls[i].width) && WITHIN(y, controls[i].y, controls[i].y + controls[i].height)) || (TERN(TOUCH_SCREEN_CALIBRATION, controls[i].type == TouchControlType::CALIBRATE, false))) { touch_control_type = controls[i].type; touch(&controls[i]); break; @@ -142,7 +142,7 @@ void Touch::idle() { x = y = 0; current_control = nullptr; touch_time = 0; - touch_control_type = NONE; + touch_control_type = TouchControlType::NONE; time_to_hold = 0; repeat_delay = TOUCH_REPEAT_DELAY; } @@ -151,38 +151,38 @@ void Touch::idle() { void Touch::touch(touch_control_t *control) { switch (control->type) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) - case CALIBRATE: + case TouchControlType::CALIBRATE: if (touch_calibration.handleTouch(x, y)) ui.refresh(); break; #endif // TOUCH_SCREEN_CALIBRATION - case MENU_SCREEN: ui.goto_screen((screenFunc_t)control->data); break; - case BACK: ui.goto_previous_screen(); break; - case MENU_CLICK: + case TouchControlType::MENU_SCREEN: ui.goto_screen((screenFunc_t)control->data); break; + case TouchControlType::BACK: ui.goto_previous_screen(); break; + case TouchControlType::MENU_CLICK: TERN_(SINGLE_TOUCH_NAVIGATION, ui.encoderPosition = control->data); ui.lcd_clicked = true; break; - case CLICK: ui.lcd_clicked = true; break; + case TouchControlType::CLICK: ui.lcd_clicked = true; break; #if HAS_RESUME_CONTINUE - case RESUME_CONTINUE: extern bool wait_for_user; wait_for_user = false; break; + case TouchControlType::RESUME_CONTINUE: extern bool wait_for_user; wait_for_user = false; break; #endif - case CANCEL: ui.encoderPosition = 0; ui.selection = false; ui.lcd_clicked = true; break; - case CONFIRM: ui.encoderPosition = 1; ui.selection = true; ui.lcd_clicked = true; break; - case MENU_ITEM: ui.encoderPosition = control->data; ui.refresh(); break; - case PAGE_UP: + case TouchControlType::CANCEL: ui.encoderPosition = 0; ui.selection = false; ui.lcd_clicked = true; break; + case TouchControlType::CONFIRM: ui.encoderPosition = 1; ui.selection = true; ui.lcd_clicked = true; break; + case TouchControlType::MENU_ITEM: ui.encoderPosition = control->data; ui.refresh(); break; + case TouchControlType::PAGE_UP: encoderTopLine = encoderTopLine > LCD_HEIGHT ? encoderTopLine - LCD_HEIGHT : 0; ui.encoderPosition = ui.encoderPosition > LCD_HEIGHT ? ui.encoderPosition - LCD_HEIGHT : 0; ui.refresh(); break; - case PAGE_DOWN: + case TouchControlType::PAGE_DOWN: encoderTopLine = (encoderTopLine + 2 * LCD_HEIGHT < screen_items) ? encoderTopLine + LCD_HEIGHT : screen_items - LCD_HEIGHT; ui.encoderPosition = ui.encoderPosition + LCD_HEIGHT < (uint32_t)screen_items ? ui.encoderPosition + LCD_HEIGHT : screen_items; ui.refresh(); break; - case SLIDER: hold(control); ui.encoderPosition = (x - control->x) * control->data / control->width; break; - case INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; - case DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; - case HEATER: + case TouchControlType::SLIDER: hold(control); ui.encoderPosition = (x - control->x) * control->data / control->width; break; + case TouchControlType::INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; + case TouchControlType::DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; + case TouchControlType::HEATER: int8_t heater; heater = control->data; ui.clear_lcd(); @@ -213,18 +213,18 @@ void Touch::touch(touch_control_t *control) { #endif break; - case FAN: + case TouchControlType::FAN: ui.clear_lcd(); static uint8_t fan, fan_speed; fan = 0; fan_speed = thermalManager.fan_speed[fan]; MenuItem_percent::action(GET_TEXT_F(MSG_FIRST_FAN_SPEED), &fan_speed, 0, 255, []{ thermalManager.set_fan_speed(fan, fan_speed); }); break; - case FEEDRATE: + case TouchControlType::FEEDRATE: ui.clear_lcd(); MenuItem_int3::action(GET_TEXT_F(MSG_SPEED), &feedrate_percentage, 10, 999); break; - case FLOWRATE: + case TouchControlType::FLOWRATE: ui.clear_lcd(); MenuItemBase::itemIndex = control->data; #if EXTRUDERS == 1 @@ -235,15 +235,15 @@ void Touch::touch(touch_control_t *control) { break; #if ENABLED(AUTO_BED_LEVELING_UBL) - case UBL: hold(control, UBL_REPEAT_DELAY); ui.encoderPosition += control->data; break; + case TouchControlType::UBL: hold(control, UBL_REPEAT_DELAY); ui.encoderPosition += control->data; break; #endif - case MOVE_AXIS: + case TouchControlType::MOVE_AXIS: ui.goto_screen((screenFunc_t)ui.move_axis_screen); break; // TODO: TOUCH could receive data to pass to the callback - case BUTTON: ((screenFunc_t)control->data)(); break; + case TouchControlType::BUTTON: ((screenFunc_t)control->data)(); break; default: break; } diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 6021a840b65e..f20505e96e18 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -34,7 +34,7 @@ #include HAL_PATH(../../HAL, tft/gt911.h) #define TOUCH_DRIVER_CLASS GT911 #elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) - #include HAL_PATH(../../HAL, tft/xpt2046.h) + #include "../../HAL/shared/tft/xpt2046.h" #define TOUCH_DRIVER_CLASS XPT2046 #else #error "Unknown Touch Screen Type." @@ -43,7 +43,7 @@ // Menu Navigation extern int8_t encoderTopLine, encoderLine, screen_items; -enum TouchControlType : uint16_t { +enum class TouchControlType : uint16_t { NONE = 0x0000, CALIBRATE, MENU_SCREEN, @@ -72,7 +72,7 @@ typedef void (*screenFunc_t)(); void add_control(uint16_t x, uint16_t y, TouchControlType control_type, intptr_t data, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED); inline void add_control(uint16_t x, uint16_t y, TouchControlType control_type, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, control_type, 0, image, is_enabled, color_enabled, color_disabled); } -inline void add_control(uint16_t x, uint16_t y, screenFunc_t screen, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, MENU_SCREEN, (intptr_t)screen, image, is_enabled, color_enabled, color_disabled); } +inline void add_control(uint16_t x, uint16_t y, screenFunc_t screen, MarlinImage image, bool is_enabled = true, uint16_t color_enabled = COLOR_CONTROL_ENABLED, uint16_t color_disabled = COLOR_CONTROL_DISABLED) { add_control(x, y, TouchControlType::MENU_SCREEN, (intptr_t)screen, image, is_enabled, color_enabled, color_disabled); } typedef struct __attribute__((__packed__)) { TouchControlType type; @@ -116,8 +116,8 @@ class Touch { static void clear() { controls_count = 0; } static void idle(); static bool is_clicked() { - if (touch_control_type == CLICK) { - touch_control_type = NONE; + if (touch_control_type == TouchControlType::CLICK) { + touch_control_type = TouchControlType::NONE; return true; } return false; diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 2cce95c8df01..ab7a34f300f9 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -49,9 +49,9 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { - add_control(164, TFT_HEIGHT - 50, PAGE_UP, imgPageUp, encoderTopLine > 0); - add_control(796, TFT_HEIGHT - 50, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); - add_control(480, TFT_HEIGHT - 50, BACK, imgBack); + add_control(164, TFT_HEIGHT - 50, TouchControlType::PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(796, TFT_HEIGHT - 50, TouchControlType::PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(480, TFT_HEIGHT - 50, TouchControlType::BACK, imgBack); draw_menu_navigation = false; } #endif @@ -150,7 +150,7 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { #endif else return; - TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 80, 120, Heater)); + TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(TouchControlType::HEATER, x, y, 80, 120, Heater)); tft.canvas(x, y, 80, 120); tft.set_background(COLOR_BACKGROUND); @@ -195,7 +195,7 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { } void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { - TERN_(TOUCH_SCREEN, touch.add_control(FAN, x, y, 80, 120)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FAN, x, y, 80, 120)); tft.canvas(x, y, 80, 120); tft.set_background(COLOR_BACKGROUND); @@ -311,7 +311,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 274, y, 100, 32)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FEEDRATE, 274, y, 100, 32)); // flow rate tft.canvas(650, y, 100, 32); @@ -321,7 +321,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder])); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 650, y, 100, 32, active_extruder)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FLOWRATE, 650, y, 100, 32, active_extruder)); #if ENABLED(TOUCH_SCREEN) add_control(900, y, menu_main, imgSettings); @@ -410,7 +410,7 @@ void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char * const va #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); + touch.add_control(TouchControlType::SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue); #endif } @@ -419,9 +419,9 @@ void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char * const va void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(164, TFT_HEIGHT - 64, DECREASE, imgDecrease); - add_control(796, TFT_HEIGHT - 64, INCREASE, imgIncrease); - add_control(480, TFT_HEIGHT - 64, CLICK, imgConfirm); + add_control(164, TFT_HEIGHT - 64, TouchControlType::DECREASE, imgDecrease); + add_control(796, TFT_HEIGHT - 64, TouchControlType::INCREASE, imgIncrease); + add_control(480, TFT_HEIGHT - 64, TouchControlType::CLICK, imgConfirm); #endif } @@ -450,8 +450,8 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con 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)); + add_control(88, TFT_HEIGHT - 64, TouchControlType::CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + add_control(328, TFT_HEIGHT - 64, TouchControlType::CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); #else menu_line(++line); if (no) { @@ -474,7 +474,7 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif menu_line(row); @@ -556,12 +556,12 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #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); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, TouchControlType::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, TouchControlType::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, TouchControlType::UBL, - ENCODER_STEPS_PER_MENU_ITEM, imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); + add_control(320, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::CLICK, imgLeveling); + add_control(224, TFT_HEIGHT - 34, TouchControlType::BACK, imgBack); #endif } #endif // AUTO_BED_LEVELING_UBL @@ -825,7 +825,7 @@ static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); } - TERN_(TOUCH_SCREEN, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); + TERN_(TOUCH_SCREEN, if (enabled) touch.add_control(TouchControlType::BUTTON, x, y, width, height, data)); } void MarlinUI::move_axis_screen() { @@ -870,13 +870,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.eNamePos.x = x; motionAxisState.eNamePos.y = y; drawCurESelection(); - TERN_(TOUCH_SCREEN, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + TERN_(TOUCH_SCREEN, if (!busy) touch.add_control(TouchControlType::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_(TOUCH_SCREEN, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, TouchControlType::BUTTON, (intptr_t)do_home, imgHome, !busy)); x += BTN_WIDTH + spacing; uint16_t xplus_x = x; @@ -887,7 +887,7 @@ void MarlinUI::move_axis_screen() { 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); + if (!busy) touch.add_control(TouchControlType::BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif // ROW 3 -> E- CurX Y- Z- @@ -925,13 +925,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.stepValuePos.y = y; if (!busy) { drawCurStepValue(); - TERN_(TOUCH_SCREEN, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::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_(TOUCH_SCREEN, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); + TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, TouchControlType::BACK, imgBack)); } #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 19cc4590aa5e..dc35669b74e1 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -49,9 +49,9 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { - add_control(48, 206, PAGE_UP, imgPageUp, encoderTopLine > 0); - add_control(240, 206, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); - add_control(144, 206, BACK, imgBack); + add_control(48, 206, TouchControlType::PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(240, 206, TouchControlType::PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(144, 206, TouchControlType::BACK, imgBack); draw_menu_navigation = false; } #endif @@ -150,7 +150,7 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { #endif else return; - TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 64, 100, Heater)); + TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.TouchControlType::HEATER, x, y, 64, 100, Heater)); tft.canvas(x, y, 64, 100); tft.set_background(COLOR_BACKGROUND); @@ -293,7 +293,7 @@ void MarlinUI::draw_status_screen() { offset -= tft_string.width(); } tft.add_text(301 - tft_string.width() - offset, 3, nhz ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 0, 103, 312, 24)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::MOVE_AXIS, 0, 103, 312, 24)); // feed rate tft.canvas(70, 136, 80, 32); @@ -303,7 +303,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); tft.add_text(32, 6, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 70, 136, 80, 32)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FEEDRATE, 70, 136, 80, 32)); // flow rate tft.canvas(170, 136, 80, 32); @@ -313,7 +313,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder])); tft_string.add('%'); tft.add_text(32, 6, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 170, 136, 80, 32, active_extruder)); + TERN_(TOUCH_SCREEN, touch.TouchControlType::FLOWRATE, 170, 136, 80, 32, active_extruder)); // print duration char buffer[14]; @@ -408,9 +408,9 @@ void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char * const va void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(32, TFT_HEIGHT - 64, DECREASE, imgDecrease); - add_control(224, TFT_HEIGHT - 64, INCREASE, imgIncrease); - add_control(128, TFT_HEIGHT - 64, CLICK, imgConfirm); + add_control(32, TFT_HEIGHT - 64, TouchControlType::DECREASE, imgDecrease); + add_control(224, TFT_HEIGHT - 64, TouchControlType::INCREASE, imgIncrease); + add_control(128, TFT_HEIGHT - 64, TouchControlType::CLICK, imgConfirm); #endif } @@ -439,8 +439,8 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string); } #if ENABLED(TOUCH_SCREEN) - if (no) add_control( 48, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); - if (yes) add_control(208, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); + if (no) add_control( 48, TFT_HEIGHT - 64, TouchControlType::CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + if (yes) add_control(208, TFT_HEIGHT - 64, TouchControlType::CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); #endif } @@ -450,7 +450,7 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif menu_line(row); @@ -532,12 +532,12 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #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(224, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, CLICK, imgLeveling); - add_control(144, 206, BACK, imgBack); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, TouchControlType::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, TouchControlType::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, TouchControlType::UBL, -(ENCODER_STEPS_PER_MENU_ITEM), imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); + add_control(224, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::CLICK, imgLeveling); + add_control(144, 206, TouchControlType::BACK, imgBack); #endif } #endif // AUTO_BED_LEVELING_UBL @@ -805,7 +805,7 @@ static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); } - TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); + TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(TouchControlType::BUTTON, x, y, width, height, data)); } void MarlinUI::move_axis_screen() { // Reset @@ -850,7 +850,7 @@ void MarlinUI::move_axis_screen() { motionAxisState.eNamePos.x = x; motionAxisState.eNamePos.y = y; drawCurESelection(); - TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(TouchControlType::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); @@ -867,7 +867,7 @@ void MarlinUI::move_axis_screen() { 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); + if (!busy) touch.add_control(TouchControlType::BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif // ROW 3 -> E- CurX Y- Z- @@ -905,13 +905,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.stepValuePos.y = TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT; if (!busy) { drawCurStepValue(); - TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + TERN_(HAS_TFT_XPT2046, touch.add_control(TouchControlType::BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); } // aligned with x+ drawBtn(xplus_x, y, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, TouchControlType::BACK, imgBack)); } #endif // HAS_UI_320x240 diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 04a121a0e03d..2dcbf5151a0e 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -49,9 +49,9 @@ void MarlinUI::tft_idle() { #if ENABLED(TOUCH_SCREEN) if (TERN0(HAS_TOUCH_SLEEP, lcd_sleep_task())) return; if (draw_menu_navigation) { - add_control(104, TFT_HEIGHT - 34, PAGE_UP, imgPageUp, encoderTopLine > 0); - add_control(344, TFT_HEIGHT - 34, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); - add_control(224, TFT_HEIGHT - 34, BACK, imgBack); + add_control(104, TFT_HEIGHT - 34, TouchControlType::PAGE_UP, imgPageUp, encoderTopLine > 0); + add_control(344, TFT_HEIGHT - 34, TouchControlType::PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items); + add_control(224, TFT_HEIGHT - 34, TouchControlType::BACK, imgBack); draw_menu_navigation = false; } #endif @@ -150,7 +150,7 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { #endif else return; - TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 80, 120, Heater)); + TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(TouchControlType::HEATER, x, y, 80, 120, Heater)); tft.canvas(x, y, 80, 120); tft.set_background(COLOR_BACKGROUND); @@ -195,7 +195,7 @@ void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) { } void draw_fan_status(uint16_t x, uint16_t y, const bool blink) { - TERN_(TOUCH_SCREEN, touch.add_control(FAN, x, y, 80, 120)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FAN, x, y, 80, 120)); tft.canvas(x, y, 80, 120); tft.set_background(COLOR_BACKGROUND); @@ -294,7 +294,7 @@ void MarlinUI::draw_status_screen() { offset -= tft_string.width(); } tft.add_text(455 - tft_string.width() - offset, 3, nhz ? 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)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT)); y += TERN(HAS_UI_480x272, 38, 48); // feed rate @@ -305,7 +305,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 96, 176, 100, 32)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FEEDRATE, 96, 176, 100, 32)); // flow rate tft.canvas(284, y, 100, 32); @@ -315,7 +315,7 @@ void MarlinUI::draw_status_screen() { tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder])); tft_string.add('%'); tft.add_text(36, 1, color , tft_string); - TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 284, 176, 100, 32, active_extruder)); + TERN_(TOUCH_SCREEN, touch.add_control(TouchControlType::FLOWRATE, 284, 176, 100, 32, active_extruder)); #if ENABLED(TOUCH_SCREEN) add_control(404, y, menu_main, imgSettings); @@ -404,7 +404,7 @@ void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char * const va #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); + touch.add_control(TouchControlType::SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue); #endif } @@ -413,9 +413,9 @@ void MenuEditItemBase::draw_edit_screen(FSTR_P const fstr, const char * const va void TFT::draw_edit_screen_buttons() { #if ENABLED(TOUCH_SCREEN) - add_control(64, TFT_HEIGHT - 64, DECREASE, imgDecrease); - add_control(352, TFT_HEIGHT - 64, INCREASE, imgIncrease); - add_control(208, TFT_HEIGHT - 64, CLICK, imgConfirm); + add_control(64, TFT_HEIGHT - 64, TouchControlType::DECREASE, imgDecrease); + add_control(352, TFT_HEIGHT - 64, TouchControlType::INCREASE, imgIncrease); + add_control(208, TFT_HEIGHT - 64, TouchControlType::CLICK, imgConfirm); #endif } @@ -444,8 +444,8 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string); } #if ENABLED(TOUCH_SCREEN) - if (no) add_control( 88, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); - if (yes) add_control(328, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); + if (no) add_control( 88, TFT_HEIGHT - 64, TouchControlType::CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL); + if (yes) add_control(328, TFT_HEIGHT - 64, TouchControlType::CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM)); #endif } @@ -455,7 +455,7 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #if ENABLED(TOUCH_SCREEN) touch.clear(); draw_menu_navigation = false; - touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT); #endif menu_line(row); @@ -537,12 +537,12 @@ void MenuItem_confirm::draw_select_screen(FSTR_P const yes, FSTR_P const no, con #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); + add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, TouchControlType::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, TouchControlType::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, TouchControlType::UBL, -(ENCODER_STEPS_PER_MENU_ITEM), imgLeft); + add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight); + add_control(320, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, TouchControlType::CLICK, imgLeveling); + add_control(224, TFT_HEIGHT - 34, TouchControlType::BACK, imgBack); #endif } #endif // AUTO_BED_LEVELING_UBL @@ -806,7 +806,7 @@ static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY); } - TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(BUTTON, x, y, width, height, data)); + TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(TouchControlType::BUTTON, x, y, width, height, data)); } void MarlinUI::move_axis_screen() { @@ -851,13 +851,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.eNamePos.x = x; motionAxisState.eNamePos.y = y; drawCurESelection(); - TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); + TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(TouchControlType::BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select)); x += BTN_WIDTH + spacing; drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy); x += BTN_WIDTH + spacing; //imgHome is 64x64 - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy)); + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, TouchControlType::BUTTON, (intptr_t)do_home, imgHome, !busy)); x += BTN_WIDTH + spacing; uint16_t xplus_x = x; @@ -868,7 +868,7 @@ void MarlinUI::move_axis_screen() { 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); + if (!busy) touch.add_control(TouchControlType::BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select); #endif // ROW 3 -> E- CurX Y- Z- @@ -906,13 +906,13 @@ void MarlinUI::move_axis_screen() { motionAxisState.stepValuePos.y = y; if (!busy) { drawCurStepValue(); - TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); + TERN_(HAS_TFT_XPT2046, touch.add_control(TouchControlType::BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size)); } // aligned with x+ drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy); - TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack)); + TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, TouchControlType::BACK, imgBack)); } #endif // HAS_UI_480x320 diff --git a/Marlin/src/lcd/tft/ui_common.cpp b/Marlin/src/lcd/tft/ui_common.cpp index bb0578576632..816a57320065 100644 --- a/Marlin/src/lcd/tft/ui_common.cpp +++ b/Marlin/src/lcd/tft/ui_common.cpp @@ -74,7 +74,7 @@ void menu_item(const uint8_t row, bool sel ) { menu_line(row, sel ? COLOR_SELECTION_BG : COLOR_BACKGROUND); #if ENABLED(TOUCH_SCREEN) - const TouchControlType tct = TERN(SINGLE_TOUCH_NAVIGATION, true, sel) ? MENU_CLICK : MENU_ITEM; + const TouchControlType tct = TERN(TouchControlType::SINGLE_TOUCH_NAVIGATION, true, sel) ? TouchControlType::MENU_CLICK : TouchControlType::MENU_ITEM; touch.add_control(tct, 0, TFT_TOP_LINE_Y + row * MENU_LINE_HEIGHT, TFT_WIDTH, MENU_ITEM_HEIGHT, encoderTopLine + row); #endif } @@ -227,7 +227,7 @@ void MarlinUI::clear_lcd() { calibrationState calibration_stage = touch_calibration.get_calibration_state(); - if (calibration_stage == CALIBRATION_NONE) { + if (calibration_stage == CALIBRATION_NONE || calibration_stage == CALIBRATION_TOP_LEFT) { defer_status_screen(true); clear_lcd(); calibration_stage = touch_calibration.calibration_start(); @@ -258,13 +258,13 @@ void MarlinUI::clear_lcd() { tft.add_bar(0, 15, 31, 1, COLOR_TOUCH_CALIBRATION); tft.add_bar(15, 0, 1, 31, COLOR_TOUCH_CALIBRATION); - touch.add_control(CALIBRATE, 0, 0, TFT_WIDTH, TFT_HEIGHT, uint32_t(x) << 16 | uint32_t(y)); + touch.add_control(TouchControlType::CALIBRATE, 0, 0, TFT_WIDTH, TFT_HEIGHT, uint32_t(x) << 16 | uint32_t(y)); } else { tft_string.set(calibration_stage == CALIBRATION_SUCCESS ? GET_TEXT(MSG_CALIBRATION_COMPLETED) : GET_TEXT(MSG_CALIBRATION_FAILED)); defer_status_screen(false); touch_calibration.calibration_end(); - touch.add_control(BACK, 0, 0, TFT_WIDTH, TFT_HEIGHT); + touch.add_control(TouchControlType::BACK, 0, 0, TFT_WIDTH, TFT_HEIGHT); } tft.canvas(0, (TFT_HEIGHT - tft_string.font_height()) >> 1, TFT_WIDTH, tft_string.font_height()); diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index 6f6d0f74da6a..f703ce15bb9b 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -151,6 +151,20 @@ if (lcd_id != 0xFFFFFFFF) return; #error "Unsupported TFT driver" #endif +#if 0 + static_assert((TFT_WIDTH * TFT_HEIGHT * 18) / 8 == 345600, "invalid tft dimensions"); + io.DataTransferBegin(); + io.WriteReg8(0x2C); + for (unsigned long n = 0; n < TFT_WIDTH * TFT_HEIGHT; n++) + io.WriteData(n/(TFT_WIDTH*6)); + io.DataTransferEnd(); + + OUT_WRITE(EXP1_01_PIN, HIGH); + delay(1000); + OUT_WRITE(EXP1_01_PIN, LOW); + delay(5000); +#endif + #if PIN_EXISTS(TFT_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT) TERN(HAS_LCD_BRIGHTNESS, ui._set_brightness(), WRITE(TFT_BACKLIGHT_PIN, HIGH)); #endif @@ -166,7 +180,7 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym switch (lcd_id) { case LTDC_RGB: - io.DataTransferBegin(DATASIZE_8BIT); + io.DataTransferBegin(); io.WriteReg(0x01); io.WriteData(Xmin); @@ -180,6 +194,7 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym io.DataTransferEnd(); break; +#ifdef TFT_SUPPORTS_8BIT case ST7735: // ST7735 160x128 case ST7789: // ST7789V 320x240 case ST7796: // ST7796 480x320 @@ -187,30 +202,31 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym case ILI9488: // ILI9488 480x320 case SSD1963: // SSD1963 case ILI9488_ID1: // 0x8066 ILI9488 480x320 - io.DataTransferBegin(DATASIZE_8BIT); + io.DataTransferBegin(); // CASET: Column Address Set - io.WriteReg(ILI9341_CASET); - io.WriteData((Xmin >> 8) & 0xFF); - io.WriteData(Xmin & 0xFF); - io.WriteData((Xmax >> 8) & 0xFF); - io.WriteData(Xmax & 0xFF); + io.WriteReg8(ILI9341_CASET); + io.WriteData8((Xmin >> 8) & 0xFF); + io.WriteData8(Xmin & 0xFF); + io.WriteData8((Xmax >> 8) & 0xFF); + io.WriteData8(Xmax & 0xFF); // RASET: Row Address Set - io.WriteReg(ILI9341_PASET); - io.WriteData((Ymin >> 8) & 0xFF); - io.WriteData(Ymin & 0xFF); - io.WriteData((Ymax >> 8) & 0xFF); - io.WriteData(Ymax & 0xFF); + io.WriteReg8(ILI9341_PASET); + io.WriteData8((Ymin >> 8) & 0xFF); + io.WriteData8(Ymin & 0xFF); + io.WriteData8((Ymax >> 8) & 0xFF); + io.WriteData8(Ymax & 0xFF); // RAMWR: Memory Write - io.WriteReg(ILI9341_RAMWR); + io.WriteReg8(ILI9341_RAMWR); io.DataTransferEnd(); break; +#endif // TFT_SUPPORTS_8BIT case R61505: // R61505U 320x240 case ILI9328: // ILI9328 320x240 - io.DataTransferBegin(DATASIZE_16BIT); + io.DataTransferBegin(); // Mind the mess: with landscape screen orientation 'Horizontal' is Y and 'Vertical' is X io.WriteReg(ILI9328_HASTART); @@ -240,22 +256,46 @@ void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { uint16_t dataWidth, data; dataWidth = *Sequence++; - io.DataTransferBegin(dataWidth); + +#if ENABLED(TFT_SUPPORTS_8BIT) + bool is_8bit = ( dataWidth == DATASIZE_8BIT ); +#endif // TFT_SUPPORTS_8BIT + + io.DataTransferBegin(); for (;;) { data = *Sequence++; if (data != 0xFFFF) { - io.WriteData(data); +#if ENABLED(TFT_SUPPORTS_8BIT) + if (is_8bit) + io.WriteData8((uint8_t)data); + else +#endif // TFT_SUPPORTS_8BIT + io.WriteData(data); continue; } data = *Sequence++; if (data == 0x7FFF) break; if (data == 0xFFFF) - io.WriteData(0xFFFF); + { +#if ENABLED(TFT_SUPPORTS_8BIT) + if (is_8bit) + io.WriteData8(0xFF); + else +#endif // TFT_SUPPORTS_8BIT + io.WriteData(0xFFFF); + } else if (data & 0x8000) delay(data & 0x7FFF); else if ((data & 0xFF00) == 0) - io.WriteReg(data); + { +#if ENABLED(TFT_SUPPORTS_8BIT) + if (is_8bit) + io.WriteReg8((uint8_t)data); + else +#endif // TFT_SUPPORTS_8BIT + io.WriteReg(data); + } } io.DataTransferEnd(); diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 50b921cd2a93..85c4a3a5aece 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfig.h" #if HAS_SPI_TFT - #include HAL_PATH(../../HAL, tft/tft_spi.h) + #include "../../HAL/shared/tft/tft_spi.h" #elif HAS_FSMC_TFT #include HAL_PATH(../../HAL, tft/tft_fsmc.h) #elif HAS_LTDC_TFT @@ -99,6 +99,9 @@ #define ESC_END 0xFFFF, 0x7FFF #define ESC_FFFF 0xFFFF, 0xFFFF +#define DATASIZE_8BIT 0 +#define DATASIZE_16BIT 2 + class TFT_IO { public: static TFT_IO_DRIVER io; @@ -113,17 +116,22 @@ class TFT_IO { inline static void Abort() { io.Abort(); }; inline static uint32_t GetID() { return io.GetID(); }; - inline static void DataTransferBegin(uint16_t DataWidth = DATASIZE_16BIT) { io.DataTransferBegin(DataWidth); } + inline static void DataTransferBegin() { io.DataTransferBegin(); } inline static void DataTransferEnd() { io.DataTransferEnd(); }; - // inline static void DataTransferAbort() { io.DataTransferAbort(); }; - inline static void WriteData(uint16_t Data) { io.WriteData(Data); }; + inline static void WriteData(uint16_t Data) { io.WriteData(Data); } +#if ENABLED(TFT_SUPPORTS_8BIT) + inline static void WriteData8(uint8_t Data) { io.WriteData8(Data); } +#endif inline static void WriteReg(uint16_t Reg) { io.WriteReg(Reg); }; +#if ENABLED(TFT_SUPPORTS_8BIT) + inline static void WriteReg8(uint8_t Reg) { io.WriteReg8(Reg); } +#endif - inline static void WriteSequence(uint16_t *Data, uint16_t Count) { io.WriteSequence(Data, Count); }; + inline static void WriteSequence(const uint16_t *Data, uint16_t Count) { io.WriteSequence(Data, Count); }; - #if ENABLED(USE_SPI_DMA_TC) - inline static void WriteSequenceIT(uint16_t *Data, uint16_t Count) { io.WriteSequenceIT(Data, Count); }; + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) + inline static void WriteSequenceAsync(const uint16_t *Data, uint16_t Count, void (*completeCallback)(void*) = nullptr, void *ud = nullptr) { io.WriteSequenceAsync(Data, Count, completeCallback, ud); }; #endif // static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); } diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index d641dd3b1c92..226b5bf37260 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -31,7 +31,7 @@ #include HAL_PATH(../../HAL, tft/gt911.h) GT911 touchIO; #elif ENABLED(TFT_TOUCH_DEVICE_XPT2046) - #include HAL_PATH(../../HAL, tft/xpt2046.h) + #include "../../HAL/shared/tft/xpt2046.h" XPT2046 touchIO; #else #error "Unknown Touch Screen Type." diff --git a/Marlin/src/libs/MAX31865.cpp b/Marlin/src/libs/MAX31865.cpp index 3fe069464463..66498a815879 100644 --- a/Marlin/src/libs/MAX31865.cpp +++ b/Marlin/src/libs/MAX31865.cpp @@ -53,13 +53,6 @@ #define DEBUG_OUT ENABLED(DEBUG_MAX31865) #include "../core/debug_out.h" -// The maximum speed the MAX31865 can do is 5 MHz -SPISettings MAX31865::spiConfig = SPISettings( - TERN(TARGET_LPC1768, SPI_QUARTER_SPEED, TERN(ARDUINO_ARCH_STM32, SPI_CLOCK_DIV4, 500000)), - MSBFIRST, - SPI_MODE1 // CPOL0 CPHA1 -); - #if DISABLED(LARGE_PINMAP) /** @@ -150,7 +143,6 @@ void MAX31865::begin(max31865_numwires_t wires, const_float_t zero_res, const_fl softSpiInit(); // Define pin modes for Software SPI else { DEBUG_ECHOLNPGM("Init MAX31865 Hardware SPI"); - SPI.begin(); // Start and configure hardware SPI } initFixedFlags(wires); @@ -582,15 +574,20 @@ void MAX31865::spiBeginTransaction() { digitalWrite(cselPin, LOW); DELAY_NS_VAR(MAX31865_SPI_TIMING_TCC); - if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) - SPI.beginTransaction(spiConfig); + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) { + // The maximum speed the MAX31865 can do is 5 MHz + spiInitEx(TERN(TARGET_LPC1768, SPI_QUARTER_SPEED, TERN(ARDUINO_ARCH_STM32, SPI_CLOCK_DIV4, 500000))); + spiSetBitOrder(SPI_BITORDER_MSB); + spiSetClockMode(SPI_CLKMODE_1); + } else digitalWrite(sclkPin, HIGH); } void MAX31865::spiEndTransaction() { - if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) - SPI.endTransaction(); + if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) { + spiClose(); + } else digitalWrite(sclkPin, LOW); @@ -610,7 +607,7 @@ void MAX31865::spiEndTransaction() { */ uint8_t MAX31865::spiTransfer(uint8_t x) { if (sclkPin == TERN(LARGE_PINMAP, -1UL, 255)) - return SPI.transfer(x); + return spiRec(x); uint8_t reply = 0; for (int i = 7; i >= 0; i--) { diff --git a/Marlin/src/libs/MAX31865.h b/Marlin/src/libs/MAX31865.h index 95bde756cee7..be7a05384e51 100644 --- a/Marlin/src/libs/MAX31865.h +++ b/Marlin/src/libs/MAX31865.h @@ -45,7 +45,6 @@ #include "../inc/MarlinConfig.h" #include "../HAL/shared/Delay.h" -#include HAL_PATH(../HAL, MarlinSPI.h) #define MAX31865_CONFIG_REG 0x00 #define MAX31865_CONFIG_BIAS 0x80 @@ -90,8 +89,6 @@ typedef enum max31865_numwires { /* Interface class for the MAX31865 RTD Sensor reader */ class MAX31865 { private: - static SPISettings spiConfig; - TERN(LARGE_PINMAP, uint32_t, uint8_t) sclkPin, misoPin, mosiPin, cselPin; uint16_t spiDelay; diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index 591d0d069318..b14ffb68ca3e 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -32,8 +32,6 @@ W25QXXFlash W25QXX; #define NC -1 #endif -MarlinSPI W25QXXFlash::mySPI(SPI_FLASH_MOSI_PIN, SPI_FLASH_MISO_PIN, SPI_FLASH_SCK_PIN, NC); - #define SPI_FLASH_CS_H() OUT_WRITE(SPI_FLASH_CS_PIN, HIGH) #define SPI_FLASH_CS_L() OUT_WRITE(SPI_FLASH_CS_PIN, LOW) @@ -64,10 +62,13 @@ void W25QXXFlash::init(uint8_t spiRate) { default: clock = SPI_CLOCK_DIV2;// Default from the SPI library } - mySPI.setClockDivider(clock); - mySPI.setBitOrder(MSBFIRST); - mySPI.setDataMode(SPI_MODE0); - mySPI.begin(); + spiInitEx(clock, SPI_FLASH_MOSI_PIN, SPI_FLASH_MISO_PIN, SPI_FLASH_SCK_PIN, NC); + spiSetBitOrder(SPI_BITORDER_MSB); + spiSetClockMode(SPI_CLKMODE_0); +} + +void W25QXXFlash::close() { + spiClose(); } /** @@ -76,12 +77,12 @@ void W25QXXFlash::init(uint8_t spiRate) { * @return Byte received */ uint8_t W25QXXFlash::spi_flash_Rec() { - const uint8_t returnByte = mySPI.transfer(0xFF); + const uint8_t returnByte = spiRec(0xFF); return returnByte; } uint8_t W25QXXFlash::spi_flash_read_write_byte(uint8_t data) { - const uint8_t returnByte = mySPI.transfer(data); + const uint8_t returnByte = spiRec(data); return returnByte; } @@ -92,10 +93,10 @@ uint8_t W25QXXFlash::spi_flash_read_write_byte(uint8_t data) { * @param nbyte Number of bytes to receive. * @return Nothing * - * @details Uses DMA + * @details Uses async (for example DMA) */ void W25QXXFlash::spi_flash_Read(uint8_t *buf, uint16_t nbyte) { - mySPI.dmaTransfer(0, const_cast(buf), nbyte); + spiRead(buf, nbyte); } /** @@ -105,7 +106,7 @@ void W25QXXFlash::spi_flash_Read(uint8_t *buf, uint16_t nbyte) { * * @details */ -void W25QXXFlash::spi_flash_Send(uint8_t b) { mySPI.transfer(b); } +void W25QXXFlash::spi_flash_Send(uint8_t b) { spiSend(b); } /** * @brief Write token and then write from 512 byte buffer to SPI (for SD card) @@ -116,8 +117,7 @@ void W25QXXFlash::spi_flash_Send(uint8_t b) { mySPI.transfer(b); } * @details Use DMA */ void W25QXXFlash::spi_flash_SendBlock(uint8_t token, const uint8_t *buf) { - mySPI.transfer(token); - mySPI.dmaSend(const_cast(buf), 512); + spiSendBlock(token, buf); } uint16_t W25QXXFlash::W25QXX_ReadID(void) { diff --git a/Marlin/src/libs/W25Qxx.h b/Marlin/src/libs/W25Qxx.h index 778463477d82..d249e7936f62 100644 --- a/Marlin/src/libs/W25Qxx.h +++ b/Marlin/src/libs/W25Qxx.h @@ -23,8 +23,6 @@ #include -#include HAL_PATH(../HAL, MarlinSPI.h) - #define W25X_WriteEnable 0x06 #define W25X_WriteDisable 0x04 #define W25X_ReadStatusReg 0x05 @@ -51,10 +49,9 @@ #define SPI_FLASH_PerWritePageSize 256 class W25QXXFlash { -private: - static MarlinSPI mySPI; public: void init(uint8_t spiRate); + void close(); static uint8_t spi_flash_Rec(); static uint8_t spi_flash_read_write_byte(uint8_t data); static void spi_flash_Read(uint8_t *buf, uint16_t nbyte); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 6cc40ccecee9..8054bde38180 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -109,10 +109,6 @@ Stepper stepper; // Singleton #include "../feature/dac/dac_dac084s085.h" #endif -#if HAS_MOTOR_CURRENT_SPI - #include -#endif - #if ENABLED(MIXING_EXTRUDER) #include "../feature/mixing.h" #endif @@ -3500,11 +3496,12 @@ void Stepper::report_positions() { // From Arduino DigitalPotControl example void Stepper::set_digipot_value_spi(const int16_t address, const int16_t value) { + spiInitEx(10000); // TODO: any SPI pins to select here? WRITE(DIGIPOTSS_PIN, LOW); // Take the SS pin low to select the chip - SPI.transfer(address); // Send the address and value via SPI - SPI.transfer(value); + spiSend(address); // Send the address and value via SPI + spiSend(value); WRITE(DIGIPOTSS_PIN, HIGH); // Take the SS pin high to de-select the chip - //delay(10); + spiClose(); } #endif // HAS_MOTOR_CURRENT_SPI @@ -3606,7 +3603,6 @@ void Stepper::report_positions() { #if HAS_MOTOR_CURRENT_SPI - SPI.begin(); SET_OUTPUT(DIGIPOTSS_PIN); LOOP_L_N(i, COUNT(motor_current_setting)) diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index 1fd94b26a8d8..fa0ae4e92e33 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -30,7 +30,6 @@ // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI -#include #include void tmc26x_init_to_defaults(); diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 2face373166e..de20c01c414e 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -33,13 +33,45 @@ #include "../stepper.h" #include -#include enum StealthIndex : uint8_t { LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K, STEALTH_AXIS_U, STEALTH_AXIS_V, STEALTH_AXIS_W) }; #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE, ST##_HOLD_MULTIPLIER) +#if !ENABLED(TMC_USE_SW_SPI) +struct MarlinTMCSPIInterface : public TMCSPIInterface { + void begin(uint32_t maxClockFreq, int bitOrder, int clkMode) override { + int spi_bitOrder = ( bitOrder == TMCSPI_BITORDER_MSB ) ? SPI_BITORDER_MSB : SPI_BITORDER_LSB; + int spi_clkmode = SPI_CLKMODE_0; + + if (clkMode == TMCSPI_CLKMODE_0) spi_clkmode = SPI_CLKMODE_0; + else if (clkMode == TMCSPI_CLKMODE_1) spi_clkmode = SPI_CLKMODE_1; + else if (clkMode == TMCSPI_CLKMODE_2) spi_clkmode = SPI_CLKMODE_2; + else if (clkMode == TMCSPI_CLKMODE_3) spi_clkmode = SPI_CLKMODE_3; + + #if !defined(TMC_SPI_MISO) || !defined(TMC_SPI_MOSI) || !defined(TMC_SPI_SCK) + // define in case the pins are unknown/not-definable/fixed. + spiInitEx(maxClockFreq); + #else + spiInitEx(maxClockFreq, TMC_SPI_SCK, TMC_SPI_MISO, TMC_SPI_MOSI); + #endif + spiSetBitOrder(spi_bitOrder); + spiSetClockMode(spi_clkmode); + } + void end() override { + spiClose(); + } + uint8_t transfer(uint8_t txval) override { + return spiRec(txval); + } + void sendRepeat(uint8_t val, uint16_t repcnt) override { + spiWriteRepeat(val, repcnt); + } +}; +static MarlinTMCSPIInterface _tmc_spiMan; +#endif + // IC = TMC model number // ST = Stepper object letter // L = Label characters @@ -48,12 +80,7 @@ enum StealthIndex : uint8_t { #if ENABLED(TMC_USE_SW_SPI) #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, true) #else -#if !defined(TMC_SPI_MISO) || !defined(TMC_SPI_MOSI) || !defined(TMC_SPI_SCK) - // define in case the pins are unknown/not-definable/fixed. - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) -#else - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS, false) -#endif + #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), &_tmc_spiMan, ST##_CHAIN_POS) #endif #if ENABLED(TMC_SERIAL_MULTIPLEXER) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 2ad0f0e0821d..d22c7f382fee 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3115,7 +3115,6 @@ void Temperature::disable_all_heaters() { #if !HAS_MAXTC_SW_SPI // Initialize SPI using the default Hardware SPI bus. // FIXME: spiBegin, spiRec and spiInit doesn't work when soft spi is used. - spiBegin(); spiInit(MAX_TC_SPEED_BITS); #endif @@ -3129,7 +3128,7 @@ void Temperature::disable_all_heaters() { } #if !HAS_MAXTC_SW_SPI - // Need to terminate our work. + // Terminate our work. spiClose(); #endif diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 37ce4ee94e56..9ddb5822ab14 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -40,6 +40,8 @@ #define BOARD_WEBSITE_URL "https://github.com/makerbase-mks" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +#define HALSPI_ESP32_STATIC_DMADESCS + // MAX_EXPANDER_BITS is defined for MKS TinyBee in HAL/ESP32/inc/Conditionals_adv.h // @@ -143,7 +145,7 @@ #define EXP2_04_PIN 5 #define EXP2_05_PIN 12 #define EXP2_06_PIN 23 -#define EXP2_07_PIN 34 +#define EXP2_07_PIN 34 // INPUT ONLY #define EXP2_08_PIN -1 // RESET // @@ -158,39 +160,69 @@ #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_RS EXP1_04_PIN #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN - #define LCD_BACKLIGHT_PIN -1 - - #if ENABLED(MKS_MINI_12864) - // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) - #define DOGLCD_CS EXP1_06_PIN - #define DOGLCD_A0 EXP1_07_PIN - #define LCD_RESET_PIN -1 - #elif ENABLED(FYSETC_MINI_12864_2_1) - // MKS_MINI_12864_V3, BTT_MINI_12864_V1, FYSETC_MINI_12864_2_1 - #define DOGLCD_CS EXP1_03_PIN - #define DOGLCD_A0 EXP1_04_PIN - #define LCD_RESET_PIN EXP1_05_PIN - #define NEOPIXEL_PIN EXP1_06_PIN - #if SD_CONNECTION_IS(ONBOARD) - #define FORCE_SOFT_SPI - #endif - #if BOTH(MKS_MINI_12864_V3, SDSUPPORT) - #define PAUSE_LCD_FOR_BUSY_SD - #endif + + #if ENABLED(MKS_TS35_V2_0) + // The MKS TS35-R V2.0 is a SPI-bus driven screen whose logic signals + // range from 0 to 3.3V. Since on the TineBee the EXP1 pins are all + // powered up to 5V we cannot use the EXP1 port for logic signals. + // Thus we have to remap the pins onto the EXP1 connector, which is + // a hassle. + + // DISPLAY PINS. + #define TFT_A0_PIN EXP1_02_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN -1 // no space for this pin on this board + + // SPI BUS PINS. + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN -1 // has to be custom soldered to work! + #define TFT_MOSI_PIN EXP2_06_PIN + #define TOUCH_SCK_PIN TFT_SCK_PIN + #define TOUCH_MISO_PIN EXP2_01_PIN + #define TOUCH_MOSI_PIN TFT_MOSI_PIN + + // SPI BUS CHIP-SELECT PINS. + #define TFT_CS_PIN EXP2_04_PIN + #define TOUCH_CS_PIN EXP2_05_PIN + + #define TOUCH_INT_PIN EXP2_03_PIN + + // Disable any LCD related PINs config + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 #else - #define LCD_PINS_D4 EXP1_05_PIN - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define LCD_PINS_D5 EXP1_06_PIN - #define LCD_PINS_D6 EXP1_07_PIN - #define LCD_PINS_D7 EXP1_08_PIN + #define LCD_BACKLIGHT_PIN -1 + + #if ENABLED(MKS_MINI_12864) + // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) + #define DOGLCD_CS EXP1_06_PIN + #define DOGLCD_A0 EXP1_07_PIN + #define LCD_RESET_PIN -1 + #elif ENABLED(FYSETC_MINI_12864_2_1) + // MKS_MINI_12864_V3, BTT_MINI_12864_V1, FYSETC_MINI_12864_2_1 + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + #define LCD_RESET_PIN EXP1_05_PIN + #define NEOPIXEL_PIN EXP1_06_PIN + #if SD_CONNECTION_IS(ONBOARD) + #define FORCE_SOFT_SPI + #endif + #if BOTH(MKS_MINI_12864_V3, SDSUPPORT) + #define PAUSE_LCD_FOR_BUSY_SD + #endif + #else + #define LCD_PINS_D4 EXP1_05_PIN + #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #define LCD_PINS_D5 EXP1_06_PIN + #define LCD_PINS_D6 EXP1_07_PIN + #define LCD_PINS_D7 EXP1_08_PIN + #endif + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 600 #endif - #define BOARD_ST7920_DELAY_1 96 - #define BOARD_ST7920_DELAY_2 48 - #define BOARD_ST7920_DELAY_3 600 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 2006900bae5b..8ce7cb488e66 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -170,7 +170,7 @@ // To minimize pin usage use the same clock pin as the display/SD card reader. (May generate LCD noise.) #define TMC_SPI_SCK EXP2_02_PIN // If pin 2_06 is unused, it can be used for the clock to avoid the LCD noise. - //#define TMC_SW_SCK P2_06 + //#define TMC_SPI_SCK P2_06 #if ENABLED(SOFTWARE_DRIVER_ENABLE) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 85d7d0f16ecb..ffa9d7bfb501 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -321,9 +321,6 @@ #define BTN_EN1 EXP2_03_PIN #define BTN_ENC EXP1_02_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define TFT_BUFFER_SIZE 2400 #ifndef TFT_WIDTH diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 644ca80651c5..4395d1c4760b 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -390,26 +390,60 @@ #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_07_PIN - #define TFT_A0_PIN EXP1_08_PIN - #define TFT_DC_PIN EXP1_08_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TFT_RESET_PIN EXP1_04_PIN - - #define LCD_USE_DMA_SPI - - #define TOUCH_INT_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - - // SPI 1 - #define SD_SCK_PIN EXP2_02_PIN - #define SD_MISO_PIN EXP2_01_PIN - #define SD_MOSI_PIN EXP2_06_PIN + #if ENABLED(MKS_TS35_V2_0) + // OPTIONAL CONTROLS BESIDE THE TOUCH SCREEN + // (the TS35-R V2.0 model does not have them) + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + + // DISPLAY PINS. + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN + + // SPI BUS PINS. + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN -1 // has to be custom soldered to work! + #define TFT_MOSI_PIN EXP2_06_PIN + #define TOUCH_SCK_PIN TFT_SCK_PIN + #define TOUCH_MISO_PIN EXP2_01_PIN + #define TOUCH_MOSI_PIN TFT_MOSI_PIN + + // SPI BUS CHIP-SELECT PINS. + #define TFT_CS_PIN EXP1_07_PIN + #define TOUCH_CS_PIN EXP1_05_PIN + + #define TOUCH_INT_PIN EXP1_06_PIN + + // Disable any LCD related PINs config + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_RS -1 + + #ifndef TFT_QUEUE_SIZE + #define TFT_QUEUE_SIZE 6144 + #endif + #else + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_A0_PIN EXP1_08_PIN + #define TFT_DC_PIN EXP1_08_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + #define TFT_RESET_PIN EXP1_04_PIN + + #define LCD_USE_DMA_SPI + + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_CS_PIN EXP1_05_PIN + // TOUCH_BUTTONS_HW_SPI_DEVICE = 1 + #define TOUCH_SCK_PIN P0_15 + #define TOUCH_MISO_PIN P0_17 + #define TOUCH_MOSI_PIN P0_18 + #endif - #define TFT_BUFFER_SIZE 2400 + #ifndef TFT_BUFFER_SIZE + #define TFT_BUFFER_SIZE 2400 + #endif #elif IS_TFTGLCD_PANEL @@ -417,8 +451,6 @@ #define TFTGLCD_CS EXP2_03_PIN #endif - #define SD_DETECT_PIN EXP2_07_PIN - #else #define BTN_ENC EXP1_02_PIN // (58) open-drain diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index ec74cc640e85..927849971558 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -35,6 +35,9 @@ #endif #endif +// BTT SKR V1.4 = 12MHz +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 33b22522b4ca..30e52a39dc6d 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -184,7 +184,7 @@ #define SD_MISO_PIN P1_23 // J8-3 (moved from EXP2 P0.8) #define SD_MOSI_PIN P2_12 // J8-4 (moved from EXP2 P0.9) #define SD_SS_PIN P0_28 - #define LPC_SOFTWARE_SPI // With a custom cable we need software SPI because the + #define SOFTWARE_SPI // With a custom cable we need software SPI because the // selected pins are not on a hardware SPI controller #elif SD_CONNECTION_IS(LCD) || SD_CONNECTION_IS(ONBOARD) #define SD_SCK_PIN P0_07 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index b365e7c9583c..4034490de897 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -300,8 +300,10 @@ #define TOUCH_INT_PIN EXP1_06_PIN #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + // TOUCH_BUTTONS_HW_SPI_DEVICE = 2 + #define TOUCH_SCK_PIN P0_7 + #define TOUCH_MISO_PIN P0_8 + #define TOUCH_MOSI_PIN P0_9 // Disable any LCD related PINs config #define LCD_PINS_ENABLE -1 diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 358a1d87b1f6..5b54ee62b633 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -349,8 +349,10 @@ #define TOUCH_INT_PIN EXP1_06_PIN #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 + // TOUCH_BUTTONS_HW_SPI_DEVICE = 2 + #define TOUCH_SCK_PIN P0_7 + #define TOUCH_MISO_PIN P0_8 + #define TOUCH_MOSI_PIN P0_9 // Disable any LCD related PINs config #define LCD_PINS_ENABLE -1 diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 8d18e41bf108..2798ad97252e 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -501,6 +501,15 @@ #if _EXISTS(TFTGLCD_CS) REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_CS) #endif +#if _EXISTS(TFTGLCD_SCK) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_SCK) +#endif +#if _EXISTS(TFTGLCD_MISO) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_MISO) +#endif +#if _EXISTS(TFTGLCD_MOSI) + REPORT_NAME_DIGITAL(__LINE__, TFTGLCD_MOSI) +#endif // // E Multiplexing diff --git a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h index f157c8e45544..43ec80988779 100644 --- a/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_MINGDA_MPX_ARM_MINI.h @@ -148,9 +148,6 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 #endif #if NEED_TOUCH_PINS diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h index be5f6c740482..291eeee132c3 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN.h @@ -182,8 +182,6 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 #define TFT_BUFFER_SIZE 14400 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index 8d48bcca4764..62e592f290be 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -287,9 +287,6 @@ #define TFT_RESET_PIN EXP1_04_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_USE_DMA_SPI #endif @@ -329,9 +326,9 @@ #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define PIN_SPI_SCK EXP2_02_PIN - #define PIN_TFT_MISO EXP2_01_PIN - #define PIN_TFT_MOSI EXP2_06_PIN + #define TFTGLCD_SCK EXP2_02_PIN + #define TFTGLCD_MISO EXP2_01_PIN + #define TFTGLCD_MOSI EXP2_06_PIN #define TFTGLCD_CS EXP2_03_PIN #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h index 712b7773ab8a..b78734dacd0e 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h @@ -287,9 +287,6 @@ #define TFT_RESET_PIN PC6 #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #define LCD_USE_DMA_SPI #endif @@ -329,9 +326,9 @@ #elif IS_TFTGLCD_PANEL #if ENABLED(TFTGLCD_PANEL_SPI) - #define PIN_SPI_SCK PA5 - #define PIN_TFT_MISO PA6 - #define PIN_TFT_MOSI PA7 + #define TFTGLCD_SCK PA5 + #define TFTGLCD_MISO PA6 + #define TFTGLCD_MOSI PA7 #define TFTGLCD_CS PE8 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h index 858dabb8b986..020a3add4572 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h @@ -202,9 +202,6 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 - #define TFT_BUFFER_SIZE 14400 #endif diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h index b5341082f4ea..9920ad95bec2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_PRO.h @@ -243,8 +243,6 @@ #define TFT_BUFFER_SIZE 14400 #if NEED_TOUCH_PINS - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 2 #define TOUCH_CS_PIN PA7 // SPI2_NSS #define TOUCH_SCK_PIN PB13 // SPI2_SCK #define TOUCH_MISO_PIN PB14 // SPI2_MISO diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h index 416fece66aad..936918cad633 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_common.h @@ -272,9 +272,6 @@ #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h index 603da09d14ef..7fccca018181 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h @@ -290,9 +290,6 @@ #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index cac9c22fe5b5..309fb12910b9 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -309,9 +309,6 @@ #define LCD_BACKLIGHT_PIN EXP1_03_PIN #define TFT_BACKLIGHT_PIN LCD_BACKLIGHT_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - #ifndef TFT_WIDTH #define TFT_WIDTH 480 #endif diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index fc609f11e67a..cd4d527500da 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -101,8 +101,10 @@ uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) // Select card chipSelect(); +#ifdef SD_WRITE_TIMEOUT // Wait up to 300 ms if busy waitNotBusy(SD_WRITE_TIMEOUT); +#endif uint8_t *pa = (uint8_t *)(&arg); @@ -115,7 +117,7 @@ uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) d[5] = CRC7(d, 5); // Send message - LOOP_L_N(k, 6) spiSend(d[k]); + spiWrite(d, 6); #else // Send command @@ -133,6 +135,7 @@ uint8_t DiskIODriver_SPI_SD::cardCommand(const uint8_t cmd, const uint32_t arg) // Wait for response for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++) { /* Intentionally left empty */ } + return status_; } @@ -165,14 +168,18 @@ uint32_t DiskIODriver_SPI_SD::cardSize() { } void DiskIODriver_SPI_SD::chipDeselect() { + if (!chipSelected) return; extDigitalWrite(chipSelectPin_, HIGH); spiSend(0xFF); // Ensure MISO goes high impedance spiClose(); + chipSelected = false; } void DiskIODriver_SPI_SD::chipSelect() { - spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, chipSelectPin_); + if (chipSelected) return; + spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, -1); extDigitalWrite(chipSelectPin_, LOW); + chipSelected = true; } /** @@ -209,10 +216,14 @@ bool DiskIODriver_SPI_SD::erase(uint32_t firstBlock, uint32_t lastBlock) { error(SD_CARD_ERROR_ERASE); goto FAIL; } +#ifdef SD_ERASE_TIMEOUT if (!waitNotBusy(SD_ERASE_TIMEOUT)) { error(SD_CARD_ERROR_ERASE_TIMEOUT); goto FAIL; } +#else + while (spiRec() != 0xFF) {} +#endif chipDeselect(); return true; FAIL: @@ -251,7 +262,9 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi errorCode_ = type_ = 0; chipSelectPin_ = chipSelectPin; // 16-bit init start time allows over a minute +#ifdef SD_INIT_TIMEOUT const millis_t init_timeout = millis() + SD_INIT_TIMEOUT; +#endif uint32_t arg; hal.watchdog_refresh(); // In case init takes too long @@ -266,23 +279,29 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi extDigitalWrite(chipSelectPin_, HIGH); // For some CPUs pinMode can write the wrong data so init desired data value first pinMode(chipSelectPin_, OUTPUT); // Solution for #8746 by @benlye #endif - spiBegin(); // Set SCK rate for initialization commands spiRate_ = SPI_SD_INIT_RATE; - spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, chipSelectPin_); + spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, -1); // Must supply min of 74 clock cycles with CS high. - LOOP_L_N(i, 10) spiSend(0xFF); + // TODO: can we just use spiWriteRepeat??? + spiWriteRepeat(0xFF, 10); hal.watchdog_refresh(); // In case init takes too long + // Delayed chip-select activate. + extDigitalWrite(chipSelectPin_, LOW); + chipSelected = true; + // Command to go idle in SPI mode while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { +#ifdef SD_INIT_TIMEOUT if (ELAPSED(millis(), init_timeout)) { error(SD_CARD_ERROR_CMD0); goto FAIL; } +#endif } #if ENABLED(SD_CHECK_AND_RETRY) @@ -293,6 +312,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // check SD version for (;;) { + if (cardCommand(CMD8, 0x1AA) == (R1_ILLEGAL_COMMAND | R1_IDLE_STATE)) { type(SD_CARD_TYPE_SD1); break; @@ -305,10 +325,12 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi break; } +#ifdef SD_INIT_TIMEOUT if (ELAPSED(millis(), init_timeout)) { error(SD_CARD_ERROR_CMD8); goto FAIL; } +#endif } hal.watchdog_refresh(); // In case init takes too long @@ -316,12 +338,15 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Initialize card and send host supports SDHC if SD2 arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0; while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) { +#ifdef SD_INIT_TIMEOUT // Check for timeout if (ELAPSED(millis(), init_timeout)) { error(SD_CARD_ERROR_ACMD41); goto FAIL; } +#endif } + // If SD2 read OCR register to check for SDHC card if (type() == SD_CARD_TYPE_SD2) { if (cardCommand(CMD58, 0)) { @@ -332,6 +357,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Discard rest of ocr - contains allowed voltage range LOOP_L_N(i, 3) spiRec(); } + chipDeselect(); ready = true; @@ -463,18 +489,22 @@ bool DiskIODriver_SPI_SD::readData(uint8_t *dst) { bool DiskIODriver_SPI_SD::readData(uint8_t *dst, const uint16_t count) { bool success = false; +#ifdef SD_READ_TIMEOUT const millis_t read_timeout = millis() + SD_READ_TIMEOUT; +#endif while ((status_ = spiRec()) == 0xFF) { // Wait for start block token +#ifdef SD_READ_TIMEOUT if (ELAPSED(millis(), read_timeout)) { error(SD_CARD_ERROR_READ_TIMEOUT); goto FAIL; } +#endif } if (status_ == DATA_START_BLOCK) { spiRead(dst, count); // Transfer data - const uint16_t recvCrc = (spiRec() << 8) | spiRec(); + const uint16_t recvCrc = ((uint16_t)spiRec() << 8) | (uint16_t)spiRec(); #if ENABLED(SD_CHECK_AND_RETRY) success = !crcSupported || recvCrc == CRC_CCITT(dst, count); if (!success) error(SD_CARD_ERROR_READ_CRC); @@ -486,7 +516,9 @@ bool DiskIODriver_SPI_SD::readData(uint8_t *dst, const uint16_t count) { else error(SD_CARD_ERROR_READ); +#ifdef SD_READ_TIMEOUT FAIL: +#endif chipDeselect(); return success; } @@ -583,12 +615,18 @@ bool DiskIODriver_SPI_SD::writeBlock(uint32_t blockNumber, const uint8_t *src) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; // Use address if not SDHC card if (!cardCommand(CMD24, blockNumber)) { if (writeData(DATA_START_BLOCK, src)) { - if (waitNotBusy(SD_WRITE_TIMEOUT)) { // Wait for flashing to complete +#ifdef SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) { // Wait for flashing to complete + error(SD_CARD_ERROR_WRITE_TIMEOUT); + } + else +#else + while (spiRec() != 0xFF) {} +#endif + { success = !(cardCommand(CMD13, 0) || spiRec()); // Response is r2 so get and check two bytes for nonzero if (!success) error(SD_CARD_ERROR_WRITE_PROGRAMMING); } - else - error(SD_CARD_ERROR_WRITE_TIMEOUT); } } else @@ -606,15 +644,22 @@ bool DiskIODriver_SPI_SD::writeBlock(uint32_t blockNumber, const uint8_t *src) { bool DiskIODriver_SPI_SD::writeData(const uint8_t *src) { if (ENABLED(SDCARD_READONLY)) return false; - bool success = true; chipSelect(); // Wait for previous write to finish - if (!waitNotBusy(SD_WRITE_TIMEOUT) || !writeData(WRITE_MULTIPLE_TOKEN, src)) { - error(SD_CARD_ERROR_WRITE_MULTIPLE); - success = false; - } +#ifdef SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) + goto FAIL; +#else + while (spiRec() != 0xFF) {} +#endif + if (!writeData(WRITE_MULTIPLE_TOKEN, src)) + goto FAIL; chipDeselect(); - return success; + return true; +FAIL: + chipDeselect(); + error(SD_CARD_ERROR_WRITE_MULTIPLE); + return false; } // Send one block of data for write block or write multiple blocks @@ -670,17 +715,31 @@ bool DiskIODriver_SPI_SD::writeStart(uint32_t blockNumber, const uint32_t eraseC bool DiskIODriver_SPI_SD::writeStop() { if (ENABLED(SDCARD_READONLY)) return false; - bool success = false; chipSelect(); - if (waitNotBusy(SD_WRITE_TIMEOUT)) { - spiSend(STOP_TRAN_TOKEN); - success = waitNotBusy(SD_WRITE_TIMEOUT); - } - else +#ifdef SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) { error(SD_CARD_ERROR_STOP_TRAN); + goto FAIL; + } +#else + while (spiRec() != 0xFF) {} +#endif + spiSend(STOP_TRAN_TOKEN); +#ifdef SD_WRITE_TIMEOUT + if (!waitNotBusy(SD_WRITE_TIMEOUT)) { + goto FAIL; + } +#else + while (spiRec() != 0xFF) {} +#endif chipDeselect(); - return success; + return true; +#ifdef SD_WRITE_TIMEOUT +FAIL: + chipDeselect(); + return false; +#endif } #endif // NEED_SD2CARD_SPI diff --git a/Marlin/src/sd/Sd2Card.h b/Marlin/src/sd/Sd2Card.h index e0dce02a0236..d08d1dbd5203 100644 --- a/Marlin/src/sd/Sd2Card.h +++ b/Marlin/src/sd/Sd2Card.h @@ -39,10 +39,24 @@ #include -uint16_t const SD_INIT_TIMEOUT = 2000, // (ms) Init timeout - SD_ERASE_TIMEOUT = 10000, // (ms) Erase timeout - SD_READ_TIMEOUT = 300, // (ms) Read timeout - SD_WRITE_TIMEOUT = 600; // (ms) Write timeout +#ifndef SD_DISABLE_TIMEOUTS +#ifndef SD_INIT_TIMEOUT + // (ms) Init timeout + #define SD_INIT_TIMEOUT 2000 +#endif +#ifndef SD_ERASE_TIMEOUT + // (ms) Erase timeout + #define SD_ERASE_TIMEOUT 10000 +#endif +#ifndef SD_READ_TIMEOUT + // (ms) Read timeout + #define SD_READ_TIMEOUT 300 +#endif +#ifndef SD_WRITE_TIMEOUT + // (ms) Write timeout + #define SD_WRITE_TIMEOUT 600 +#endif +#endif //SD_DISABLE_TIMEOUTS // SD card errors typedef enum : uint8_t { @@ -179,6 +193,7 @@ class DiskIODriver_SPI_SD : public DiskIODriver { spiRate_, status_, type_; + bool chipSelected = false; // private functions inline uint8_t cardAcmd(const uint8_t cmd, const uint32_t arg) { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 1f2ecf10f2d8..3020a5787b78 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -42,7 +42,6 @@ void MAX3421e::ncs() { WRITE(USB_CS_PIN, HIGH); } // write single byte into MAX3421 register void MAX3421e::regWr(uint8_t reg, uint8_t data) { - spiBegin(); spiInit(SD_SPI_SPEED); cs(); spiSend(reg | 0x02); @@ -54,7 +53,6 @@ void MAX3421e::regWr(uint8_t reg, uint8_t data) { // multiple-byte write // return a pointer to memory position after last written uint8_t* MAX3421e::bytesWr(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { - spiBegin(); spiInit(SD_SPI_SPEED); cs(); spiSend(reg | 0x02); @@ -75,7 +73,6 @@ void MAX3421e::gpioWr(uint8_t data) { // single host register read uint8_t MAX3421e::regRd(uint8_t reg) { - spiBegin(); spiInit(SD_SPI_SPEED); cs(); spiSend(reg); @@ -88,7 +85,6 @@ uint8_t MAX3421e::regRd(uint8_t reg) { // multiple-byte register read // return a pointer to a memory position after last read uint8_t* MAX3421e::bytesRd(uint8_t reg, uint8_t nbytes, uint8_t *data_p) { - spiBegin(); spiInit(SD_SPI_SPEED); cs(); spiSend(reg); diff --git a/ini/features.ini b/ini/features.ini index fddda53b23fa..a7353ad2c440 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -39,9 +39,10 @@ HAS_LCDPRINT = src_filter=+ HAS_MARLINUI_HD44780 = src_filter=+ HAS_MARLINUI_U8GLIB = marlinfirmware/U8glib-HAL@~0.5.2 src_filter=+ -HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + +HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + HAS_FSMC_TFT = src_filter=+ + -HAS_SPI_TFT = src_filter=+ + +HAS_SPI_TFT = src_filter=+ +HAS_TFT_XPT2046 = src_filter=+ I2C_EEPROM = src_filter=+ SOFT_I2C_EEPROM = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/master.zip SPI_EEPROM = src_filter=+ diff --git a/ini/lpc176x.ini b/ini/lpc176x.ini index 0cb26628fe49..ec4e5270349c 100644 --- a/ini/lpc176x.ini +++ b/ini/lpc176x.ini @@ -20,7 +20,7 @@ lib_ldf_mode = off lib_compat_mode = strict extra_scripts = ${common.extra_scripts} Marlin/src/HAL/LPC1768/upload_extra_script.py -build_src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + + + lib_deps = ${common.lib_deps} Servo custom_marlin.USES_LIQUIDCRYSTAL = arduino-libraries/LiquidCrystal@~1.0.7 diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index c8f28cd0e314..97d0984b764c 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -18,7 +18,7 @@ build_flags = ${common.build_flags} -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 -build_src_filter = ${common.default_src_filter} + + +build_src_filter = ${common.default_src_filter} + + + extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py From e731821a870f5c9b2163c60213ffb642a4cf5068 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 24 Nov 2022 13:37:40 +0100 Subject: [PATCH 19/83] - various STM32 fixes --- Marlin/src/HAL/STM32/HAL_SPI_HW.cpp | 2 +- Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp | 12 +++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp index ba650f2b49e4..0c872f61d0d0 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp @@ -51,7 +51,7 @@ #include "pinconfig.h" -#include "HAL_NVIC.h" +#include "../shared/ARM/HAL_NVIC.h" // ------------------------ // Hardware SPI diff --git a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp index 40957969f37d..a431fa768446 100644 --- a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp +++ b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp @@ -28,11 +28,21 @@ // See STM32F1xx reference manual page 204 #define VECTOR_TABLE_SIZE 75 #endif + #define IRQ_VECTOR_ALIGNMENT (1<<9) // Defined by GCC. // The vector is located in flash memory, thus there may be no memory bus for write access // wired into the CPU (hard fault at attempt). extern void (*const g_pfnVectors[VECTOR_TABLE_SIZE])(); -#define _NVIC_HAS_DEFAULT_VECTOR + #define _NVIC_HAS_DEFAULT_VECTOR +#elif defined(STM32F4xx) + // There are a few less entries specifically for "STM32F405xx/07xx and STM32F415xx/17xx" but w/e. + #define VECTOR_TABLE_SIZE 107 + #define IRQ_VECTOR_ALIGNMENT (1<<9) + // Defined by GCC. + // The vector is located in flash memory, thus there may be no memory bus for write access + // wired into the CPU (hard fault at attempt). + extern void (*const g_pfnVectors[VECTOR_TABLE_SIZE])(); + #define _NVIC_HAS_DEFAULT_VECTOR #elif defined(TARGET_LPC1768) // See NXP UM10360 page 75ff #define VECTOR_TABLE_SIZE 51 From 1394088c3c02a8309b66034ddd6f7008098f3d8d Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 24 Nov 2022 13:50:25 +0100 Subject: [PATCH 20/83] - various ESP32 fixes (HAL NVIC for ARM only) --- Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 2 +- platformio.ini | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index 84b558117028..6f9ce74514a8 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -1652,7 +1652,7 @@ static void SPIInstallAsync(spi_dev_t& SPI, intr_handle_t& handleOut) { _spi_on_error(1); } -static void SPIUninstallAsync(intr_handle_t handle) { +static void __attribute__((unused)) SPIUninstallAsync(intr_handle_t handle) { // Unregister the ISR. esp_err_t err = esp_intr_free(handle); diff --git a/platformio.ini b/platformio.ini index 613f2c963abe..2e799010209f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -53,7 +53,7 @@ extra_scripts = lib_deps = default_src_filter = + - - + - - - - - - - - - + - - - - - - - - - - - - From f375d4d12001e12e0b3a56e7849944861e487b73 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 24 Nov 2022 19:27:40 +0100 Subject: [PATCH 21/83] - adjustment for SOFTWARE_SPI & HALSPI_HW_GENERIC on STM32 (it now compiles) - removed some compilation warnings - disabled async SPI support it HALSPI_HW_GENERIC is enabled (the generic implementations are supposed to be very easy) - SPI fixes for AVR --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 8 ++---- Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 2 +- Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp | 2 +- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 2 +- Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp | 31 +++++++++++++++++++++-- Marlin/src/HAL/STM32/HAL_SPI_SW.cpp | 34 +++++++++++++++++++++++--- Marlin/src/HAL/shared/HAL_SPI.h | 2 +- 7 files changed, 65 insertions(+), 16 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index b9d39e70f711..e12854fe79ba 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -49,8 +49,6 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } -void spiClose() { /* do nothing */ } - #if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) // ------------------------ @@ -112,9 +110,7 @@ void spiClose() { /* do nothing */ } spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); } - void spiClose() { - // nop. - } + void spiClose() { /* do nothing */ } void spiSetBitOrder(int bitOrder) { if (bitOrder == SPI_BITORDER_MSB) { @@ -401,7 +397,7 @@ void spiClose() { /* do nothing */ } LOOP_L_N(i, 16) { int bitidx = ( msb ? 15-i : i ); WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, ( data & ( 1 << bitidx )) != 0); + WRITE(SD_MOSI_PIN, ( v & ( 1 << bitidx )) != 0); WRITE(SD_SCK_PIN, HIGH); } diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index 6f9ce74514a8..a7e9e6f747da 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -88,7 +88,7 @@ static void _spi_on_error(uint32_t code = 0) { } } -static void _spi_infobeep(uint32_t code) { +static void __attribute__((unused)) _spi_infobeep(uint32_t code) { #if PIN_EXISTS(BEEPER) OUT_WRITE(BEEPER_PIN, HIGH); delay(500); diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp index 925fa563643f..c8dbfd832046 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp @@ -59,7 +59,7 @@ static void _spi_on_error() { } } -static void _spi_infobeep(uint32_t code) { +static void __attribute__((unused)) _spi_infobeep(uint32_t code) { #if PIN_EXISTS(BEEPER) OUT_WRITE(BEEPER_PIN, HIGH); delay(500); diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 25e2b266ad3a..659e0dedec44 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -96,7 +96,7 @@ static void _spi_on_error(uint32_t code = 0) { } } -static void _spi_infobeep(uint32_t code) { +static void __attribute__((unused)) _spi_infobeep(uint32_t code) { #if PIN_EXISTS(BEEPER) OUT_WRITE(BEEPER_PIN, HIGH); delay(500); diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp index 566c98890343..084764eaa510 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp @@ -39,7 +39,34 @@ * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz */ + static void _spiOnError(unsigned int beep_code = 0) { + for (;;) { +#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + } + static SPISettings spiConfig; + static uint32_t _spi_clock; /** * @brief Begin SPI port setup @@ -160,7 +187,7 @@ void spiWrite(const uint8_t *buf, uint16_t numbytes) { void *inout_buf = malloc(numbytes); if (inout_buf == nullptr) - _spi_on_error(); + _spiOnError(); memcpy(inout_buf, buf, numbytes); // Generic transfer, non-DMA. SPI.transfer(inout_buf, numbytes); @@ -168,7 +195,7 @@ } void spiWrite16(const uint16_t *buf, uint16_t numtx) { - for (uint32_t n = 0; n < numbytes; n++) { + for (uint32_t n = 0; n < numtx; n++) { SPI.transfer16(buf[n]); } } diff --git a/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp index b7d8cd6b379a..fac73cc98f20 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp @@ -40,6 +40,32 @@ // TODO: this software SPI is really bad... it tries to use SPI clock-mode 3 only...?????? + static void _spiOnError(unsigned int beep_code = 0) { + for (;;) { +#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + } + #include "../shared/Delay.h" void spiBegin(void) { @@ -121,7 +147,7 @@ void spiSetClockMode(int clockMode) { if (clockMode != SPI_CLKMODE_3) - _spi_on_error(); + _spiOnError(); } uint8_t HAL_SPI_STM32_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3 @@ -139,7 +165,7 @@ result |= ( (READ(SD_MISO_PIN) != 0) << bitidx ); } DELAY_NS(125); - return b; + return result; } uint16_t HAL_SPI_STM32_SpiTransfer_Mode_3_16bits(uint16_t v) { // using Mode 3 @@ -148,7 +174,7 @@ for (uint8_t bits = 0; bits < 16; bits++) { int bitidx = ( msb ? 15-bits : bits ); WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, (b & ( 1 << bitidx )) != 0); + WRITE(SD_MOSI_PIN, (v & ( 1 << bitidx )) != 0); delaySPIFunc(); WRITE(SD_SCK_PIN, HIGH); @@ -157,7 +183,7 @@ result |= ( (READ(SD_MISO_PIN) != 0) << bitidx ); } DELAY_NS(125); - return b; + return result; } // Soft SPI receive byte diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index 2dc4500155d7..e47e68bf91cc 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -130,7 +130,7 @@ void spiWriteRepeat(uint8_t val, uint16_t repcnt); // Send a repetition of 16bit numbers. void spiWriteRepeat16(uint16_t val, uint16_t repcnt); -#if (defined(ESP_PLATFORM) || defined(STM32F1xx) || defined(STM32F4xx) || defined(TARGET_LPC1768)) && !defined(SOFTWARE_SPI) && defined(USE_SPI_DMA_TC) +#if (defined(ESP_PLATFORM) || defined(STM32F1xx) || defined(STM32F4xx) || defined(TARGET_LPC1768)) && !defined(SOFTWARE_SPI) && !defined(HALSPI_HW_GENERIC) && defined(USE_SPI_DMA_TC) #define HAL_SPI_SUPPORTS_ASYNC From 4223ef4cb40e76434b2a85a99cdb1fadbd59046b Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Tue, 29 Nov 2022 16:27:59 +0100 Subject: [PATCH 22/83] - reliability upgrade for ATmega2560 MCU series (640-1280-1281-2560-2561) The _ATmega_savePinAlternate function saves the device state which affects the provided GPIO pin and disables it. This way the provided pin can be safely used for GPIO purposes until the _ATmega_restorePinAlternate function is called. Then the device state is reset prior to the call of _ATmega_savePinAlternate, assuming that no other device state change related to the disabled peripherals was undertaken inbetween the function calls. - added REPRAP_FULL_GRAPHIC_SMART_CONTROLLER to MKS TinyBee V1.0 --- Marlin/src/HAL/AVR/HAL.cpp | 30 + Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/AVR/HAL_SPI.cpp | 2 + Marlin/src/HAL/AVR/fastio/fastio_1280.h | 2 + Marlin/src/HAL/AVR/fastio/fastio_1281.h | 2 + Marlin/src/HAL/AVR/fastio/fastio_168.h | 2 + Marlin/src/HAL/AVR/fastio/fastio_644.h | 2 + Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h | 2 + Marlin/src/HAL/AVR/registers.h | 1933 ++++++++++++++++++++ Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 6 +- 10 files changed, 1980 insertions(+), 3 deletions(-) create mode 100644 Marlin/src/HAL/AVR/registers.h diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 5382eb36a2bd..4ff643c48ff1 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -61,6 +61,15 @@ void save_reset_reason() { wdt_disable(); } +#include "registers.h" + +MarlinHAL::MarlinHAL() { +#if ENABLED(HAL_AVR_DIRTY_INIT) + // Clean-wipe the device state. + _ATmega_resetperipherals(); +#endif +} + void MarlinHAL::init() { // Init Servo Pins #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW) @@ -78,6 +87,27 @@ void MarlinHAL::init() { #endif init_pwm_timers(); // Init user timers to default frequency - 1000HZ + +#if defined(BEEPER_PIN) || ENABLED(ATMEGA_NO_BEEPFIX) + // Make sure no alternative is locked onto the BEEPER. + // This fixes the issue where the ATmega is constantly beeping. + // Might destroy other peripherals using the pin; to circumvent that please undefine the BEEPER_PIN! + // The true culprit is the AVR ArduinoCore that enables peripherals redundantly. + // (USART1 on the GeeeTech GT2560) + _ATmega_savePinAlternate(BEEPER_PIN); + + OUT_WRITE(BEEPER_PIN, LOW); +#endif + + // EXAMPLE: beep loop using proper pin state. +#if defined(BEEPER_PIN) && 0 + while (true) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); + } +#endif } void MarlinHAL::reboot() { diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index d458790979ff..465307fb0373 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -187,7 +187,7 @@ class MarlinHAL { public: // Earliest possible init, before setup() - MarlinHAL() {} + MarlinHAL(); // Watchdog static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp index e12854fe79ba..7c324c032cd9 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI.cpp @@ -33,6 +33,8 @@ #include "../../inc/MarlinConfig.h" +#include "registers.h" + void spiBegin() { #if PIN_EXISTS(SD_SS) // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h index f482f823e8b9..071f1f629d9e 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -586,6 +586,8 @@ #define DIO85_DDR DDRH #define DIO85_PWM nullptr +#define DIO_NUM 86 + #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h index e0bc5e2995d1..eec0b663178b 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h @@ -383,6 +383,8 @@ #define DIO53_DDR DDRF #define DIO53_PWM nullptr +#define DIO_NUM 54 + #undef PA0 #define PA0_PIN PINA0 #define PA0_RPORT PINA diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h index 8cfdd1e8f825..ece6deb6311f 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_168.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h @@ -188,6 +188,8 @@ #define DIO21_DDR DDRC #define DIO21_PWM nullptr +#define DIO_NUM 22 + #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index f4a9427e0abf..193c018ae2df 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -279,6 +279,8 @@ #define DIO31_DDR DDRA #define DIO31_PWM nullptr +#define DIO_NUM 32 + #define AIO0_PIN PINA0 #define AIO0_RPORT PINA #define AIO0_WPORT PORTA diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index 51d400b70565..df10b58a2df2 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -380,6 +380,8 @@ #define DIO47_PWM 0 #define DIO47_DDR DDRE +#define DIO_NUM 48 + #define TEENSY_E2 46 #define TEENSY_E3 47 diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h new file mode 100644 index 000000000000..10f55dbb3d68 --- /dev/null +++ b/Marlin/src/HAL/AVR/registers.h @@ -0,0 +1,1933 @@ +/** + * 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 . + * + */ + +#pragma once + +// OVERVIEW OF PREPROCESSOR DEFINITIONS: +// __AVR_ATmega2560__ +// __AVR_ATmega1284P__ +// __AVR_ATmega1280__ +// __AVR_ATmega644__ +// __AVR_ATmega644P__ +// __AVR_ATmega2561__ + +// ATmega2560 technical reference manual date: 28th of November, 2022 + +// As old as the ATmega series of CPU is, the worse the actual libraries making +// use of the MCU likely are. + +// These registers as references do not take program space since they are purely references. + +// Adding 0x20 to the memory location of registers is a retarded idea. +// See page 403 of ATmega2560 documentation, Note 4. + +struct _bit_reg_t { + uint8_t val; + + bool getValue(uint8_t idx) { + return ( val & (1< 0 + _SPA_DIOn_PORTRET(pin, 0) +#endif +#if DIO_NUM > 1 + _SPA_DIOn_PORTRET(pin, 1) +#endif +#if DIO_NUM > 2 + _SPA_DIOn_PORTRET(pin, 2) +#endif +#if DIO_NUM > 3 + _SPA_DIOn_PORTRET(pin, 3) +#endif +#if DIO_NUM > 4 + _SPA_DIOn_PORTRET(pin, 4) +#endif +#if DIO_NUM > 5 + _SPA_DIOn_PORTRET(pin, 5) +#endif +#if DIO_NUM > 6 + _SPA_DIOn_PORTRET(pin, 6) +#endif +#if DIO_NUM > 7 + _SPA_DIOn_PORTRET(pin, 7) +#endif +#if DIO_NUM > 8 + _SPA_DIOn_PORTRET(pin, 8) +#endif +#if DIO_NUM > 9 + _SPA_DIOn_PORTRET(pin, 9) +#endif + +#if DIO_NUM > 10 + _SPA_DIOn_PORTRET(pin, 10) +#endif +#if DIO_NUM > 11 + _SPA_DIOn_PORTRET(pin, 11) +#endif +#if DIO_NUM > 12 + _SPA_DIOn_PORTRET(pin, 12) +#endif +#if DIO_NUM > 13 + _SPA_DIOn_PORTRET(pin, 13) +#endif +#if DIO_NUM > 14 + _SPA_DIOn_PORTRET(pin, 14) +#endif +#if DIO_NUM > 15 + _SPA_DIOn_PORTRET(pin, 15) +#endif +#if DIO_NUM > 16 + _SPA_DIOn_PORTRET(pin, 16) +#endif +#if DIO_NUM > 17 + _SPA_DIOn_PORTRET(pin, 17) +#endif +#if DIO_NUM > 18 + _SPA_DIOn_PORTRET(pin, 18) +#endif +#if DIO_NUM > 19 + _SPA_DIOn_PORTRET(pin, 19) +#endif + +#if DIO_NUM > 20 + _SPA_DIOn_PORTRET(pin, 20) +#endif +#if DIO_NUM > 21 + _SPA_DIOn_PORTRET(pin, 21) +#endif +#if DIO_NUM > 22 + _SPA_DIOn_PORTRET(pin, 22) +#endif +#if DIO_NUM > 23 + _SPA_DIOn_PORTRET(pin, 23) +#endif +#if DIO_NUM > 24 + _SPA_DIOn_PORTRET(pin, 24) +#endif +#if DIO_NUM > 25 + _SPA_DIOn_PORTRET(pin, 25) +#endif +#if DIO_NUM > 26 + _SPA_DIOn_PORTRET(pin, 26) +#endif +#if DIO_NUM > 27 + _SPA_DIOn_PORTRET(pin, 27) +#endif +#if DIO_NUM > 28 + _SPA_DIOn_PORTRET(pin, 28) +#endif +#if DIO_NUM > 29 + _SPA_DIOn_PORTRET(pin, 29) +#endif + +#if DIO_NUM > 30 + _SPA_DIOn_PORTRET(pin, 30) +#endif +#if DIO_NUM > 31 + _SPA_DIOn_PORTRET(pin, 31) +#endif +#if DIO_NUM > 32 + _SPA_DIOn_PORTRET(pin, 32) +#endif +#if DIO_NUM > 33 + _SPA_DIOn_PORTRET(pin, 33) +#endif +#if DIO_NUM > 34 + _SPA_DIOn_PORTRET(pin, 34) +#endif +#if DIO_NUM > 35 + _SPA_DIOn_PORTRET(pin, 35) +#endif +#if DIO_NUM > 36 + _SPA_DIOn_PORTRET(pin, 36) +#endif +#if DIO_NUM > 37 + _SPA_DIOn_PORTRET(pin, 37) +#endif +#if DIO_NUM > 38 + _SPA_DIOn_PORTRET(pin, 38) +#endif +#if DIO_NUM > 39 + _SPA_DIOn_PORTRET(pin, 39) +#endif + +#if DIO_NUM > 40 + _SPA_DIOn_PORTRET(pin, 40) +#endif +#if DIO_NUM > 41 + _SPA_DIOn_PORTRET(pin, 41) +#endif +#if DIO_NUM > 42 + _SPA_DIOn_PORTRET(pin, 42) +#endif +#if DIO_NUM > 43 + _SPA_DIOn_PORTRET(pin, 43) +#endif +#if DIO_NUM > 44 + _SPA_DIOn_PORTRET(pin, 44) +#endif +#if DIO_NUM > 45 + _SPA_DIOn_PORTRET(pin, 45) +#endif +#if DIO_NUM > 46 + _SPA_DIOn_PORTRET(pin, 46) +#endif +#if DIO_NUM > 47 + _SPA_DIOn_PORTRET(pin, 47) +#endif +#if DIO_NUM > 48 + _SPA_DIOn_PORTRET(pin, 48) +#endif +#if DIO_NUM > 49 + _SPA_DIOn_PORTRET(pin, 49) +#endif + +#if DIO_NUM > 50 + _SPA_DIOn_PORTRET(pin, 50) +#endif +#if DIO_NUM > 51 + _SPA_DIOn_PORTRET(pin, 51) +#endif +#if DIO_NUM > 52 + _SPA_DIOn_PORTRET(pin, 52) +#endif +#if DIO_NUM > 53 + _SPA_DIOn_PORTRET(pin, 53) +#endif +#if DIO_NUM > 54 + _SPA_DIOn_PORTRET(pin, 54) +#endif +#if DIO_NUM > 55 + _SPA_DIOn_PORTRET(pin, 55) +#endif +#if DIO_NUM > 56 + _SPA_DIOn_PORTRET(pin, 56) +#endif +#if DIO_NUM > 57 + _SPA_DIOn_PORTRET(pin, 57) +#endif +#if DIO_NUM > 58 + _SPA_DIOn_PORTRET(pin, 58) +#endif +#if DIO_NUM > 59 + _SPA_DIOn_PORTRET(pin, 59) +#endif + +#if DIO_NUM > 60 + _SPA_DIOn_PORTRET(pin, 60) +#endif +#if DIO_NUM > 61 + _SPA_DIOn_PORTRET(pin, 61) +#endif +#if DIO_NUM > 62 + _SPA_DIOn_PORTRET(pin, 62) +#endif +#if DIO_NUM > 63 + _SPA_DIOn_PORTRET(pin, 63) +#endif +#if DIO_NUM > 64 + _SPA_DIOn_PORTRET(pin, 64) +#endif +#if DIO_NUM > 65 + _SPA_DIOn_PORTRET(pin, 65) +#endif +#if DIO_NUM > 66 + _SPA_DIOn_PORTRET(pin, 66) +#endif +#if DIO_NUM > 67 + _SPA_DIOn_PORTRET(pin, 67) +#endif +#if DIO_NUM > 68 + _SPA_DIOn_PORTRET(pin, 68) +#endif +#if DIO_NUM > 69 + _SPA_DIOn_PORTRET(pin, 69) +#endif + +#if DIO_NUM > 70 + _SPA_DIOn_PORTRET(pin, 70) +#endif +#if DIO_NUM > 71 + _SPA_DIOn_PORTRET(pin, 71) +#endif +#if DIO_NUM > 72 + _SPA_DIOn_PORTRET(pin, 72) +#endif +#if DIO_NUM > 73 + _SPA_DIOn_PORTRET(pin, 73) +#endif +#if DIO_NUM > 74 + _SPA_DIOn_PORTRET(pin, 74) +#endif +#if DIO_NUM > 75 + _SPA_DIOn_PORTRET(pin, 75) +#endif +#if DIO_NUM > 76 + _SPA_DIOn_PORTRET(pin, 76) +#endif +#if DIO_NUM > 77 + _SPA_DIOn_PORTRET(pin, 77) +#endif +#if DIO_NUM > 78 + _SPA_DIOn_PORTRET(pin, 78) +#endif +#if DIO_NUM > 79 + _SPA_DIOn_PORTRET(pin, 79) +#endif + +#if DIO_NUM > 80 + _SPA_DIOn_PORTRET(pin, 80) +#endif +#if DIO_NUM > 81 + _SPA_DIOn_PORTRET(pin, 81) +#endif +#if DIO_NUM > 82 + _SPA_DIOn_PORTRET(pin, 82) +#endif +#if DIO_NUM > 83 + _SPA_DIOn_PORTRET(pin, 83) +#endif +#if DIO_NUM > 84 + _SPA_DIOn_PORTRET(pin, 84) +#endif +#if DIO_NUM > 85 + _SPA_DIOn_PORTRET(pin, 85) +#endif +#if DIO_NUM > 86 + _SPA_DIOn_PORTRET(pin, 86) +#endif +#if DIO_NUM > 87 + _SPA_DIOn_PORTRET(pin, 87) +#endif +#if DIO_NUM > 88 + _SPA_DIOn_PORTRET(pin, 88) +#endif +#if DIO_NUM > 89 + _SPA_DIOn_PORTRET(pin, 89) +#endif + + // Default. + return { eATmegaPort::PORT_A, 0 }; +} + +inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { + ATmegaPinInfo info = _ATmega_getPinInfo(pin); + + pin_dev_state_t state; + + if (info.port == eATmegaPort::PORT_A) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + else if (info.port == eATmegaPort::PORT_B) { + state._PCIE0 = _PCICR._PCIE0; + + _PCICR._PCIE0 = false; + + if (info.pinidx == 7) { + state._COM1C = TIMER1._TCCRnA._COMnC; + + TIMER1._TCCRnA._COMnC = 0; + } + else if (info.pinidx == 6) { + state._COM1B = TIMER1._TCCRnA._COMnB; + + TIMER1._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 5) { + state._COM1A = TIMER1._TCCRnA._COMnA; + + TIMER1._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 4) { + state._COM2A = _TIMER2._TCCR2A._COM2A; + + _TIMER2._TCCR2A._COM2A = 0; + } + else if (info.pinidx <= 3) { + state._SPE = _SPCR._SPE; + + _SPCR._SPE = false; + } + } + else if (info.port == eATmegaPort::PORT_C) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 5 || info.pinidx == 3) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + + USART1._UCSRnB._TXEN = false; + } + if (info.pinidx == 5 || info.pinidx == 2) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + + USART1._UCSRnB._RXEN = false; + } + if (info.pinidx <= 3) { + state._PCIE0 = _PCICR._PCIE0; + + _PCICR._PCIE0 = false; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx >= 4 && info.pinidx <= 7) { + state._PCIE0 = _PCICR._PCIE0; + + _PCICR._PCIE0 = false; + } + if (info.pinidx == 5) { + state._COM3C = TIMER3._TCCRnA._COMnC; + + TIMER3._TCCRnA._COMnC = 0; + } + if (info.pinidx == 4 || info.pinidx == 3) { + state._COM3B = TIMER3._TCCRnA._COMnB; + + TIMER3._TCCRnA._COMnB = 0; + } + if (info.pinidx == 2 || info.pinidx == 0) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + + USART0._UCSRnB._RXEN = false; + } + if (info.pinidx == 2 || info.pinidx == 1) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + + USART0._UCSRnB._TXEN = false; + } + if (info.pinidx == 0) { + state._PCIE1 = _PCICR._PCIE1; + + _PCICR._PCIE1 = false; + } + } + // Port F ignored. + else if (info.port == eATmegaPort::PORT_G) { + if (info.pinidx == 5) { + state._COM0B = _TCCR0A._COM0B; + + _TCCR0A._COM0B = 0; + } + if (info.pinidx == 4 || info.pinidx == 3) { + state._AS2 = _ASSR._AS2; + + _ASSR._AS2 = false; + } + if (info.pinidx <= 2) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + } + else if (info.port == eATmegaPort::PORT_H) { + if (info.pinidx == 6) { + state._COM2B = _TIMER2._TCCR2A._COM2B; + + _TIMER2._TCCR2A._COM2B = 0; + } + if (info.pinidx == 5) { + state._COM4C = TIMER4._TCCRnA._COMnC; + + TIMER4._TCCRnA._COMnC = 0; + } + if (info.pinidx == 4) { + state._COM4B = TIMER4._TCCRnA._COMnB; + + TIMER4._TCCRnA._COMnB = 0; + } + if (info.pinidx == 3) { + state._COM4A = TIMER4._TCCRnA._COMnA; + + TIMER4._TCCRnA._COMnA = 0; + } + if (info.pinidx == 2 || info.pinidx == 0) { + state._USART2_RXEN = USART2._UCSRnB._RXEN; + + USART2._UCSRnB._RXEN = false; + } + if (info.pinidx == 2 || info.pinidx == 1) { + state._USART2_TXEN = USART2._UCSRnB._TXEN; + + USART2._UCSRnB._TXEN = false; + } + } + else if (info.port == eATmegaPort::PORT_J) { + if (info.pinidx <= 6) { + state._PCIE1 = _PCICR._PCIE1; + + _PCICR._PCIE1 = false; + } + if (info.pinidx == 2 || info.pinidx == 0) { + state._USART3_RXEN = USART3._UCSRnB._RXEN; + + USART3._UCSRnB._RXEN = false; + } + if (info.pinidx == 2 || info.pinidx == 1) { + state._USART3_TXEN = USART3._UCSRnB._TXEN; + + USART3._UCSRnB._TXEN = false; + } + } + else if (info.port == eATmegaPort::PORT_K) { + state._PCIE2 = _PCICR._PCIE2; + + _PCICR._PCIE2 = false; + } + else if (info.port == eATmegaPort::PORT_L) { + if (info.pinidx == 5) { + state._COM5C = TIMER5._TCCRnA._COMnC; + + TIMER5._TCCRnA._COMnC = 0; + } + if (info.pinidx == 4) { + state._COM5B = TIMER5._TCCRnA._COMnB; + + TIMER5._TCCRnA._COMnB = 0; + } + if (info.pinidx == 3) { + state._COM5A = TIMER5._TCCRnA._COMnA; + + TIMER5._TCCRnA._COMnA = 0; + } + } + + return state; +} + +inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& state) { + ATmegaPinInfo info = _ATmega_getPinInfo(pin); + + if (info.port == eATmegaPort::PORT_A) { + _XMCRA._SRE = state._SRE; + } + else if (info.port == eATmegaPort::PORT_B) { + _PCICR._PCIE0 = state._PCIE0; + + if (info.pinidx == 7) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + else if (info.pinidx == 6) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + else if (info.pinidx == 5) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + else if (info.pinidx == 4) { + _TIMER2._TCCR2A._COM2A = state._COM2A; + } + else if (info.pinidx <= 3) { + _SPCR._SPE = state._SPE; + } + } + else if (info.port == eATmegaPort::PORT_C) { + _XMCRA._SRE = state._SRE; + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 5 || info.pinidx == 3) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (info.pinidx == 5 || info.pinidx == 2) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (info.pinidx <= 3) { + _PCICR._PCIE0 = state._PCIE0; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx >= 4 && info.pinidx <= 7) { + _PCICR._PCIE0 = state._PCIE0; + } + if (info.pinidx == 5) { + TIMER3._TCCRnA._COMnC = state._COM3C; + } + if (info.pinidx == 4 || info.pinidx == 3) { + TIMER3._TCCRnA._COMnB = state._COM3B; + } + if (info.pinidx == 2 || info.pinidx == 0) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + if (info.pinidx == 2 || info.pinidx == 1) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (info.pinidx == 0) { + _PCICR._PCIE1 = state._PCIE1; + } + } + // Port F ignored. + else if (info.port == eATmegaPort::PORT_G) { + if (info.pinidx == 5) { + _TCCR0A._COM0B = state._COM0B; + } + if (info.pinidx == 4 || info.pinidx == 3) { + _ASSR._AS2 = state._AS2; + } + if (info.pinidx <= 2) { + _XMCRA._SRE = state._SRE; + } + } + else if (info.port == eATmegaPort::PORT_H) { + if (info.pinidx == 6) { + _TIMER2._TCCR2A._COM2B = state._COM2B; + } + if (info.pinidx == 5) { + TIMER4._TCCRnA._COMnC = state._COM4C; + } + if (info.pinidx == 4) { + TIMER4._TCCRnA._COMnB = state._COM4B; + } + if (info.pinidx == 3) { + TIMER4._TCCRnA._COMnA = state._COM4A; + } + if (info.pinidx == 2 || info.pinidx == 0) { + USART2._UCSRnB._RXEN = state._USART2_RXEN; + } + if (info.pinidx == 2 || info.pinidx == 1) { + USART2._UCSRnB._TXEN = state._USART2_TXEN; + } + } + else if (info.port == eATmegaPort::PORT_J) { + if (info.pinidx <= 6) { + _PCICR._PCIE1 = state._PCIE1; + } + if (info.pinidx == 2 || info.pinidx == 0) { + USART3._UCSRnB._RXEN = state._USART3_RXEN; + } + if (info.pinidx == 2 || info.pinidx == 1) { + USART3._UCSRnB._TXEN = state._USART3_TXEN; + } + } + else if (info.port == eATmegaPort::PORT_K) { + _PCICR._PCIE2 = state._PCIE2; + } + else if (info.port == eATmegaPort::PORT_L) { + if (info.pinidx == 5) { + TIMER5._TCCRnA._COMnC = state._COM5C; + } + if (info.pinidx == 4) { + TIMER5._TCCRnA._COMnB = state._COM5B; + } + if (info.pinidx == 3) { + TIMER5._TCCRnA._COMnA = state._COM5A; + } + } +} \ No newline at end of file diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 9ddb5822ab14..01757b7ed366 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -214,11 +214,13 @@ #define PAUSE_LCD_FOR_BUSY_SD #endif #else - #define LCD_PINS_D4 EXP1_05_PIN - #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) + #define LCD_PINS_D4 EXP1_05_PIN + #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) || ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN #define LCD_PINS_D7 EXP1_08_PIN + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_RS EXP1_04_PIN #endif #define BOARD_ST7920_DELAY_1 96 #define BOARD_ST7920_DELAY_2 48 From 6cf4f5a34231c91abdc7b11d18d5a23b554b55b4 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Tue, 29 Nov 2022 20:57:32 +0100 Subject: [PATCH 23/83] - added another set of AVR MCUs to the supported list for the reliability update --- Marlin/src/HAL/AVR/HAL.cpp | 2 +- Marlin/src/HAL/AVR/registers.h | 920 ++++++++++++++++++++++++++++++--- 2 files changed, 835 insertions(+), 87 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 4ff643c48ff1..cbe72abf9262 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -91,7 +91,7 @@ void MarlinHAL::init() { #if defined(BEEPER_PIN) || ENABLED(ATMEGA_NO_BEEPFIX) // Make sure no alternative is locked onto the BEEPER. // This fixes the issue where the ATmega is constantly beeping. - // Might destroy other peripherals using the pin; to circumvent that please undefine the BEEPER_PIN! + // Might destroy other peripherals using the pin; to circumvent that please undefine one of the above things! // The true culprit is the AVR ArduinoCore that enables peripherals redundantly. // (USART1 on the GeeeTech GT2560) _ATmega_savePinAlternate(BEEPER_PIN); diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 10f55dbb3d68..fa99c636a181 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -30,7 +30,29 @@ // __AVR_ATmega644P__ // __AVR_ATmega2561__ +// Contributed by Martin Turski, company owner of EirDev, on the 29th of November, 2022 +// Contact E-Mail: turningtides@outlook.de +// Created specifically for the Marlin FW for AVR backwards-compatibility. +// Please expand this file with details of every supported AVR implementation. +// 1) download the latest technical reference manual +// 2) add the new technical reference manual below using a set of __AVR_*__ preprocessor definitions and a new __AVR_TRM*__ incrementing define +// 3) check which of the existing AVR registers exist on the new implementation and enable them +// 4) add any new register definitions +// 5) add the register memory layout below the definitions +// 6) extend the _ATmega_resetperipherals functions +// 7) extend the _ATmega_savePinAlternate function +// 8) copy the extension idea to _ATmega_restorePinAlternate and finish implementing it +// You need to adjust the eATmegaPort enumeration aswell. + +#if defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega640__) // ATmega2560 technical reference manual date: 28th of November, 2022 +// ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf +#define __AVR_TRM01__ +#elif defined(__AVR_ATmega164A__) || defined(__AVR_ATmega164PA__) || defined(__AVR_ATmega324A__) || defined(__AVR_ATmega324PA__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284__) || defined(__AVT_ATmega1284P__) +// ATmega1284 technical reference manual date: 29th of November, 2022 +// ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf +#define __AVR_TRM02__ +#endif // As old as the ATmega series of CPU is, the worse the actual libraries making // use of the MCU likely are. @@ -53,6 +75,9 @@ struct _bit_reg_t { val &= ~(1<= 4) { + state._SPE = _SPCR._SPE; + + _SPCR._SPE = false; + } + + if (info.pinidx == 4) { + state._COM0A = TIMER0._TCCRnA._COMnA; + + TIMER0._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 5) { + state._COM0B = TIMER0._TCCRnA._COMnB; + + TIMER0._TCCRnA._COMnB = 0; + } + } + else if (info.port == eATmegaPort::PORT_C) { + state._AS2 = _ASSR._AS2; + state._PCIE2 = _PCICR._PCIE2; + + _ADDR._AS2 = false; + _PCICR._PCIE2 = false; + } + else if (info.port == eATmegaPort::PORT_D) { + state._PCIE3 = _PCICR._PCIE3; + + _PCICR._PCIE3 = false; + + if (info.pinidx == 7) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + + _TIMER2._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 6) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + + _TIMER2._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 5) { + state._COM1A = _TIMER1._TCCRnA._COMnA; + + _TIMER1._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 4) { + state._COM1B = _TIMER1._TCCRnB._COMnB; + + _TIMER1._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 3) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + + USART1._UCSRnB._TXEN = false; + } + else if (info.pinidx == 2 || info.pinidx == 0) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + + USART1._UCSRnB._RXEN = false; + } + else if (info.pinidx == 1) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + + USART0._UCSRnB._TXEN = false; + } + } +#endif return state; } @@ -1817,6 +2490,8 @@ inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& state) { ATmegaPinInfo info = _ATmega_getPinInfo(pin); +#if defined(__AVR_TRM01__) + // See page 75ff of ATmega2560 technical reference manual. if (info.port == eATmegaPort::PORT_A) { _XMCRA._SRE = state._SRE; } @@ -1833,7 +2508,7 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat TIMER1._TCCRnA._COMnA = state._COM1A; } else if (info.pinidx == 4) { - _TIMER2._TCCR2A._COM2A = state._COM2A; + _TIMER2._TCCRnA._COMnA = state._COM2A; } else if (info.pinidx <= 3) { _SPCR._SPE = state._SPE; @@ -1876,7 +2551,7 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat // Port F ignored. else if (info.port == eATmegaPort::PORT_G) { if (info.pinidx == 5) { - _TCCR0A._COM0B = state._COM0B; + TIMER0._TCCRnA._COMnB = state._COM0B; } if (info.pinidx == 4 || info.pinidx == 3) { _ASSR._AS2 = state._AS2; @@ -1887,7 +2562,7 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat } else if (info.port == eATmegaPort::PORT_H) { if (info.pinidx == 6) { - _TIMER2._TCCR2A._COM2B = state._COM2B; + _TIMER2._TCCRnA._COMnB = state._COM2B; } if (info.pinidx == 5) { TIMER4._TCCRnA._COMnC = state._COM4C; @@ -1930,4 +2605,77 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat TIMER5._TCCRnA._COMnA = state._COM5A; } } +#elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + _PCICR._PCIE0 = state._PCIE0; + + if (info.pinidx == 7) { + _DIDR0._ADC7D = state._ADCnD; + } + else if (info.pinidx == 6) { + _DIDR0._ADC6D = state._ADCnD; + } + else if (info.pinidx == 5) { + _DIDR0._ADC5D = state._ADCnD; + } + else if (info.pinidx == 4) { + _DIDR0._ADC4D = state._ADCnD; + } + else if (info.pinidx == 3) { + _DIDR0._ADC3D = state._ADCnD; + } + else if (info.pinidx == 2) { + _DIDR0._ADC2D = state._ADCnD; + } + else if (info.pinidx == 1) { + _DIDR0._ADC1D = state._ADCnD; + } + else if (info.pinidx == 0) { + _DIDR0._ADC0D = state._ADCnD; + } + } + else if (info.port == eATmegaPort::PORT_B) { + _PCICR._PCIE1 = state._PCIE1; + + if (info.pinidx <= 7 && info.pinidx >= 4) { + _SPCR._SPE = state._SPE; + } + + if (info.pinidx == 4) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + else if (info.pinidx == 5) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + } + else if (info.port == eATmegaPort::PORT_C) { + _ADDR._AS2 = state._AS2; + _PCICR._PCIE2 = state._PCIE2; + } + else if (info.port == eATmegaPort::PORT_D) { + _PCICR._PCIE3 = state._PCIE3; + + if (info.pinidx == 7) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + else if (info.pinidx == 6) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + else if (info.pinidx == 5) { + _TIMER1._TCCRnA._COMnA = state._COM1A; + } + else if (info.pinidx == 4) { + _TIMER1._TCCRnA._COMnB = state._COM1B; + } + else if (info.pinidx == 3) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + else if (info.pinidx == 2 || info.pinidx == 0) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + else if (info.pinidx == 1) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + } +#endif } \ No newline at end of file From 31c8e83e5d9a44810e0c010b758446b7c98c9717 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Wed, 30 Nov 2022 12:20:55 +0100 Subject: [PATCH 24/83] - added another set of supported AVR MCUs --- Marlin/src/HAL/AVR/registers.h | 719 ++++++++++++++++++++++++++++----- 1 file changed, 607 insertions(+), 112 deletions(-) diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index fa99c636a181..4c1d74db7ca3 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -44,6 +44,10 @@ // 8) copy the extension idea to _ATmega_restorePinAlternate and finish implementing it // You need to adjust the eATmegaPort enumeration aswell. +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) +#error Fatal error: __AVR_TRMn__ already defined! (n: 01|02|03|04) +#endif + #if defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega640__) // ATmega2560 technical reference manual date: 28th of November, 2022 // ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf @@ -52,6 +56,14 @@ // ATmega1284 technical reference manual date: 29th of November, 2022 // ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf #define __AVR_TRM02__ +#elif defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +// ATmega328 technical reference manual date: 29th of November, 2022 +// ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf +#define __AVR_TRM03__ +#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__) +// AT90USB1287 technical reference manual ID: 7593D–AVR–07/06 +// Preliminary. +#define __AVR_TRM04__ #endif // As old as the ATmega series of CPU is, the worse the actual libraries making @@ -59,9 +71,6 @@ // These registers as references do not take program space since they are purely references. -// Adding 0x20 to the memory location of registers is a retarded idea. -// See page 403 of ATmega2560 documentation, Note 4. - struct _bit_reg_t { uint8_t val; @@ -76,7 +85,7 @@ struct _bit_reg_t { } }; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) typedef _bit_reg_t PIN_reg_t; typedef _bit_reg_t DDR_reg_t; @@ -119,7 +128,35 @@ struct PORTG_dev_t { #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM03__) + +struct _bitC_reg_t { + uint8_t val : 7; + uint8_t reserved1 : 1; + + bool getValue(uint8_t idx) { + return ( val & (1<= 2) { + state._SPE = _SPCR._SPE; + + _SPCR._SPE = false; + } + + if (info.pinidx == 3) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + + _TIMER2._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 2) { + state._COM1B = TIMER1._TCCRnA._COMnB; + + TIMER1._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 1) { + state._COM1A = TIMER1._TCCRnA._COMnA; + + TIMER1._TCCRnA._COMnA = 0; + } + } + else if (info.port == eATmegaPort::PORT_C) { + state._PCIE1 = _PCICR._PCIE1; + + _PCICR._PCIE1 = false; + + if (info.pinidx <= 5 && info.pinidx >= 4) { + state._TWEN = _TWCR._TWEN; + + _TWCR._TWEN = false; + } + + if (info.pinidx == 5) { + state._ADCnD = _DIDR0._ADC5D; + + _DIDR0._ADC5D = false; + } + else if (info.pinidx == 4) { + state._ADCnD = _DIDR0._ADC4D; + + _DIDR0._ADC4D = false; + } + if (info.pinidx == 3) { + state._ADCnD = _DIDR0._ADC3D; + + _DIDR0._ADC3D = false; + } + if (info.pinidx == 2) { + state._ADCnD = _DIDR0._ADC2D; + + _DIDR0._ADC2D = false; + } + if (info.pinidx == 1) { + state._ADCnD = _DIDR0._ADC1D; + + _DIDR0._ADC1D = false; + } + if (info.pinidx == 0) { + state._ADCnD = _DIDR0._ADC0D; + + _DIDR0._ADC0D = false; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 2) { + state._PCIE1 = _PCICR._PCIE1; + + _PCICR._PCIE1 = false; + } + else { + state._PCIE2 = _PCICR._PCIE2; + + _PCICR._PCIE2 = false; + } + + if (info.pinidx == 6) { + state._COM0A = TIMER0._TCCRnA._COMnA; + + TIMER0._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 5) { + state._COM0B = TIMER0._TCCRnA._COMnB; + + TIMER0._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 4) { + state._UMSEL = USART0._UCSRnC._UMSEL; + + USART0._UCSRnC._UMSEL = 0; + } + else if (info.pinidx == 3) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + + _TIMER2._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 1) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + + USART0._UCSRnB._TXEN = false; + } + else if (info.pinidx == 0) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + + USART0._UCSRnB._RXEN = false; + } + } #endif return state; @@ -2649,7 +3070,7 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat } } else if (info.port == eATmegaPort::PORT_C) { - _ADDR._AS2 = state._AS2; + _ASSR._AS2 = state._AS2; _PCICR._PCIE2 = state._PCIE2; } else if (info.port == eATmegaPort::PORT_D) { @@ -2662,10 +3083,10 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat _TIMER2._TCCRnA._COMnB = state._COM2B; } else if (info.pinidx == 5) { - _TIMER1._TCCRnA._COMnA = state._COM1A; + TIMER1._TCCRnA._COMnA = state._COM1A; } else if (info.pinidx == 4) { - _TIMER1._TCCRnA._COMnB = state._COM1B; + TIMER1._TCCRnA._COMnB = state._COM1B; } else if (info.pinidx == 3) { USART1._UCSRnB._TXEN = state._USART1_TXEN; @@ -2677,5 +3098,79 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat USART0._UCSRnB._TXEN = state._USART0_TXEN; } } +#elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PCICR._PCIE0 = state._PCIE0; + + if (info.pinidx <= 7 && info.pinidx <= 6) { + _ASSR._AS2 = state._AS2; + } + else if (info.pinidx <= 5 && info.pinidx >= 2) { + _SPCR._SPE = state._SPE; + } + + if (info.pinidx == 3) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + else if (info.pinidx == 2) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + else if (info.pinidx == 1) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + } + else if (info.port == eATmegaPort::PORT_C) { + _PCICR._PCIE1 = state._PCIE1; + + if (info.pinidx <= 5 && info.pinidx >= 4) { + _TWCR._TWEN = state._TWEN; + } + + if (info.pinidx == 5) { + _DIDR0._ADC5D = state._ADCnD; + } + else if (info.pinidx == 4) { + _DIDR0._ADC4D = state._ADCnD; + } + if (info.pinidx == 3) { + _DIDR0._ADC3D = state._ADCnD; + } + if (info.pinidx == 2) { + _DIDR0._ADC2D = state._ADCnD; + } + if (info.pinidx == 1) { + _DIDR0._ADC1D = state._ADCnD; + } + if (info.pinidx == 0) { + _DIDR0._ADC0D = state._ADCnD; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 2) { + _PCICR._PCIE1 = state._PCIE1; + } + else { + _PCICR._PCIE2 = state._PCIE2; + } + + if (info.pinidx == 6) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + else if (info.pinidx == 5) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + else if (info.pinidx == 4) { + USART0._UCSRnC._UMSEL = state._UMSEL; + } + else if (info.pinidx == 3) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + else if (info.pinidx == 1) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + else if (info.pinidx == 0) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + } #endif } \ No newline at end of file From b8da4fb6a60a543a0ccd06b47aeb4675fddc346d Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Wed, 30 Nov 2022 18:38:31 +0100 Subject: [PATCH 25/83] - added another set of 8bit AVR MCUs to the reliability update compatibility list (that should cover all of the AVR devices already supported by Marlin) --- Marlin/src/HAL/AVR/registers.h | 1008 ++++++++++++++++++++++++++++---- 1 file changed, 905 insertions(+), 103 deletions(-) diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 4c1d74db7ca3..79d29857477d 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -71,6 +71,9 @@ // These registers as references do not take program space since they are purely references. +// It would be great if the old AVR definitions could be wasted in favor of these +// and code be rewritten to use the following more robust definitions. + struct _bit_reg_t { uint8_t val; @@ -85,7 +88,7 @@ struct _bit_reg_t { } }; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) typedef _bit_reg_t PIN_reg_t; typedef _bit_reg_t DDR_reg_t; @@ -156,7 +159,7 @@ struct PORTC_dev_t { #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct TIFR0_reg_t { uint8_t _TOV0 : 1; @@ -167,7 +170,7 @@ struct TIFR0_reg_t { static_assert(sizeof(TIFR0_reg_t) == 1, "invalid size of ATmega2560 TIFR0_reg_t"); struct TIFR1_reg_t { -#ifdef __AVR_TRM01__ +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _TOV1 : 1; uint8_t _OCF1A : 1; uint8_t _OCF1B : 1; @@ -196,10 +199,10 @@ static_assert(sizeof(TIFR2_reg_t) == 1, "invalid size of ATmega2560 TIFR2_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) struct TIFR3_reg_t { -#ifdef __AVR_TRM01__ +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _TOV3 : 1; uint8_t _OCF3A : 1; uint8_t _OCF3B : 1; @@ -246,7 +249,7 @@ static_assert(sizeof(TIFR5_reg_t) == 1, "invalid size of ATmega2560 TIFR5_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct PCIFR_reg_t { #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) @@ -260,16 +263,19 @@ struct PCIFR_reg_t { uint8_t _PCIF2 : 1; uint8_t _PCIF3 : 1; uint8_t reserved1 : 4; +#elif defined(__AVR_TRM04__) + uint8_t _PCIF0 : 1; + uint8_t reserved1 : 7; #endif }; static_assert(sizeof(PCIFR_reg_t) == 1, "invalid size of ATmega2560 PCIFR_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct EIFR_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _INTF0 : 1; uint8_t _INTF1 : 1; uint8_t _INTF2 : 1; @@ -292,7 +298,7 @@ struct EIFR_reg_t { static_assert(sizeof(EIFR_reg_t) == 1, "invalid size of ATmega2560 EIFR_reg_t"); struct EIMSK_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _INT0 : 1; uint8_t _INT1 : 1; uint8_t _INT2 : 1; @@ -316,7 +322,7 @@ static_assert(sizeof(EIMSK_reg_t) == 1, "invalid size of ATmega2560 EIMSK_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct EECR_reg_t { uint8_t _EERE : 1; @@ -330,7 +336,7 @@ struct EECR_reg_t { static_assert(sizeof(EECR_reg_t) == 1, "invalid size of ATmega2560 EECR_reg_t"); struct EEAR_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint16_t _EEAR : 12; uint16_t reserved1 : 4; #elif defined(__AVR_TRM03__) @@ -354,7 +360,7 @@ static_assert(sizeof(GTCCR_reg_t) == 1, "invalid size of ATmega2560 GTCCR_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct SPCR_reg_t { uint8_t _SPR : 2; @@ -377,7 +383,7 @@ static_assert(sizeof(SPSR_reg_t) == 1, "invalid size of ATmega2560 SPSR_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct ACSR_reg_t { uint8_t _ACIS : 2; @@ -392,7 +398,7 @@ static_assert(sizeof(ACSR_reg_t) == 1, "invalid size of ATmega2560 ACSR_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct SMCR_reg_t { uint8_t _SE : 1; @@ -402,7 +408,7 @@ struct SMCR_reg_t { static_assert(sizeof(SMCR_reg_t) == 1, "invalid size of ATmega2560 SMCR_reg_t"); struct MCUSR_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint8_t _PORF : 1; uint8_t _EXTRF : 1; uint8_t _BORF : 1; @@ -420,7 +426,7 @@ struct MCUSR_reg_t { static_assert(sizeof(MCUSR_reg_t) == 1, "invalid size of ATmega2560 MCUSR_reg_t"); struct MCUCR_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _IVCE : 1; uint8_t _IVSEL : 1; uint8_t reserved1 : 2; @@ -448,7 +454,7 @@ struct MCUCR_reg_t { static_assert(sizeof(MCUCR_reg_t) == 1, "invalid size of ATmega2560 MCUCR_reg_t"); struct SPMCSR_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint8_t _SPMEN : 1; uint8_t _PGERS : 1; uint8_t _PGWRT : 1; @@ -483,7 +489,7 @@ static_assert(sizeof(SPMCSR_reg_t) == 1, "invalid size of ATmega2560 SPMCSR_reg_ #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) struct RAMPZ_reg_t { uint8_t _RAMPZ : 2; @@ -503,10 +509,10 @@ static_assert(sizeof(EIND_reg_t) == 1, "invalid size of ATmega2560 EIND_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct SP_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint16_t _SP; #elif defined(__AVR_TRM03__) #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) @@ -522,7 +528,7 @@ static_assert(sizeof(SP_reg_t) == 2, "invalid size of ATmega2560 SP_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct SREG_reg_t { uint8_t _C : 1; @@ -557,7 +563,7 @@ static_assert(sizeof(CLKPR_reg_t) == 1, "invalid size of ATmega2560 CLKPR_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct PRR0_reg_t { #if defined(__AVR_TRM01__) @@ -587,13 +593,22 @@ struct PRR0_reg_t { uint8_t _PRTIM0 : 1; uint8_t _PRTIM2 : 1; uint8_t _PRTWI : 1; +#elif defined(__AVR_TRM04__) + uint8_t _PRADC : 1; + uint8_t reserved1 : 1; + uint8_t _PRSPI : 1; + uint8_t _PRTIM1 : 1; + uint8_t reserved2 : 1; + uint8_t _PRTIM0 : 1; + uint8_t _PRTIM2 : 1; + uint8_t _PRTWI : 1; #endif }; static_assert(sizeof(PRR0_reg_t) == 1, "invalid size of ATmega2560 PRR0_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) struct PRR1_reg_t { #if defined(__AVR_TRM01__) @@ -607,13 +622,19 @@ struct PRR1_reg_t { #elif defined(__AVR_TRM02__) uint8_t _PRTIM3 : 1; uint8_t reserved1 : 7; +#elif defined(__AVR_TRM04__) + uint8_t _PRUSART1 : 1; + uint8_t reserved1 : 2; + uint8_t _PRTIM3 : 1; + uint8_t reserved2 : 3; + uint8_t _PRUSB : 1; #endif }; static_assert(sizeof(PRR1_reg_t) == 1, "invalid size of ATmega2560 PRR1_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct PCICR_reg_t { #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) @@ -627,12 +648,15 @@ struct PCICR_reg_t { uint8_t _PCIE2 : 1; uint8_t _PCIE3 : 1; uint8_t reserved1 : 4; +#elif defined(__AVR_TRM04__) + uint8_t _PCIE0 : 1; + uint8_t reserved1 : 7; #endif }; static_assert(sizeof(PCICR_reg_t) == 1, "invalid size of ATmega2560 PCICR_reg_t"); struct EICRA_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _ISC0 : 2; uint8_t _ISC1 : 2; uint8_t _ISC2 : 2; @@ -652,7 +676,7 @@ static_assert(sizeof(EICRA_reg_t) == 1, "invalid size of ATmega2560 EICRA_reg_t" #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) struct EICRB_reg_t { uint8_t _ISC4 : 2; @@ -683,7 +707,7 @@ struct _bitPCMSK1_reg_t { #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct TIMSK0_reg_t { #if defined(__AVR_TRM01__) @@ -694,7 +718,7 @@ struct TIMSK0_reg_t { uint8_t reserved1 : 1; uint8_t _ICIE0 : 1; uint8_t reserved2 : 2; -#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) uint8_t _TOIE0 : 1; uint8_t _OCIE0A : 1; uint8_t _OCIE0B : 1; @@ -704,7 +728,7 @@ struct TIMSK0_reg_t { static_assert(sizeof(TIMSK0_reg_t) == 1, "invalid size of ATmega2560 TIMSK0_reg_t"); struct TIMSK1_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _TOIE1 : 1; uint8_t _OCIE1A : 1; uint8_t _OCIE1B : 1; @@ -733,10 +757,10 @@ static_assert(sizeof(TIMSK2_reg_t) == 1, "invalid size of ATmega2560 TIMSK2_reg_ #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) struct TIMSK3_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _TOIE3 : 1; uint8_t _OCIE3A : 1; uint8_t _OCIE3B : 1; @@ -783,7 +807,7 @@ static_assert(sizeof(TIMSK5_reg_t) == 1, "invalid size of ATmega2560 TIMSK5_reg_ #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) struct XMCRA_reg_t { uint8_t _SRW0 : 2; @@ -802,7 +826,7 @@ static_assert(sizeof(XMCRB_reg_t) == 1, "invalid size of ATmega2560 XMCRB_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct ADCSRA_reg_t { uint8_t _ADPS : 3; @@ -815,7 +839,7 @@ struct ADCSRA_reg_t { static_assert(sizeof(ADCSRA_reg_t) == 1, "invalid size of ATmega2560 ADCSRA_reg_t"); struct ADCSRB_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _ADTS : 3; uint8_t _MUX5 : 1; uint8_t reserved1 : 2; @@ -831,7 +855,7 @@ struct ADCSRB_reg_t { static_assert(sizeof(ADCSRB_reg_t) == 1, "invalid size of ATmega2560 ADCSRB_reg_t"); struct ADMUX_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint8_t _MUX0 : 1; uint8_t _MUX1 : 1; uint8_t _MUX2 : 1; @@ -871,10 +895,10 @@ static_assert(sizeof(DIDR2_reg_t) == 1, "invalid size of ATmega2560 DIDR2_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct DIDR0_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) uint8_t _ADC0D : 1; uint8_t _ADC1D : 1; uint8_t _ADC2D : 1; @@ -904,10 +928,10 @@ static_assert(sizeof(DIDR1_reg_t) == 1, "invalid size of ATmega2560 DIDR1_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct TCCRnA_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t _WGMn0 : 1; uint8_t _WGMn1 : 1; uint8_t _COMnC : 2; @@ -934,7 +958,7 @@ struct TCCRnB_reg_t { static_assert(sizeof(TCCRnB_reg_t) == 1, "invalid size of ATmega2560 TCCRnB_reg_t"); struct TCCRnC_reg_t { -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint8_t reserved1 : 5; uint8_t _FOCnC : 1; uint8_t _FOCnB : 1; @@ -956,11 +980,11 @@ struct TIMER_dev_t { uint16_t _ICRn; uint16_t _OCRnA; uint16_t _OCRnB; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) uint16_t _OCRnC; #endif }; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) static_assert(sizeof(TIMER_dev_t) == 14, "invalid size of ATmega2560 TIMER_dev_t"); #elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) static_assert(sizeof(TIMER_dev_t) == 12, "invalid size of ATmega1284 TIMER_dev_t"); @@ -968,7 +992,7 @@ static_assert(sizeof(TIMER_dev_t) == 12, "invalid size of ATmega1284 TIMER_dev_t #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct TCCRnA_8bit_reg_t { uint8_t _WGMn0 : 1; @@ -999,7 +1023,7 @@ static_assert(sizeof(TIMER_8bit_dev_t) == 5, "invalid size of ATmega2560 TIMER_8 #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct ASSR_reg_t { uint8_t _TCR2BUB : 1; @@ -1015,7 +1039,7 @@ static_assert(sizeof(ASSR_reg_t) == 1, "invalid size of ATmega2560 ASSR_reg_t"); #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct TWSR_reg_t { uint8_t _TWPS0 : 1; @@ -1055,7 +1079,7 @@ static_assert(sizeof(TWAMR_reg_t) == 1, "invalid size of ATmega2560 TWAMR_reg_t" #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) struct UBRRn_reg_t { uint16_t _UBRR : 12; @@ -1109,6 +1133,397 @@ static_assert(sizeof(USART_dev_t) == 7, "invalid size of ATmega2560 USART_dev_t" #endif +#if defined(__AVR_TRM04__) + +struct UHCON_reg_t { + uint8_t _SOFEN : 1; + uint8_t _RESET : 1; + uint8_t _RESUME : 1; + uint8_t reserved1 : 5; +}; +static_assert(sizeof(UHCON_reg_t) == 1, "invalid size of ATUSB90 UHCON_reg_t"); + +struct UHINT_reg_t { + uint8_t _DCONNI : 1; + uint8_t _DDISCI : 1; + uint8_t _RSTI : 1; + uint8_t _RSMEDI : 1; + uint8_t _RXRSMI : 1; + uint8_t _HSOFI : 1; + uint8_t _HWUPI : 1; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UHINT_reg_t) == 1, "invalid size of ATUSB90 UHINT_reg_t"); + +struct UHIEN_reg_t { + uint8_t _SUSPE : 1; + uint8_t _MSOFE : 1; + uint8_t _SOFE : 1; + uint8_t _EORSTE : 1; + uint8_t _WAKEUPE : 1; + uint8_t _EORSME : 1; + uint8_t _UPRSME : 1; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UHIEN_reg_t) == 1, "invalid size of ATUSB90 UHIEN_reg_t"); + +struct UHADDR_reg_t { + uint8_t _HADD : 7; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UHADDR_reg_t) == 1, "invalid size of ATUSB90 UHADDR_reg_t"); + +struct UHFNUM_reg_t { + uint16_t _FNUM : 11; + uint16_t reserved1 : 5; +}; +static_assert(sizeof(UHFNUM_reg_t) == 2, "invalid size of ATUSB90 UHFNUM_reg_t"); + +struct UPINTX_reg_t { + uint8_t _RXINI : 1; + uint8_t _RXSTALLI : 1; + uint8_t _TXOUTI : 1; + uint8_t _TXSTPI : 1; + uint8_t _PERRI : 1; + uint8_t _RWAL : 1; + uint8_t _NAKEDI : 1; + uint8_t _FIFOCON : 1; +}; +static_assert(sizeof(UPINTX_reg_t) == 1, "invalid size of ATUSB90 UPINTX_reg_t"); + +struct UPNUM_reg_t { + uint8_t _PNUM : 3; + uint8_t reserved1 : 5; +}; +static_assert(sizeof(UPNUM_reg_t) == 1, "invalid size of ATUSB90 UPNUM_reg_t"); + +struct UPRST_reg_t { + uint8_t _PRST : 7; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UPRST_reg_t) == 1, "invalid size of ATUSB90 UPRST_reg_t"); + +struct UPCONX_reg_t { + uint8_t _PEN : 1; + uint8_t reserved1 : 2; + uint8_t _RSTDT : 1; + uint8_t _AUTOSW : 1; + uint8_t _INMODE : 1; + uint8_t _PFREEZE : 1; + uint8_t reserved2 : 1; +}; +static_assert(sizeof(UPCONX_reg_t) == 1, "invalid size of ATUSB90 UPCONX_reg_t"); + +struct UPCFG0X_reg_t { + uint8_t _PEPNUM : 4; + uint8_t _PTOKEN : 2; + uint8_t _PTYPE : 2; +}; +static_assert(sizeof(UPCFG0X_reg_t) == 1, "invalid size of ATUSB90 UPCFG0_reg_t"); + +struct UPCFG1X_reg_t { + uint8_t reserved1 : 1; + uint8_t _ALLOC : 1; + uint8_t _PBK : 2; + uint8_t _PSIZE : 3; + uint8_t reserved2 : 1; +}; +static_assert(sizeof(UPCFG1X_reg_t) == 1, "invalid size of ATUSB90 UPCFG1X_reg_t"); + +struct UPSTAX_reg_t { + uint8_t _NBUSYBK : 2; + uint8_t _DTSEQ : 2; + uint8_t reserved1 : 1; + uint8_t _UNDERFI : 1; + uint8_t _OVERFI : 1; + uint8_t _CFGOK : 1; +}; +static_assert(sizeof(UPSTAX_reg_t) == 1, "invalid size of ATUSB90 UPSTAX_reg_t"); + +struct UPIENX_reg_t { + uint8_t _RXINE : 1; + uint8_t _RXSTALLE : 1; + uint8_t _TXOUTE : 1; + uint8_t _TXSTPE : 1; + uint8_t _PERRE : 1; + uint8_t reserved1 : 1; + uint8_t _NAKEDE : 1; + uint8_t _FLERRE : 1; +}; +static_assert(sizeof(UPIENX_reg_t) == 1, "invalid size of ATUSB90 UPIENX_reg_t"); + +struct UHWCON_reg_t { + uint8_t _UVREGE : 1; + uint8_t reserved1 : 3; + uint8_t _UVCONE : 1; + uint8_t reserved2 : 1; + uint8_t _UIDE : 1; + uint8_t _UIMOD : 1; +}; +static_assert(sizeof(UHWCON_reg_t) == 1, "invalid size of ATUSB90 UHWCON_reg_t"); + +struct USBCON_reg_t { + uint8_t _VBUSTE : 1; + uint8_t _IDTE : 1; + uint8_t reserved1 : 2; + uint8_t _OTGPADE : 1; + uint8_t _FRZCLK : 1; + uint8_t _HOST : 1; + uint8_t _USBE : 1; +}; +static_assert(sizeof(USBCON_reg_t) == 1, "invalid size of ATUSB90 USBCON_reg_t"); + +struct USBSTA_reg_t { + uint8_t _VBUS : 1; + uint8_t _ID : 1; + uint8_t reserved1 : 1; + uint8_t _SPEED : 1; + uint8_t reserved2 : 4; +}; +static_assert(sizeof(USBSTA_reg_t) == 1, "invalid size of ATUSB90 USBSTA_reg_t"); + +struct USBINT_reg_t { + uint8_t _VBUSTI : 1; + uint8_t _IDTI : 1; + uint8_t reserved1 : 6; +}; +static_assert(sizeof(USBINT_reg_t) == 1, "invalid size of ATUSB90 USBINT_reg_t"); + +struct UDPADD_reg_t { + uint16_t _DPADD : 11; + uint16_t reserved1 : 4; + uint16_t _DPACC : 1; +}; +static_assert(sizeof(UDPADD_reg_t) == 2, "invalid size of ATUSB90 UDPADD_reg_t"); + +struct OTGCON_reg_t { + uint8_t _VBUSRQC : 1; + uint8_t _VBUSREQ : 1; + uint8_t _VBUSHWC : 1; + uint8_t _SRPSEL : 1; + uint8_t _SRPREQ : 1; + uint8_t _HNPREQ : 1; + uint8_t reserved1 : 1; + uint8_t _zero : 1; +}; +static_assert(sizeof(OTGCON_reg_t) == 1, "invalid size of ATUSB90 OTGCON_reg_t"); + +struct OTGIEN_reg_t { + uint8_t _SRPE : 1; + uint8_t _VBERRE : 1; + uint8_t _BCERRE : 1; + uint8_t _ROLEEXE : 1; + uint8_t _HNPERRE : 1; + uint8_t _STOE : 1; + uint8_t reserved1 : 2; +}; +static_assert(sizeof(OTGIEN_reg_t) == 1, "invalid size of ATUSB90 OTGIEN_reg_t"); + +struct OTGINT_reg_t { + uint8_t _SRPI : 1; + uint8_t _VBERRI : 1; + uint8_t _BCERRI : 1; + uint8_t _ROLEEXI : 1; + uint8_t _HNPERRI : 1; + uint8_t _STOI : 1; + uint8_t reserved1 : 2; +}; +static_assert(sizeof(OTGINT_reg_t) == 1, "invalid size of ATUSB90 OTGINT_reg_t"); + +struct UDCON_reg_t { + uint8_t _DETACH : 1; + uint8_t _RMWKUP : 1; + uint8_t _LSM : 1; + uint8_t reserved1 : 5; +}; +static_assert(sizeof(UDCON_reg_t) == 1, "invalid size of ATUSB90 UDCON_reg_t"); + +struct UDINT_reg_t { + uint8_t _SUSPI : 1; + uint8_t _MSOFI : 1; + uint8_t _SOFI : 1; + uint8_t _EORSTI : 1; + uint8_t _WAKEUPI : 1; + uint8_t _EORSMI : 1; + uint8_t _UPRSMI : 1; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UDINT_reg_t) == 1, "invalid size of ATUSB90 UDINT_reg_t"); + +struct UDIEN_reg_t { + uint8_t _SUSPE : 1; + uint8_t _MSOFE : 1; + uint8_t _SOFE : 1; + uint8_t _EORSTE : 1; + uint8_t _WAKEUPE : 1; + uint8_t _EORSME : 1; + uint8_t _UPRSME : 1; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UDIEN_reg_t) == 1, "invalid size of ATUSB90 UDIEN_reg_t"); + +struct UDADDR_reg_t { + uint8_t _UADD : 7; + uint8_t _ADDEN : 1; +}; +static_assert(sizeof(UDADDR_reg_t) == 1, "invalid size of ATUSB90 UADDR_reg_t"); + +struct UDFNUM_reg_t { + uint16_t _FNUM : 11; + uint16_t reserved1 : 5; +}; +static_assert(sizeof(UDFNUM_reg_t) == 2, "invalid size of ATUSB90 UDFNUM_reg_t"); + +struct UDMFN_reg_t { + uint8_t reserved1 : 4; + uint8_t _FNCERR : 1; + uint8_t reserved2 : 3; +}; +static_assert(sizeof(UDMFN_reg_t) == 1, "invalid size of ATUSB90 UDMFN_reg_t"); + +struct UDTST_reg_t { + uint8_t reserved1 : 2; + uint8_t _TSTJ : 1; + uint8_t _TSTK : 1; + uint8_t _TSTPCKT : 1; + uint8_t _OPMODE2 : 1; + uint8_t reserved2 : 2; +}; +static_assert(sizeof(UDTST_reg_t) == 1, "invalid size of ATUSB90 UDTST_reg_t"); + +struct UEINTX_reg_t { + uint8_t _TXINI : 1; + uint8_t _STALLEDI : 1; + uint8_t _RXOUTI : 1; + uint8_t _RXSTPI : 1; + uint8_t _NAKOUTI : 1; + uint8_t _RWAL : 1; + uint8_t _NAKINI : 1; + uint8_t _FIFOCON : 1; +}; +static_assert(sizeof(UEINTX_reg_t) == 1, "invalid size of ATUSB90 UEINTX_reg_t"); + +struct UENUM_reg_t { + uint8_t _EPNUM : 3; + uint8_t reserved1 : 5; +}; +static_assert(sizeof(UENUM_reg_t) == 1, "invalid size of ATUSB90 UENUM_reg_t"); + +struct UERST_reg_t { + uint8_t _EPRST : 7; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UERST_reg_t) == 1, "invalid size of ATUSB90 UERST_reg_t"); + +struct UECONX_reg_t { + uint8_t _EPEN : 1; + uint8_t reserved1 : 2; + uint8_t _RSTDT : 1; + uint8_t _STALLRQC : 1; + uint8_t _STALLRQ : 1; + uint8_t reserved2 : 2; +}; +static_assert(sizeof(UECONX_reg_t) == 1, "invalid size of ATUSB90 UECONX_reg_t"); + +struct UECFG0X_reg_t { + uint8_t _EPDIR : 1; + uint8_t _NYETSDIS : 1; + uint8_t _AUTOSW : 1; + uint8_t _ISOSW : 1; + uint8_t reserved1 : 2; + uint8_t _EPTYPE : 2; +}; +static_assert(sizeof(UECFG0X_reg_t) == 1, "invalid size of ATUSB90 UECFG0X_reg_t"); + +struct UECFG1X_reg_t { + uint8_t reserved1 : 1; + uint8_t _ALLOC : 1; + uint8_t _EPBK : 2; + uint8_t _EPSIZE : 3; + uint8_t reserved2 : 1; +}; +static_assert(sizeof(UECFG1X_reg_t) == 1, "invalid size of ATUSB90 UECFG1X_reg_t"); + +struct UESTA0X_reg_t { + uint8_t _NBUSYBK : 2; + uint8_t _DTSEQ : 2; + uint8_t _ZLPSEEN : 1; + uint8_t _UNDERFI : 1; + uint8_t _OVERFI : 1; + uint8_t _CFGOK : 1; +}; +static_assert(sizeof(UESTA0X_reg_t) == 1, "invalid size of ATUSB90 UESTA0X_reg_t"); + +struct UESTA1X_reg_t { + uint8_t _CURRBK : 2; + uint8_t _CTRLDIR : 1; + uint8_t reserved1 : 5; +}; +static_assert(sizeof(UESTA1X_reg_t) == 1, "invalid size of ATUSB90 UESTA1X_reg_t"); + +struct UEIENX_reg_t { + uint8_t _TXINE : 1; + uint8_t _STALLEDE : 1; + uint8_t _RXOUTE : 1; + uint8_t _RXSTPE : 1; + uint8_t _NAKOUTE : 1; + uint8_t reserved1 : 1; + uint8_t _NAKINE : 1; + uint8_t _FLERRE : 1; +}; +static_assert(sizeof(UEIENX_reg_t) == 1, "invalid size of ATUSB90 UEIENX_reg_t"); + +struct UEBCX_reg_t { + uint16_t _BYCT : 11; + uint16_t reserved1 : 5; +}; +static_assert(sizeof(UEBCX_reg_t) == 2, "invalid size of ATUSB90 UEBCX_reg_t"); + +struct UEINT_reg_t { + uint8_t _EPINT : 7; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UEINT_reg_t) == 1, "invalid size of ATUSB90 UEINT_reg_t"); + +struct UPERRX_reg_t { + uint8_t _DATATGL : 1; + uint8_t _DATAPID : 1; + uint8_t _PID : 1; + uint8_t _TIMEOUT : 1; + uint8_t _CRC16 : 1; + uint8_t _COUNTER : 2; + uint8_t reserved1 : 1; +}; +static_assert(sizeof(UPERRX_reg_t) == 1, "invalid size of ATUSB90 UPERRX_reg_t"); + +struct UPBCX_reg_t { + uint16_t _PBYCT : 11; + uint16_t reserved1 : 5; +}; +static_assert(sizeof(UPBCX_reg_t) == 2, "invalid size of ATUSB90 UPBCX_reg_t"); + +struct OTGTCON_reg_t { + uint8_t _VALUE : 2; + uint8_t reserved1 : 3; + uint8_t _PAGE : 2; + uint8_t _one : 1; +}; +static_assert(sizeof(OTGTCON_reg_t) == 1, "invalid size of ATUSB90 OTGTCON_reg_t"); + +struct PLLCSR_reg_t { + uint8_t _PLOCK : 1; + uint8_t _PLLE : 1; + uint8_t _PLLP : 3; + uint8_t reserved1 : 3; +}; +static_assert(sizeof(PLLCSR_reg_t) == 1, "invalid size of ATUSB90 PLLCSR_reg_t"); + +#endif + +/* + REGISTER MEMORY MAP +*/ + #if defined(__AVR_TRM01__) // page 399ff of ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf static PORT_dev_t& _PORTA = *(PORT_dev_t*)0x20; @@ -1316,6 +1731,123 @@ static uint8_t& _TWDR = *(uint8_t*)0xBB; static TWCR_reg_t& _TWCR = *(TWCR_reg_t*)0xBC; static TWAMR_reg_t& _TWAMR = *(TWAMR_reg_t*)0xBD; static USART_dev_t& USART0 = *(USART_dev_t*)0xC0; + +#elif defined(__AVR_TRM04__) +static PORT_dev_t& _PORTA = *(PORT_dev_t*)0x20; +static PORT_dev_t& _PORTB = *(PORT_dev_t*)0x23; +static PORT_dev_t& _PORTC = *(PORT_dev_t*)0x26; +static PORT_dev_t& _PORTD = *(PORT_dev_t*)0x29; +static PORT_dev_t& _PORTE = *(PORT_dev_t*)0x2C; +static PORT_dev_t& _PORTF = *(PORT_dev_t*)0x2F; +static TIFR0_reg_t& _TIFR0 = *(TIFR0_reg_t*)0x35; +static TIFR1_reg_t& _TIFR1 = *(TIFR1_reg_t*)0x36; +static TIFR2_reg_t& _TIFR2 = *(TIFR2_reg_t*)0x37; +static TIFR3_reg_t& _TIFR3 = *(TIFR3_reg_t*)0x38; +static PCIFR_reg_t& _PCIFR = *(PCIFR_reg_t*)0x3B; +static EIFR_reg_t& _EIFR = *(EIFR_reg_t*)0x3C; +static EIMSK_reg_t& _EIMSK = *(EIMSK_reg_t*)0x3D; +static _bit_reg_t& _GPIOR0 = *(_bit_reg_t*)0x3E; +static EECR_reg_t& _EECR = *(EECR_reg_t*)0x3F; +static uint8_t& _EEDR = *(uint8_t*)0x40; +static EEAR_reg_t& _EEAR = *(EEAR_reg_t*)0x41; +static GTCCR_reg_t& _GTCCR = *(GTCCR_reg_t*)0x43; +static TIMER_8bit_dev_t& TIMER0 = *(TIMER_8bit_dev_t*)0x44; +static PLLCSR_reg_t& _PLLCSR = *(PLLCSR_reg_t*)0x49; +static _bit_reg_t& _GPIOR1 = *(_bit_reg_t*)0x4A; +static _bit_reg_t& _GPIOR2 = *(_bit_reg_t*)0x4B; +static SPCR_reg_t& _SPCR = *(SPCR_reg_t*)0x4C; +static SPSR_reg_t& _SPSR = *(SPSR_reg_t*)0x4D; +static uint8_t& _SPDR = *(uint8_t*)0x4E; +static ACSR_reg_t& _ACSR = *(ACSR_reg_t*)0x50; +static uint8_t& _OCDR = *(uint8_t*)0x51; +static SMCR_reg_t& _SMCR = *(SMCR_reg_t*)0x53; +static MCUSR_reg_t& _MCUSR = *(MCUSR_reg_t*)0x54; +static MCUCR_reg_t& _MCUCR = *(MCUCR_reg_t*)0x55; +static SPMCSR_reg_t& _SPMCSR = *(SPMCSR_reg_t*)0x57; +static RAMPZ_reg_t& _RAMPZ = *(RAMPZ_reg_t*)0x5B; +static SP_reg_t& _SP = *(SP_reg_t*)0x5D; +static SREG_reg_t& _SREG = *(SREG_reg_t*)0x5F; +static WDTCSR_reg_t& _WDTCSR = *(WDTCSR_reg_t*)0x60; +static CLKPR_reg_t& _CLKPR = *(CLKPR_reg_t*)0x61; +static PRR0_reg_t& _PRR0 = *(PRR0_reg_t*)0x64; +static PRR1_reg_t& _PRR1 = *(PRR1_reg_t*)0x65; +static uint8_t& _OSCCAL = *(uint8_t*)0x66; +static PCICR_reg_t& _PCICR = *(PCICR_reg_t*)0x68; +static EICRA_reg_t& _EICRA = *(EICRA_reg_t*)0x69; +static EICRB_reg_t& _EICRB = *(EICRB_reg_t*)0x6A; +static _bit_reg_t& _PCMSK0 = *(_bit_reg_t*)0x6B; +static TIMSK0_reg_t& _TIMSK0 = *(TIMSK0_reg_t*)0x6E; +static TIMSK1_reg_t& _TIMSK1 = *(TIMSK1_reg_t*)0x6F; +static TIMSK2_reg_t& _TIMSK2 = *(TIMSK2_reg_t*)0x70; +static TIMSK3_reg_t& _TIMSK3 = *(TIMSK3_reg_t*)0x71; +static XMCRA_reg_t& _XMCRA = *(XMCRA_reg_t*)0x74; +static XMCRB_reg_t& _XMCRB = *(XMCRB_reg_t*)0x75; +static uint16_t& _ADC = *(uint16_t*)0x78; +static ADCSRA_reg_t& _ADCSRA = *(ADCSRA_reg_t*)0x7A; +static ADCSRB_reg_t& _ADCSRB = *(ADCSRB_reg_t*)0x7B; +static ADMUX_reg_t& _ADMUX = *(ADMUX_reg_t*)0x7C; +static DIDR0_reg_t& _DIDR0 = *(DIDR0_reg_t*)0x7E; +static DIDR1_reg_t& _DIDR1 = *(DIDR1_reg_t*)0x7F; +static TIMER_dev_t& TIMER1 = *(TIMER_dev_t*)0x80; +static TIMER_dev_t& TIMER3 = *(TIMER_dev_t*)0x90; +static UHCON_reg_t& _UHCON = *(UHCON_reg_t*)0x9E; +static UHINT_reg_t& _UHINT = *(UHINT_reg_t*)0x9F; +static UHIEN_reg_t& _UHIEN = *(UHIEN_reg_t*)0xA0; +static UHADDR_reg_t& _UHADDR = *(UHADDR_reg_t*)0xA1; +static UHFNUM_reg_t& _UHFNUM = *(UHFNUM_reg_t*)0xA2; +static uint8_t& _UHFLEN = *(uint8_t*)0xA4; +static uint8_t& _UPINRQX = *(uint8_t*)0xA5; +static UPINTX_reg_t& _UPINTX = *(UPINTX_reg_t*)0xA6; +static UPNUM_reg_t& _UPNUM = *(UPNUM_reg_t*)0xA7; +static UPRST_reg_t& _UPRST = *(UPRST_reg_t*)0xA8; +static UPCONX_reg_t& _UPCONX = *(UPCONX_reg_t*)0xA9; +#define _AVR_DEFREG(n,a) static n##_reg_t& _##n = *(n##_reg_t*)a +_AVR_DEFREG(UPCFG0X, 0xAA); +_AVR_DEFREG(UPCFG1X, 0xAB); +_AVR_DEFREG(UPSTAX, 0xAC); +static uint8_t& _UPCFG2X = *(uint8_t*)0xAD; +_AVR_DEFREG(UPIENX, 0xAE); +static uint8_t& _UPDATX = *(uint8_t*)0xAF; +static TIMER_8bit_dev_t& _TIMER2 = *(TIMER_8bit_dev_t*)0xB0; +static ASSR_reg_t& _ASSR = *(ASSR_reg_t*)0xB6; +static uint8_t& _TWBR = *(uint8_t*)0xB8; +static TWSR_reg_t& _TWSR = *(TWSR_reg_t*)0xB9; +static TWAR_reg_t& _TWAR = *(TWAR_reg_t*)0xBA; +static uint8_t& _TWDR = *(uint8_t*)0xBB; +static TWCR_reg_t& _TWCR = *(TWCR_reg_t*)0xBC; +static TWAMR_reg_t& _TWAMR = *(TWAMR_reg_t*)0xBD; +static USART_dev_t& USART1 = *(USART_dev_t*)0xC8; +_AVR_DEFREG(UHWCON, 0xD7); +_AVR_DEFREG(USBCON, 0xD8); +_AVR_DEFREG(USBSTA, 0xD9); +_AVR_DEFREG(USBINT, 0xDA); +_AVR_DEFREG(UDPADD, 0xDB); +_AVR_DEFREG(OTGCON, 0xDD); +_AVR_DEFREG(OTGIEN, 0xDE); +_AVR_DEFREG(OTGINT, 0xDF); +_AVR_DEFREG(UDCON, 0xE0); +_AVR_DEFREG(UDINT, 0xE1); +_AVR_DEFREG(UDIEN, 0xE2); +_AVR_DEFREG(UDADDR, 0xE3); +_AVR_DEFREG(UDFNUM, 0xE4); +_AVR_DEFREG(UDMFN, 0xE6); +_AVR_DEFREG(UDTST, 0xE7); +_AVR_DEFREG(UEINTX, 0xE8); +_AVR_DEFREG(UENUM, 0xE9); +_AVR_DEFREG(UERST, 0xEA); +_AVR_DEFREG(UECONX, 0xEB); +_AVR_DEFREG(UECFG0X, 0xEC); +_AVR_DEFREG(UECFG1X, 0xED); +_AVR_DEFREG(UESTA0X, 0xEE); +_AVR_DEFREG(UESTA1X, 0xEF); +_AVR_DEFREG(UEIENX, 0xF0); +static uint8_t& _UEDATX = *(uint8_t*)0xF1; +_AVR_DEFREG(UEBCX, 0xF2); +_AVR_DEFREG(UEINT, 0xF4); +_AVR_DEFREG(UPERRX, 0xF5); +_AVR_DEFREG(UPBCX, 0xF6); +static uint8_t& _UPINT = *(uint8_t*)0xF8; +_AVR_DEFREG(OTGTCON, 0xF9); #endif /* @@ -1326,7 +1858,7 @@ inline void _ATmega_resetperipherals() { // Due to BOOTLOADER or other board inconsistencies we could get launched into Marlin FW // with configuration that does not match the reset state in the documentation. That is why // we should clean-reset the entire device. -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) SREG_reg_t __SREG; __SREG._C = false; __SREG._Z = false; @@ -1339,8 +1871,10 @@ inline void _ATmega_resetperipherals() { _SREG = __SREG; #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) _RAMPZ._RAMPZ = 0; +#endif +#if defined(__AVR_TRM01__) _EIND._EIND0 = false; #endif @@ -1349,7 +1883,7 @@ inline void _ATmega_resetperipherals() { _EEDR = 0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) EECR_reg_t __EECR; __EECR._EERE = false; __EECR._EEPE = false; @@ -1361,13 +1895,13 @@ inline void _ATmega_resetperipherals() { _EECR = __EECR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) _GPIOR2.val = 0; _GPIOR1.val = 0; _GPIOR0.val = 0; #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) XMCRA_reg_t __XMCRA; __XMCRA._SRW0 = 0; __XMCRA._SRW1 = 0; @@ -1382,7 +1916,7 @@ inline void _ATmega_resetperipherals() { _XMCRB = __XMCRB; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) SMCR_reg_t __SMCR; __SMCR._SE = false; __SMCR._SM = 0; @@ -1390,7 +1924,7 @@ inline void _ATmega_resetperipherals() { _SMCR = __SMCR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) PRR0_reg_t __PRR0; #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) __PRR0._PRADC = false; @@ -1410,11 +1944,20 @@ inline void _ATmega_resetperipherals() { __PRR0._PRTIM0 = false; __PRR0._PRTIM2 = false; __PRR0._PRTWI = false; +#elif defined(__AVR_TRM04__) + __PRR0._PRADC = false; + __PRR0.reserved1 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0.reserved2 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; #endif _PRR0 = __PRR0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) PRR1_reg_t __PRR1; #if defined(__AVR_TRM01__) __PRR1._PRUSART1 = false; @@ -1427,11 +1970,14 @@ inline void _ATmega_resetperipherals() { #elif defined(__AVR_TRM02__) __PRR1._PRTIM3 = false; __PRR1.reserved1 = 0; +#elif defined(__AVR_TRM04__) + __PRR1._PRUSART1 = false; + __PRR1.reserved1 = 0; #endif _PRR1 = __PRR1; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) WDTCSR_reg_t __WDTCSR; __WDTCSR._WDP0 = 0; __WDTCSR._WDP1 = 0; @@ -1444,26 +1990,26 @@ inline void _ATmega_resetperipherals() { _WDTCSR = __WDTCSR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) _MCUCR._PUD = false; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) PORT_dev_t __PORT; __PORT._PIN.val = 0; __PORT._DDR.val = 0; __PORT._PORT.val = 0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) _PORTA = __PORT; _PORTC = __PORT; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) _PORTB = __PORT; _PORTD = __PORT; #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) _PORTE = __PORT; _PORTF = __PORT; #endif @@ -1497,9 +2043,9 @@ inline void _ATmega_resetperipherals() { _PORTL = __PORT; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) EICRA_reg_t __EICRA; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __EICRA._ISC0 = 0; __EICRA._ISC1 = 0; __EICRA._ISC2 = 0; @@ -1517,7 +2063,7 @@ inline void _ATmega_resetperipherals() { _EICRA = __EICRA; #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) EICRB_reg_t __EICRB; __EICRB._ISC4 = 0; __EICRB._ISC5 = 0; @@ -1526,9 +2072,9 @@ inline void _ATmega_resetperipherals() { _EICRB = __EICRB; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) EIMSK_reg_t __EIMSK; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __EIMSK._INT0 = false; __EIMSK._INT1 = false; __EIMSK._INT2 = false; @@ -1550,9 +2096,9 @@ inline void _ATmega_resetperipherals() { _EIMSK = __EIMSK; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) EIFR_reg_t __EIFR; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __EIFR._INTF0 = false; __EIFR._INTF1 = false; __EIFR._INTF2 = false; @@ -1574,7 +2120,7 @@ inline void _ATmega_resetperipherals() { _EIFR = __EIFR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) PCICR_reg_t __PCICR; #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) __PCICR._PCIE0 = false; @@ -1587,11 +2133,14 @@ inline void _ATmega_resetperipherals() { __PCICR._PCIE2 = false; __PCICR._PCIE3 = false; __PCICR.reserved1 = 0; +#elif defined(__AVR_TRM04__) + __PCICR._PCIE0 = false; + __PCICR.reserved1 = 0; #endif _PCICR = __PCICR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) PCIFR_reg_t __PCIFR; #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) __PCIFR._PCIF0 = false; @@ -1604,14 +2153,19 @@ inline void _ATmega_resetperipherals() { __PCIFR._PCIF2 = false; __PCIFR._PCIF3 = false; __PCIFR.reserved1 = 0; +#elif defined(__AVR_TRM04__) + __PCIFR._PCIF0 = false; + __PCIFR.reserved1 = 0; #endif _PCIFR = __PCIFR; #endif +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + _PCMSK0.val = 0; +#endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - _PCMSK2.val = 0; _PCMSK1.val = 0; - _PCMSK0.val = 0; + _PCMSK2.val = 0; #endif #if defined(__AVR_TRM02__) _PCMSK3.val = 0; @@ -1620,7 +2174,7 @@ inline void _ATmega_resetperipherals() { _PCMSK1.reserved1 = 0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIMER_8bit_dev_t __TIMER_8bit; __TIMER_8bit._TCCRnA._WGMn0 = 0; __TIMER_8bit._TCCRnA._WGMn1 = 0; @@ -1638,7 +2192,7 @@ inline void _ATmega_resetperipherals() { TIMER0 = __TIMER_8bit; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIMSK0_reg_t __TIMSK0; __TIMSK0._TOIE0 = false; __TIMSK0._OCIE0A = false; @@ -1654,11 +2208,11 @@ inline void _ATmega_resetperipherals() { _TIFR0 = __TIFR0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIMER_dev_t TIMER; TIMER._TCCRnA._WGMn0 = 0; TIMER._TCCRnA._WGMn1 = 0; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) TIMER._TCCRnA._COMnC = 0; #endif TIMER._TCCRnA._COMnB = 0; @@ -1669,7 +2223,7 @@ inline void _ATmega_resetperipherals() { TIMER._TCCRnB._ICESn = 0; TIMER._TCCRnB._ICNCn = 0; TIMER._TCCRnC.reserved1 = 0; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) TIMER._TCCRnC._FOCnC = false; #endif TIMER._TCCRnC._FOCnB = false; @@ -1677,13 +2231,13 @@ inline void _ATmega_resetperipherals() { TIMER._TCNTn = 0; TIMER._OCRnA = 0; TIMER._OCRnB = 0; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) TIMER._OCRnC = 0; #endif TIMER._ICRn = 0; TIMER1 = TIMER; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) TIMER3 = TIMER; #endif #if defined(__AVR_TRM01__) @@ -1691,12 +2245,12 @@ inline void _ATmega_resetperipherals() { TIMER5 = TIMER; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIMSK1_reg_t __TIMSK1; __TIMSK1._TOIE1 = false; __TIMSK1._OCIE1A = false; __TIMSK1._OCIE1B = false; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __TIMSK1._OCIE1C = false; #endif __TIMSK1.reserved1 = 0; @@ -1705,12 +2259,12 @@ inline void _ATmega_resetperipherals() { _TIMSK1 = __TIMSK1; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) TIMSK3_reg_t __TIMSK3; __TIMSK3._TOIE3 = false; __TIMSK3._OCIE3A = false; __TIMSK3._OCIE3B = false; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __TIMSK3._OCIE3C = false; #endif __TIMSK3.reserved1 = 0; @@ -1741,12 +2295,12 @@ inline void _ATmega_resetperipherals() { _TIMSK5 = __TIMSK5; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIFR1_reg_t __TIFR1; __TIFR1._TOV1 = false; __TIFR1._OCF1A = false; __TIFR1._OCF1B = false; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __TIFR1._OCF1C = false; #endif __TIFR1.reserved1 = 0; @@ -1755,12 +2309,12 @@ inline void _ATmega_resetperipherals() { _TIFR1 = __TIFR1; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) TIFR3_reg_t __TIFR3; __TIFR3._TOV3 = false; __TIFR3._OCF3A = false; __TIFR3._OCF3B = false; -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) __TIFR3._OCF3C = false; #endif __TIFR3.reserved1 = 0; @@ -1791,11 +2345,11 @@ inline void _ATmega_resetperipherals() { _TIFR5 = __TIFR5; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) _TIMER2 = __TIMER_8bit; #endif -#if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) ASSR_reg_t __ASSR; __ASSR._TCR2BUB = false; __ASSR._TCR2AUB = false; @@ -1808,7 +2362,7 @@ inline void _ATmega_resetperipherals() { _ASSR = __ASSR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) TIMSK2_reg_t __TIMSK2; __TIMSK2._TOIE2 = false; __TIMSK2._OCIE2A = false; @@ -1824,7 +2378,7 @@ inline void _ATmega_resetperipherals() { _TIFR2 = __TIFR2; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) SPCR_reg_t __SPCR; __SPCR._SPR = 0; __SPCR._CPHA = 0; @@ -1843,7 +2397,7 @@ inline void _ATmega_resetperipherals() { _SPSR = __SPSR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) USART_dev_t USART; USART._UDRn = 0; USART._UCSRnA._MPCM = false; @@ -1871,9 +2425,11 @@ inline void _ATmega_resetperipherals() { USART._UCSRnC._UMSEL = 0; USART._UBRRn._UBRR = 0; USART._UBRRn.reserved1 = 0; +#endif +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) USART0 = USART; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) USART1 = USART; #endif #if defined(__AVR_TRM01__) @@ -1881,7 +2437,7 @@ inline void _ATmega_resetperipherals() { USART3 = USART; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) _TWBR = 0; TWCR_reg_t __TWCR; @@ -1919,7 +2475,7 @@ inline void _ATmega_resetperipherals() { _TWAMR = __TWAMR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) ADCSRB_reg_t __ADCSRB; __ADCSRB._ADTS = 0; #if defined(__AVR_TRM01__) @@ -1941,7 +2497,7 @@ inline void _ATmega_resetperipherals() { _ACSR = __ACSR; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) DIDR1_reg_t __DIDR1; __DIDR1._AIN0D = false; __DIDR1._AIN1D = false; @@ -1949,13 +2505,13 @@ inline void _ATmega_resetperipherals() { _DIDR1 = __DIDR1; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) ADMUX_reg_t __ADMUX; __ADMUX._MUX0 = 0; __ADMUX._MUX1 = 0; __ADMUX._MUX2 = 0; __ADMUX._MUX3 = 0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) __ADMUX._MUX4 = 0; #elif defined(__AVR_TRM03__) __ADMUX.reserved1 = 0; @@ -1977,9 +2533,9 @@ inline void _ATmega_resetperipherals() { _ADC = 0; #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) SPMCSR_reg_t __SPMCSR; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) __SPMCSR._SPMEN = false; __SPMCSR._PGERS = false; __SPMCSR._PGWRT = false; @@ -2011,6 +2567,8 @@ inline void _ATmega_resetperipherals() { #endif _SPMCSR = __SPMCSR; #endif + + // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) } struct pin_dev_state_t { @@ -2080,6 +2638,23 @@ struct pin_dev_state_t { uint8_t _UMSEL : 2; uint8_t _USART0_TXEN : 1; uint8_t _USART0_RXEN : 1; +#elif defined(__AVR_TRM04__) + uint8_t _SRE : 1; + uint8_t _SPE : 1; + uint8_t _COM0B : 2; + uint8_t _COM1C : 2; + uint8_t _COM1B : 2; + uint8_t _COM1A : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _PCIE0 : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _TWEN : 1; + uint8_t _INTn : 1; + uint8_t _UVCONE : 1; + uint8_t _UIDE : 1; + //uint8_t _JTAGEN : 1; #endif }; @@ -2092,6 +2667,8 @@ enum class eATmegaPort { PORT_A, PORT_B, PORT_C, PORT_D #elif defined(__AVR_TRM03__) PORT_B, PORT_C, PORT_D +#elif defined(__AVR_TRM04__) + PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F #endif }; @@ -2100,17 +2677,19 @@ struct ATmegaPinInfo { uint8_t pinidx; }; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) #define _SPA_DIO_DDRA (eATmegaPort::PORT_A) #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) #define _SPA_DIO_DDRB (eATmegaPort::PORT_B) #define _SPA_DIO_DDRC (eATmegaPort::PORT_C) #define _SPA_DIO_DDRD (eATmegaPort::PORT_D) #endif -#if defined(__AVR_TRM01__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) #define _SPA_DIO_DDRE (eATmegaPort::PORT_E) #define _SPA_DIO_DDRF (eATmegaPort::PORT_F) +#endif +#if defined(__AVR_TRM01__) #define _SPA_DIO_DDRG (eATmegaPort::PORT_G) #define _SPA_DIO_DDRH (eATmegaPort::PORT_H) #define _SPA_DIO_DDRJ (eATmegaPort::PORT_J) @@ -2475,7 +3054,7 @@ inline ATmegaPinInfo _ATmega_getPinInfo(uint8_t pin) { #endif // Default. -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) return { eATmegaPort::PORT_A, 0 }; #elif defined(__AVR_TRM03__) return { eATmegaPort::PORT_B, 0 }; @@ -2903,6 +3482,143 @@ inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { USART0._UCSRnB._RXEN = false; } } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + state._COM1C = TIMER1._TCCRnA._COMnC; + + TIMER1._TCCRnA._COMnC = 0; + } + else if (info.pinidx == 6) { + state._COM1B = TIMER1._TCCRnA._COMnB; + + TIMER1._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 5) { + state._COM1A = TIMER1._TCCRnA._COMnA; + + TIMER1._TCCRnA._COMnA = 0; + } + else if (info.pinidx == 4) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + + _TIMER2._TCCRnA._COMnA = 0; + } + else if (info.pinidx <= 3) { + state._SPE = _SPCR._SPE; + + _SPCR._SPE = false; + } + + state._PCIE0 = _PCICR._PCIE0; + + _PCICR._PCIE0 = false; + } + else if (info.port == eATmegaPort::PORT_C) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 5) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + state._USART1_TXEN = USART1._UCSRnB._TXEN; + + USART1._UCSRnB._RXEN = false; + USART1._UCSRnB._TXEN = false; + } + else if (info.pinidx == 3) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + + USART1._UCSRnB._TXEN = false; + } + else if (info.pinidx == 2) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + + USART1._UCSRnB._RXEN = false; + } + else if (info.pinidx <= 1) { + state._TWEN = _TWCR._TWEN; + + _TWCR._TWEN = false; + } + + if (info.pinidx == 1) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + + _TIMER2._TCCRnA._COMnB = 0; + } + else if (info.pinidx == 0) { + state._COM0B = TIMER0._TCCRnA._COMnB; + + TIMER0._TCCRnA._COMnB = 0; + } + + if (info.pinidx == 3) { + state._INTn = _EIMSK._INT3; + + _EIMSK._INT3 = false; + } + else if (info.pinidx == 2) { + state._INTn = _EIMSK._INT2; + + _EIMSK._INT2 = false; + } + else if (info.pinidx == 1) { + state._INTn = _EIMSK._INT1; + + _EIMSK._INT1 = false; + } + else if (info.pinidx == 0) { + state._INTn = _EIMSK._INT0; + + _EIMSK._INT0 = false; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + state._UVCONE = _UHWCON._UVCONE; + + _UHWCON._UVCONE = false; + } + else if (info.pinidx == 3) { + state._UIDE = _UHWCON._UIDE; + + _UHWCON._UIDE = false; + } + else if (info.pinidx <= 2) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + + if (info.pinidx == 7) { + state._INTn = _EIMSK._INT7; + + _EIMSK._INT7 = false; + } + else if (info.pinidx == 6) { + state._INTn = _EIMSK._INT6; + + _EIMSK._INT6 = false; + } + else if (info.pinidx == 5) { + state._INTn = _EIMSK._INT5; + + _EIMSK._INT5 = false; + } + else if (info.pinidx == 4) { + state._INTn = _EIMSK._INT4; + + _EIMSK._INT4 = false; + } + } + // Ignore port F. #endif return state; @@ -3172,5 +3888,91 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat USART0._UCSRnB._RXEN = state._USART0_RXEN; } } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _XMCRA._SRE = state._SRE; + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + else if (info.pinidx == 6) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + else if (info.pinidx == 5) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + else if (info.pinidx == 4) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + else if (info.pinidx <= 3) { + _SPCR._SPE = state._SPE; + } + + _PCICR._PCIE0 = state._PCIE0; + } + else if (info.port == eATmegaPort::PORT_C) { + _XMCRA._SRE = state._SRE; + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 5) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + else if (info.pinidx == 3) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + else if (info.pinidx == 2) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + else if (info.pinidx <= 1) { + _TWCR._TWEN = state._TWEN; + } + + if (info.pinidx == 1) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + else if (info.pinidx == 0) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + + if (info.pinidx == 3) { + _EIMSK._INT3 = state._INTn; + } + else if (info.pinidx == 2) { + _EIMSK._INT2 = state._INTn; + } + else if (info.pinidx == 1) { + _EIMSK._INT1 = state._INTn; + } + else if (info.pinidx == 0) { + _EIMSK._INT0 = state._INTn; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + _UHWCON._UVCONE = state._UVCONE; + } + else if (info.pinidx == 3) { + _UHWCON._UIDE = state._UIDE; + } + else if (info.pinidx <= 2) { + _XMCRA._SRE = state._SRE; + } + + if (info.pinidx == 7) { + _EIMSK._INT7 = state._INTn; + } + else if (info.pinidx == 6) { + _EIMSK._INT6 = state._INTn; + } + else if (info.pinidx == 5) { + _EIMSK._INT5 = state._INTn; + } + else if (info.pinidx == 4) { + _EIMSK._INT4 = state._INTn; + } + } + // Ignore port F. #endif } \ No newline at end of file From bb3f8204b08908d1b4519904cbd4d40f82bc4aa4 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 1 Dec 2022 19:54:04 +0100 Subject: [PATCH 26/83] - added _ATmega_getPinFunctions function: returns the list of MCU functions mapped to the given digital pin, enabled as soon as the powering MCU component is enabled --- Marlin/src/HAL/AVR/registers.cpp | 835 +++++++++++++++++++++++++++++++ Marlin/src/HAL/AVR/registers.h | 90 +++- 2 files changed, 924 insertions(+), 1 deletion(-) create mode 100644 Marlin/src/HAL/AVR/registers.cpp diff --git a/Marlin/src/HAL/AVR/registers.cpp b/Marlin/src/HAL/AVR/registers.cpp new file mode 100644 index 000000000000..3188edb3084d --- /dev/null +++ b/Marlin/src/HAL/AVR/registers.cpp @@ -0,0 +1,835 @@ +/** + * 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 . + * + */ + +#include "registers.h" + +#ifndef countof +#define countof(o) ((sizeof(o))/(sizeof(*o))) +#endif + +// Since the compiler could be creating multiple copies of function code-graphs for each header inline-inclusion, +// we want to off-load the function definitions that define static memory into this solitary compilation unit. +// This way the ROM is NOT bloated (who knows if the compiler is optimizing same-content constant objects into one?) + +ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { + ATmegaPinInfo info = _ATmega_getPinInfo(pin); + +#if defined(__AVR_TRM01__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0A, eATmegaPinFunc::OC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::OC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::OC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::OC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::USART0_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::USART0_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_G) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3 ) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_H) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_RXD }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_J) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_CLK, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_RXD, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_K) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC15, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC14, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC13, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC12, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC11, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC10, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC9, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC8, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_L) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_ICP }; + return { funcs, countof(funcs) }; + } + } +#elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::OC3B, eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::OC3A, eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::OC0B, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::OC0A, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::EINT2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI17, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI31 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::OC2B, eATmegaPinFunc::PCI30 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI29 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::PCI27 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::PCI26 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI25 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI24, eATmegaPinFunc::TIMER3_ECI }; + return { funcs, countof(funcs) }; + } + } +#elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL2, eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL1, eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::OC0A, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::OC0B, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_CLK, eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::OC2B, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_TXD, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_RXD, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0A, eATmegaPinFunc::OC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::OC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::OC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::OC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::OC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::OC0B }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::AIN1, eATmegaPinFunc::UVCON }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::AIN0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::UID }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } +#endif + + return ATmegaPinFunctions(); // default and empty. +} \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 79d29857477d..12d43de7673c 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -22,6 +22,8 @@ #pragma once +#include + // OVERVIEW OF PREPROCESSOR DEFINITIONS: // __AVR_ATmega2560__ // __AVR_ATmega1284P__ @@ -3975,4 +3977,90 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat } // Ignore port F. #endif -} \ No newline at end of file +} + +enum class eATmegaPinFunc { +#if defined(__AVR_TRM01__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + OC0A, OC0B, OC1A, OC1B, OC1C, OC2A, OC2B, OC3C, OC3B, OC3A, OC4C, OC4B, OC4A, OC5C, OC5B, OC5A, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, PCI8, + PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, + PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TOSC1, TOSC2, + TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, + TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, + USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, + TWI_SDA, TWI_CLK, + CLK0, PDO, PDI, + AIN0, AIN1, + ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 +#elif defined(__AVR_TRM02__) + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + EINT2, EINT1, EINT0, + TIMER3_ICP, + TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, + TIMER1_ICP, + OC3B, OC3A, OC2A, OC2B, OC1A, OC1B, OC0B, OC0A, + AIN1, AIN0, + USART0_CLK, USART1_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, + CLK0, + TOSC2, TOSC1, + TWI_SDA, TWI_CLK +#elif defined(__AVR_TRM03__) + ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + XTAL2, XTAL1, + TOSC2, TOSC1, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + OC2B, OC2A, OC1B, OC1A, OC0A, OC0B, + TIMER1_ICP, + TIMER1_ECI, TIMER0_ECI, + TWI_CLK, TWI_SDA, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + CLK0, + AIN1, AIN0, + USART_CLK, + USART_TXD, USART_RXD, + EINT1, EINT0 +#elif defined(__AVR_TRM04__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + OC0B, OC0A, OC1C, OC1B, OC1A, OC2B, OC2A, OC3A, OC3B, OC3C, + CLK0, PDO, PDI, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TIMER3_ICP, TIMER1_ICP, + TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, + USART1_CLK, USART1_TXD, USART1_RXD, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + TWI_SDA, TWI_CLK, + AIN1, AIN0, + TOSC2, + UID, UVCON, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 +#endif +}; + +struct ATmegaPinFunctions { + inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} + inline ATmegaPinFunctions() = default; + inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; + + const eATmegaPinFunc *funcs = nullptr; + uint8_t cnt = 0; +}; + +ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin); \ No newline at end of file From 54ab13c92d04aa84f91d5422afdc5dfe1c3fe37a Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Tue, 6 Dec 2022 20:03:19 +0100 Subject: [PATCH 27/83] - improved the AVR HAL SPI hardware implementation + moved SOFTWARE_SPI implementation into it's own file - improved the maintainability of dozen AVR board pin header files (actual pin names instead of internal numbers) Please help me convert the rest of them so that we can have a clean Marlin experience! - added spiEstablish function which forces kick-up of SPI signals + peripherals that would otherwise be implicitly done by transmission functions (if required) - added more debug logic to ESP32 (further work pending to get DMA working) --- Marlin/src/HAL/AVR/HAL_SPI.cpp | 445 ------------- Marlin/src/HAL/AVR/HAL_SPI_HW.cpp | 423 ++++++++++++ Marlin/src/HAL/AVR/HAL_SPI_SW.cpp | 312 +++++++++ Marlin/src/HAL/AVR/fastio/fastio_1280.h | 618 +++--------------- Marlin/src/HAL/AVR/fastio/fastio_1281.h | 387 ++--------- Marlin/src/HAL/AVR/fastio/fastio_168.h | 192 +----- Marlin/src/HAL/AVR/fastio/fastio_644.h | 258 +------- Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h | 385 ++--------- Marlin/src/HAL/AVR/registers.cpp | 82 +-- Marlin/src/HAL/AVR/registers.h | 494 +++++++++++++- Marlin/src/HAL/DUE/HAL_SPI.cpp | 8 + Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 76 ++- Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp | 4 + Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 4 + Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp | 4 + Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 2 + Marlin/src/HAL/STM32/HAL_SPI_HW.cpp | 4 + Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp | 2 + Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 2 + Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 2 + Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 2 + Marlin/src/HAL/shared/HAL_SPI.h | 6 + Marlin/src/pins/mega/pins_CHEAPTRONIC.h | 49 +- Marlin/src/pins/mega/pins_CHEAPTRONICv2.h | 113 ++-- Marlin/src/pins/mega/pins_CNCONTROLS_11.h | 119 ++-- Marlin/src/pins/mega/pins_CNCONTROLS_12.h | 131 ++-- Marlin/src/pins/mega/pins_CNCONTROLS_15.h | 71 +- Marlin/src/pins/mega/pins_EINSTART-S.h | 69 +- Marlin/src/pins/mega/pins_ELEFU_3.h | 95 +-- Marlin/src/pins/mega/pins_GT2560_REV_A.h | 144 ++-- Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h | 3 +- Marlin/src/pins/mega/pins_GT2560_REV_B.h | 1 + Marlin/src/pins/mega/pins_GT2560_V3.h | 129 ++-- Marlin/src/pins/mega/pins_GT2560_V3_A20.h | 15 +- Marlin/src/pins/mega/pins_GT2560_V3_MC2.h | 9 +- Marlin/src/pins/mega/pins_GT2560_V4_A20.h | 15 +- Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 129 ++-- Marlin/src/pins/mega/pins_INTAMSYS40.h | 95 +-- Marlin/src/pins/mega/pins_LEAPFROG.h | 65 +- Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h | 73 ++- Marlin/src/pins/mega/pins_MALYAN_M180.h | 58 +- Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 109 +-- Marlin/src/pins/mega/pins_MEGATRONICS.h | 95 +-- Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 117 ++-- Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 151 ++--- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 176 ++--- Marlin/src/pins/mega/pins_MINITRONICS.h | 85 +-- Marlin/src/pins/mega/pins_OVERLORD.h | 101 +-- Marlin/src/pins/mega/pins_PICA.h | 105 +-- Marlin/src/pins/mega/pins_PICAOLD.h | 10 +- .../pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h | 37 +- Marlin/src/pins/mega/pins_SILVER_GATE.h | 84 +-- Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h | 67 +- Marlin/src/pins/mega/pins_WEEDO_62A.h | 69 +- Marlin/src/pins/ramps/env_validate.h | 11 +- Marlin/src/pins/ramps/pins_3DRAG.h | 57 +- Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h | 79 +-- 57 files changed, 3024 insertions(+), 3424 deletions(-) delete mode 100644 Marlin/src/HAL/AVR/HAL_SPI.cpp create mode 100644 Marlin/src/HAL/AVR/HAL_SPI_HW.cpp create mode 100644 Marlin/src/HAL/AVR/HAL_SPI_SW.cpp diff --git a/Marlin/src/HAL/AVR/HAL_SPI.cpp b/Marlin/src/HAL/AVR/HAL_SPI.cpp deleted file mode 100644 index 7c324c032cd9..000000000000 --- a/Marlin/src/HAL/AVR/HAL_SPI.cpp +++ /dev/null @@ -1,445 +0,0 @@ -/** - * 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 . - * - */ - -/** - * Adapted from Arduino Sd2Card Library - * Copyright (c) 2009 by William Greiman - */ - -/** - * HAL for AVR - SPI functions - */ - -#ifdef __AVR__ - -#include "../../inc/MarlinConfig.h" - -#include "registers.h" - -void spiBegin() { - #if PIN_EXISTS(SD_SS) - // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. - #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) - // SS must be in output mode even it is not chip select - SET_OUTPUT(SD_SS_PIN); - #else - // set SS high - may be chip select for another SPI device - OUT_WRITE(SD_SS_PIN, HIGH); - #endif - #endif - SET_OUTPUT(SD_SCK_PIN); - SET_INPUT(SD_MISO_PIN); - SET_OUTPUT(SD_MOSI_PIN); -} - -#if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) - - // ------------------------ - // Hardware SPI - // ------------------------ - - // make sure SPCR rate is in expected bits - #if (SPR0 != 0 || SPR1 != 1) - #error "unexpected SPCR bits" - #endif - - /** - * Initialize hardware SPI - * Set SCK rate to F_CPU/pow(2, 1 + spiRate) for spiRate [0,6] - */ - void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { - // Ignore SPI pin hints. - - // See avr processor documentation - CBI( - #ifdef PRR - PRR - #elif defined(PRR0) - PRR0 - #endif - , PRSPI - ); - - // DORD is set to 0 -> MSB transfer, else LSB - - SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1); - SPSR = spiRate & 1 || spiRate == SPI_SPEED_6 ? 0 : _BV(SPI2X); - } - - void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - // Use datarates Marlin uses - uint8_t spiRate; - if (maxClockFreq >= 20000000) { - spiRate = SPI_FULL_SPEED; - } - else if (maxClockFreq >= 5000000) { - spiRate = SPI_HALF_SPEED; - } - else if (maxClockFreq >= 2500000) { - spiRate = SPI_QUARTER_SPEED; - } - else if (maxClockFreq >= 1250000) { - spiRate = SPI_EIGHTH_SPEED; - } - else if (maxClockFreq >= 625000) { - spiRate = SPI_SPEED_5; - } - else if (maxClockFreq >= 300000) { - spiRate = SPI_SPEED_6; - } - else - spiRate = SPI_SPEED_6; - - spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); - } - - void spiClose() { /* do nothing */ } - - void spiSetBitOrder(int bitOrder) { - if (bitOrder == SPI_BITORDER_MSB) { - SPCR &= ~_BV(DORD); - } - else if (bitOrder == SPI_BITORDER_LSB) { - SPCR |= _BV(DORD); - } - } - - void spiSetClockMode(int clockMode) { - // TODO. - if (clockMode != SPI_CLKMODE_0) { - for (;;) {} - } - } - - /** SPI receive a byte */ - uint8_t spiRec(uint8_t txval) { - SPDR = txval; - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - return SPDR; - } - - uint16_t spiRec16(uint16_t txval) { - bool msb = ( TEST(SPCR, DORD) == false ); - uint8_t tx_first, tx_second; - if (msb) { - tx_first = ( txval >> 8 ); - tx_second = ( txval & 0xFF ); - } - else { - tx_first = ( txval & 0xFF ); - tx_second = ( txval >> 8 ); - } - SPDR = tx_first; - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } - uint16_t val = ( msb ? ( (uint16_t)SPDR << 8 ) : ( SPDR ) ); - SPDR = tx_second; - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } - val |= ( msb ? ( SPDR ) : ( (uint16_t)SPDR << 8 ) ); - return val; - } - - /** SPI read data */ - void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { - if (nbyte-- == 0) return; - SPDR = txval; - for (uint16_t i = 0; i < nbyte; i++) { - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - buf[i] = SPDR; - SPDR = txval; - } - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - buf[nbyte] = SPDR; - } - - /** SPI send a byte */ - void spiSend(uint8_t b) { - SPDR = b; - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - } - - void spiSend16(uint16_t v) { - bool msb = ( TEST(SPCR, DORD) == false ); - SPDR = ( msb ? ( v >> 8 ) : ( v & 0xFF ) ); - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } - SPDR = ( msb ? ( v & 0xFF ) : ( v >> 8 ) ); - while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } - } - - /** SPI send block */ - void spiSendBlock(uint8_t token, const uint8_t *buf) { - SPDR = token; - for (uint16_t i = 0; i < 512; i += 2) { - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - SPDR = buf[i]; - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - SPDR = buf[i + 1]; - } - while (!TEST(SPSR, SPIF)) { /* do nothing */ } - } - - /** Begin SPI transaction */ - void spiWrite(const uint8_t *buf, uint16_t cnt) { - for (uint16_t n = 0; n < cnt; n++) - spiSend(buf[n]); - } - - void spiWrite16(const uint16_t *buf, uint16_t cnt) { - for (uint16_t n = 0; n < cnt; n++) - spiSend16(buf[n]); - } - - void spiWriteRepeat(uint8_t val, uint16_t repcnt) { - for (uint16_t n = 0; n < repcnt; n++) - spiSend(val); - } - - void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { - for (uint16_t n = 0; n < repcnt; n++) - spiSend16(val); - } - -#if 0 - /** begin spi transaction (TODO: merge ideas into spiInitEx) */ - void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { - // Based on Arduino SPI library - // Clock settings are defined as follows. Note that this shows SPI2X - // inverted, so the bits form increasing numbers. Also note that - // fosc/64 appears twice - // SPR1 SPR0 ~SPI2X Freq - // 0 0 0 fosc/2 - // 0 0 1 fosc/4 - // 0 1 0 fosc/8 - // 0 1 1 fosc/16 - // 1 0 0 fosc/32 - // 1 0 1 fosc/64 - // 1 1 0 fosc/64 - // 1 1 1 fosc/128 - - // We find the fastest clock that is less than or equal to the - // given clock rate. The clock divider that results in clock_setting - // is 2 ^^ (clock_div + 1). If nothing is slow enough, we'll use the - // slowest (128 == 2 ^^ 7, so clock_div = 6). - uint8_t clockDiv; - - // When the clock is known at compiletime, use this if-then-else - // cascade, which the compiler knows how to completely optimize - // away. When clock is not known, use a loop instead, which generates - // shorter code. - if (__builtin_constant_p(spiClock)) { - if (spiClock >= F_CPU / 2) clockDiv = 0; - else if (spiClock >= F_CPU / 4) clockDiv = 1; - else if (spiClock >= F_CPU / 8) clockDiv = 2; - else if (spiClock >= F_CPU / 16) clockDiv = 3; - else if (spiClock >= F_CPU / 32) clockDiv = 4; - else if (spiClock >= F_CPU / 64) clockDiv = 5; - else clockDiv = 6; - } - else { - uint32_t clockSetting = F_CPU / 2; - clockDiv = 0; - while (clockDiv < 6 && spiClock < clockSetting) { - clockSetting /= 2; - clockDiv++; - } - } - - // Compensate for the duplicate fosc/64 - if (clockDiv == 6) clockDiv = 7; - - // Invert the SPI2X bit - clockDiv ^= 0x1; - - SPCR = _BV(SPE) | _BV(MSTR) | ((bitOrder == LSBFIRST) ? _BV(DORD) : 0) | - (dataMode << CPHA) | ((clockDiv >> 1) << SPR0); - SPSR = clockDiv | 0x01; - } -#endif - -#else // SOFTWARE_SPI || FORCE_SOFT_SPI - - // ------------------------ - // Software SPI - // ------------------------ - - // nop to tune soft SPI timing - #define nop asm volatile ("\tnop\n") - - static int _spi_bit_order = SPI_BITORDER_DEFAULT; - - void spiInit(uint8_t, const int/*=-1*/, const int/*=-1*/, const int/*=-1*/, const int/*=-1*/) { /* do nothing */ } - void spiInitEx(uint32_t, int, int, int, int) { /* do nothing */ } - void spiClose() { /* do nothing */ } - - void spiSetBitOrder(int bitOrder) { - _spi_bit_order = bitOrder; - } - - void spiSetClockMode(int clockMode) { - // TODO. - if (clockMode != SPI_CLKMODE_0) { - for (;;) {} - } - } - - // Soft SPI receive byte - uint8_t spiRec(uint8_t txval) { - if (txval != 0xFF) { - // TODO. - for (;;) {} - } - uint8_t data = 0; - // no interrupts during byte receive - about 8µs - cli(); - // output pin high - like sending 0xFF - WRITE(SD_MOSI_PIN, HIGH); - - bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); - - LOOP_L_N(i, 8) { - WRITE(SD_SCK_PIN, HIGH); - - nop; // adjust so SCK is nice - nop; - - if (READ(SD_MISO_PIN)) - { - int bitidx = ( msb ? 7-i : i ); - data |= ( 1 << bitidx ); - } - - WRITE(SD_SCK_PIN, LOW); - } - - sei(); - return data; - } - - uint16_t spiRec16(uint16_t txval) { - if (txval != 0xFFFF) { - // TODO. - for (;;) {} - } - uint16_t data = 0; - bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); - // no interrupts during byte receive - about 8µs - cli(); - // output pin high - like sending 0xFF - WRITE(SD_MOSI_PIN, HIGH); - - LOOP_L_N(i, 16) { - WRITE(SD_SCK_PIN, HIGH); - - nop; // adjust so SCK is nice - nop; - - if (READ(SD_MISO_PIN)) - { - int bitidx = ( msb ? 15-i : i ); - data |= ( 1 << bitidx ); - } - - WRITE(SD_SCK_PIN, LOW); - } - - sei(); - return data; - } - - // Soft SPI read data - void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { - for (uint16_t i = 0; i < nbyte; i++) - buf[i] = spiRec(txval); - } - - // Soft SPI send byte - void spiSend(uint8_t data) { - bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); - // no interrupts during byte send - about 8µs - cli(); - LOOP_L_N(i, 8) { - int bitidx = ( msb ? 7-i : i ); - WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, ( data & ( 1 << bitidx )) != 0); - WRITE(SD_SCK_PIN, HIGH); - } - - nop; // hold SCK high for a few ns - nop; - nop; - nop; - - WRITE(SD_SCK_PIN, LOW); - - sei(); - } - - void spiSend16(uint16_t v) { - bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); - // no interrupts during byte send - about 8µs - cli(); - LOOP_L_N(i, 16) { - int bitidx = ( msb ? 15-i : i ); - WRITE(SD_SCK_PIN, LOW); - WRITE(SD_MOSI_PIN, ( v & ( 1 << bitidx )) != 0); - WRITE(SD_SCK_PIN, HIGH); - } - - nop; // hold SCK high for a few ns - nop; - nop; - nop; - - WRITE(SD_SCK_PIN, LOW); - - sei(); - } - - // Soft SPI send block - void spiSendBlock(uint8_t token, const uint8_t *buf) { - spiSend(token); - for (uint16_t i = 0; i < 512; i++) - spiSend(buf[i]); - } - - void spiWrite(const uint8_t *buf, uint16_t cnt) { - for (uint16_t n = 0; n < cnt; n++) - spiSend(buf[n]); - } - - void spiWrite16(const uint16_t *buf, uint16_t cnt) { - for (uint16_t n = 0; n < cnt; n++) - spiSend16(buf[n]); - } - - void spiWriteRepeat(uint8_t val, uint16_t repcnt) { - for (uint16_t n = 0; n < repcnt; n++) - spiSend(val); - } - - void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { - for (uint16_t n = 0; n < repcnt; n++) - spiSend16(val); - } - -#endif // SOFTWARE_SPI || FORCE_SOFT_SPI - -#endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp new file mode 100644 index 000000000000..7b326018ae9b --- /dev/null +++ b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp @@ -0,0 +1,423 @@ +/** + * 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 . + * + */ + +/** + * Adapted from Arduino Sd2Card Library + * Copyright (c) 2009 by William Greiman + */ + +/** + * HAL for AVR - SPI functions + */ + +#ifdef __AVR__ + +#include "../../inc/MarlinConfig.h" + +#include "registers.h" + +#if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) + +#ifndef AVR_CHIPOSCILLATOR_FREQ +#error Missing AVR crystal oscillator frequency! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) +#endif + + // ------------------------ + // Hardware SPI + // ------------------------ + + static void _spi_on_error(int code) { + for (;;) { +#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (int n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code-1) + delay(500); + } + delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(800); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + } + + static bool _spi_is_running = false; + static int _spi_cs_pin; + static bool _spi_transaction_is_active; + static bool _spi_dirty_tx; + + void spiBegin() { + #if PIN_EXISTS(SD_SS) + // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. + #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + // SS must be in output mode even if it is not chip select + SET_OUTPUT(SD_SS_PIN); + #else + // set SS high - may be chip select for another SPI device + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + #endif + // This could still be required because the specification says that the DDR of those pins is "User Defined". + SET_OUTPUT(SD_SCK_PIN); + SET_OUTPUT(SD_MOSI_PIN); + + // By default we disable the SPI peripheral. + _PRR0._PRSPI = true; + } + + // Returns the clock frequency as output by the System Clock Prescaler. + inline uint32_t _GetSystemClockFrequency() { + // See which clock is selected. + const ATmega_lfuse lfuse = AVR_LFUSE_VALUE; + + uint32_t baseclk; + + switch(lfuse._CKSEL) { + case 15: case 14: case 13: case 12: case 11: case 10: case 9: case 8: + case 7: case 6: case 5: case 4: + baseclk = AVR_CHIPOSCILLATOR_FREQ; + break; + case 3: + // Internal 128kHz RC Oscillator. + baseclk = 128000; + break; + case 2: + // Calibrated Internal RC Oscillator. + baseclk = 8000000; + break; + case 1: + case 0: + _spi_on_error(3); + break; + } + + // Divide the system clock. + uint8_t clkps_po2 = _CLKPR._CLKPS; + + return ( baseclk >> clkps_po2 ); + } + + inline void _spiConfigBitOrder(SPCR_reg_t& __SPCR, int mode) { + if (mode == SPI_BITORDER_LSB) { + __SPCR._DORD = 1; + } + else if (mode == SPI_BITORDER_MSB) { + __SPCR._DORD = 0; + } + } + + inline void _spiConfigClockMode(SPCR_reg_t& __SPCR, int mode) { + if (mode == SPI_CLKMODE_0) { + __SPCR._CPOL = 0; + __SPCR._CPHA = 0; + } + else if (mode == SPI_CLKMODE_1) { + __SPCR._CPOL = 0; + __SPCR._CPHA = 1; + } + else if (mode == SPI_CLKMODE_2) { + __SPCR._CPOL = 1; + __SPCR._CPHA = 0; + } + else if (mode == SPI_CLKMODE_3) { + __SPCR._CPOL = 1; + __SPCR._CPHA = 1; + } + } + + /** + * Initialize hardware SPI transaction + */ + void spiInitEx(uint32_t maxClockFreq, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { + if (_spi_is_running) + _spi_on_error(1); + + // In hardware SPI mode we can only use the pre-determined SPI pins for MISO, MOSI and SCK, thus ignore the first three pin hints. + // But for the chip-select pin, we either have to go HW mode if it is the peripheral SPI pin or we can go SW if it is a GPIO. + if ( _ATmega_getPinFunctions(hint_cs).hasFunc(eATmegaPinFunc::SPI_CS) ) { + // HW SPI_CS + _spi_cs_pin = -1; + } + else { + // SW SPI_CS + _spi_cs_pin = hint_cs; + } + + // Clear the power-reduction. + _PRR0._PRSPI = false; + + // Calculate the required division to run the SPI clock below maxClockFreq. + uint32_t sysclk = _GetSystemClockFrequency(); + + SPCR_reg_t __SPCR; + __SPCR._SPIE = false; + __SPCR._SPE = true; + _spiConfigBitOrder(__SPCR, SPI_BITORDER_DEFAULT); + __SPCR._MSTR = true; + _spiConfigClockMode(__SPCR, SPI_CLKMODE_DEFAULT); + + if ((sysclk / 2) <= maxClockFreq) { + _SPSR._SPI2X = true; + __SPCR._SPR = 0; + } + else if ((sysclk / 4) <= maxClockFreq) { + _SPSR._SPI2X = false; + __SPCR._SPR = 0; + } + else if ((sysclk / 8) <= maxClockFreq) { + _SPSR._SPI2X = true; + __SPCR._SPR = 1; + } + else if ((sysclk / 16) <= maxClockFreq) { + _SPSR._SPI2X = false; + __SPCR._SPR = 1; + } + else if ((sysclk / 32) <= maxClockFreq) { + _SPSR._SPI2X = true; + __SPCR._SPR = 2; + } + else if ((sysclk / 64) <= maxClockFreq) { + _SPSR._SPI2X = false; + __SPCR._SPR = 2; + } + else { + // Cannot go below it. + _SPSR._SPI2X = false; + __SPCR._SPR = 3; + } + + // Write initial configuration. + _SPCR = __SPCR; + + _spi_is_running = true; + _spi_transaction_is_active = false; + _spi_dirty_tx = false; + } + + static void _maybe_start_transaction() { + if (_spi_transaction_is_active) return; + + if (_spi_cs_pin >= 0) + _ATmega_digitalWrite(_spi_cs_pin, LOW); + + _spi_transaction_is_active = true; + } + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + inline void _spi_finish_tx() { + if (_spi_dirty_tx == false) return; + + while (_SPSR._SPIF == false) { /* do nothing */ } + + _spi_dirty_tx = false; + } + + void spiClose() { + if (_spi_is_running == false) + _spi_on_error(2); + + _spi_finish_tx(); + + if (_spi_transaction_is_active) { + if (_spi_cs_pin >= 0) + _ATmega_digitalWrite(_spi_cs_pin, HIGH); + + _spi_transaction_is_active = false; + } + + // Disable the peripheral again. + _PRR0._PRSPI = true; + + _spi_is_running = false; + } + + void spiSetBitOrder(int bitOrder) { + _spiConfigBitOrder(_SPCR, bitOrder); + } + + void spiSetClockMode(int clockMode) { + _spiConfigClockMode(_SPCR, clockMode); + } + + void spiEstablish() { + _maybe_start_transaction(); + } + + /** SPI receive a byte */ + uint8_t spiRec(uint8_t txval) { + _maybe_start_transaction(); + _spi_finish_tx(); + _SPDR = txval; + while (_SPSR._SPIF == false) { /* wait until data has been received */ } + return _SPDR; + } + + inline void _split_txbytes(uint16_t txval, uint8_t& tx_first, uint8_t& tx_second, bool msb) { + if (msb) { + tx_first = ( txval >> 8 ); + tx_second = ( txval & 0xFF ); + } + else { + tx_first = ( txval & 0xFF ); + tx_second = ( txval >> 8 ); + } + } + + inline uint16_t _fuse_txbytes(uint8_t rx_first, uint8_t rx_second, bool msb) { + if (msb) { + return ( (uint16_t)rx_first << 8 ) | ( (uint16_t)rx_second ); + } + else { + return ( (uint16_t)rx_first ) | ( (uint16_t)rx_second << 8 ); + } + } + + uint16_t spiRec16(uint16_t txval) { + _maybe_start_transaction(); + bool msb = ( _SPCR._DORD == 0 ); + uint8_t tx_first, tx_second; + _split_txbytes(txval, tx_first, tx_second, msb); + _spi_finish_tx(); + _SPDR = tx_first; + while (_SPSR._SPIF == false) { /* Intentionally left empty */ } + uint8_t rx_first = _SPDR; + _SPDR = tx_second; + while (_SPSR._SPIF == false) { /* Intentionally left empty */ } + uint8_t rx_second = _SPDR; + return _fuse_txbytes(rx_first, rx_second, msb); + } + + /** SPI read data */ + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + if (nbyte == 0) return; + _maybe_start_transaction(); + nbyte--; + _spi_finish_tx(); + _SPDR = txval; + for (uint16_t i = 0; i < nbyte; i++) { + while (_SPSR._SPIF == false) { /* do nothing */ } + buf[i] = _SPDR; + _SPDR = txval; + } + while (_SPSR._SPIF == false) { /* do nothing */ } + buf[nbyte] = _SPDR; + } + + inline void _spiSendByte(uint8_t byte) { + _spi_finish_tx(); + _SPDR = byte; + _spi_dirty_tx = true; + } + + /** SPI send a byte */ + void spiSend(uint8_t b) { + _maybe_start_transaction(); + _spiSendByte(b); + } + + void spiSend16(uint16_t v) { + _maybe_start_transaction(); + bool msb = ( _SPCR._DORD == 0 ); + uint8_t tx_first, tx_second; + _split_txbytes(v, tx_first, tx_second, msb); + _spiSendByte(tx_first); + _spiSendByte(tx_second); + } + + /** SPI send block */ + void spiSendBlock(uint8_t token, const uint8_t *buf) { + _maybe_start_transaction(); + _spiSendByte(token); + for (uint16_t i = 0; i < 512; i++) { + _spiSendByte(buf[i]); + } + } + + /** Begin SPI transaction */ + void spiWrite(const uint8_t *buf, uint16_t cnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < cnt; n++) + _spiSendByte(n); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + _maybe_start_transaction(); + bool msb = ( _SPCR._DORD == 0 ); + for (uint16_t n = 0; n < cnt; n++) { + uint8_t tx_first, tx_second; + _split_txbytes(buf[n], tx_first, tx_second, msb); + _spiSendByte(tx_first); + _spiSendByte(tx_second); + } + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < repcnt; n++) + _spiSendByte(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + _maybe_start_transaction(); + bool msb = ( _SPCR._DORD == 0 ); + uint8_t tx_first, tx_second; + _split_txbytes(val, tx_first, tx_second, msb); + for (uint16_t n = 0; n < repcnt; n++) { + _spiSendByte(tx_first); + _spiSendByte(tx_second); + } + } + +#endif + +#endif \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp new file mode 100644 index 000000000000..ece1756dc97e --- /dev/null +++ b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp @@ -0,0 +1,312 @@ +/** + * 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 . + * + */ + +/** + * Adapted from Arduino Sd2Card Library + * Copyright (c) 2009 by William Greiman + */ + +/** + * HAL for AVR - SPI functions + */ + +#ifdef __AVR__ + +#include "../../inc/MarlinConfig.h" + +#include "registers.h" + +#if EITHER(SOFTWARE_SPI, FORCE_SOFT_SPI) + + // ------------------------ + // Software SPI + // ------------------------ + + // nop to tune soft SPI timing + #define nop asm volatile ("\tnop\n") + + static void _spi_on_error(int code) { + for (;;) { +#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (int n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code-1) + delay(500); + } + delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(800); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } + } + + static pin_dev_state_t _spi_sck_devstate, _spi_miso_devstate, _spi_mosi_devstate, _spi_cs_devstate; + static int _spi_sck_pin, _spi_miso_pin, _spi_mosi_pin, _spi_cs_pin; + static int _spi_bit_order = SPI_BITORDER_DEFAULT; + static bool _spi_is_running = false; + + void spiBegin() { + #if PIN_EXISTS(SD_SS) + // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. + #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + // SS must be in output mode even if it is not chip select + SET_OUTPUT(SD_SS_PIN); + #else + // set SS high - may be chip select for another SPI device + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + #endif + // This could still be required because the specification says that the DDR of those pins is "User Defined". + SET_OUTPUT(SD_SCK_PIN); + SET_OUTPUT(SD_MOSI_PIN); + } + + void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { + if (_spi_is_running) + _spi_on_error(1); + + // In software SPI we want to power all pins in GPIO mode. + // That is why we have to disable all peripherals that conflict with our SPI operations. + int use_pin_sck = (hint_sck >= 0) ? hint_sck : SD_SCK_PIN; + int use_pin_miso = (hint_miso >= 0) ? hint_miso : SD_MISO_PIN; + int use_pin_mosi = (hint_mosi >= 0) ? hint_mosi : SD_MOSI_PIN; + int use_pin_cs = (hint_cs >= 0) ? hint_cs : SD_SS_PIN; + + if (use_pin_sck >= 0) + _spi_sck_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_sck); + if (use_pin_miso >= 0) + _spi_miso_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_miso); + if (use_pin_mosi >= 0) + _spi_mosi_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_mosi); + if (use_pin_cs >= 0) + _spi_cs_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_cs); + + _spi_sck_pin = use_pin_sck; + _spi_miso_pin = use_pin_miso; + _spi_mosi_pin = use_pin_mosi; + _spi_cs_pin = use_pin_cs; + + _ATmega_pinMode(_spi_sck_pin, OUTPUT); + _ATmega_pinMode(_spi_miso_pin, INPUT); + _ATmega_pinMode(_spi_mosi_pin, OUTPUT); + + if (use_pin_cs >= 0) + _ATmega_digitalWrite(use_pin_cs, LOW); + + _spi_is_running = true; + } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + spiInit(0, hint_sck, hint_miso, hint_mosi, hint_cs); + } + void spiClose() { + if (_spi_is_running == false) + _spi_on_error(2); + + if (_spi_cs_pin >= 0) + _ATmega_digitalWrite(_spi_cs_pin, HIGH); + + // Restore pin device states. + // Has to be done in reverse order. + if (_spi_cs_pin >= 0) + _ATmega_restorePinAlternate(_spi_cs_pin, _spi_cs_devstate); + if (_spi_mosi_pin >= 0) + _ATmega_restorePinAlternate(_spi_mosi_pin, _spi_mosi_devstate); + if (_spi_miso_pin >= 0) + _ATmega_restorePinAlternate(_spi_miso_pin, _spi_miso_devstate); + if (_spi_sck_pin >= 0) + _ATmega_restorePinAlternate(_spi_sck_pin, _spi_sck_devstate); + + _spi_is_running = false; + } + + void spiSetBitOrder(int bitOrder) { + _spi_bit_order = bitOrder; + } + + void spiSetClockMode(int clockMode) { + // TODO. + if (clockMode != SPI_CLKMODE_0) { + for (;;) {} + } + } + + void spiEstablish() { /* do nothing */ } + + // Soft SPI receive byte + uint8_t spiRec(uint8_t txval) { + if (txval != 0xFF) { + // TODO. + for (;;) {} + } + uint8_t data = 0; + // no interrupts during byte receive - about 8µs + cli(); + // output pin high - like sending 0xFF + _ATmega_digitalWrite(_spi_mosi_pin, HIGH); + + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + + LOOP_L_N(i, 8) { + _ATmega_digitalWrite(_spi_sck_pin, HIGH); + + nop; // adjust so SCK is nice + nop; + + if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) + { + int bitidx = ( msb ? 7-i : i ); + data |= ( 1 << bitidx ); + } + + _ATmega_digitalWrite(_spi_sck_pin, LOW); + } + + sei(); + return data; + } + + uint16_t spiRec16(uint16_t txval) { + if (txval != 0xFFFF) { + // TODO. + for (;;) {} + } + uint16_t data = 0; + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + // no interrupts during byte receive - about 8µs + cli(); + // output pin high - like sending 0xFF + _ATmega_digitalWrite(_spi_mosi_pin, HIGH); + + LOOP_L_N(i, 16) { + _ATmega_digitalWrite(_spi_sck_pin, HIGH); + + nop; // adjust so SCK is nice + nop; + + if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) + { + int bitidx = ( msb ? 15-i : i ); + data |= ( 1 << bitidx ); + } + + _ATmega_digitalWrite(_spi_sck_pin, LOW); + } + + sei(); + return data; + } + + // Soft SPI read data + void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + for (uint16_t i = 0; i < nbyte; i++) + buf[i] = spiRec(txval); + } + + // Soft SPI send byte + void spiSend(uint8_t data) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + // no interrupts during byte send - about 8µs + cli(); + LOOP_L_N(i, 8) { + int bitidx = ( msb ? 7-i : i ); + _ATmega_digitalWrite(_spi_sck_pin, LOW); + _ATmega_digitalWrite(_spi_mosi_pin, ( data & ( 1 << bitidx )) != 0); + _ATmega_digitalWrite(_spi_sck_pin, HIGH); + } + + nop; // hold SCK high for a few ns + nop; + nop; + nop; + + _ATmega_digitalWrite(_spi_sck_pin, LOW); + + sei(); + } + + void spiSend16(uint16_t v) { + bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + // no interrupts during byte send - about 8µs + cli(); + LOOP_L_N(i, 16) { + int bitidx = ( msb ? 15-i : i ); + _ATmega_digitalWrite(_spi_sck_pin, LOW); + _ATmega_digitalWrite(_spi_mosi_pin, ( v & ( 1 << bitidx )) != 0); + _ATmega_digitalWrite(_spi_sck_pin, HIGH); + } + + nop; // hold SCK high for a few ns + nop; + nop; + nop; + + _ATmega_digitalWrite(_spi_sck_pin, LOW); + + sei(); + } + + // Soft SPI send block + void spiSendBlock(uint8_t token, const uint8_t *buf) { + spiSend(token); + for (uint16_t i = 0; i < 512; i++) + spiSend(buf[i]); + } + + void spiWrite(const uint8_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend(buf[n]); + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + for (uint16_t n = 0; n < cnt; n++) + spiSend16(buf[n]); + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend(val); + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + for (uint16_t n = 0; n < repcnt; n++) + spiSend16(val); + } + +#endif // SOFTWARE_SPI || FORCE_SOFT_SPI + +#endif // __AVR__ diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h index 071f1f629d9e..a8c241e5d080 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -72,1045 +72,601 @@ #define DIO0_WPORT PORTE #define DIO0_DDR DDRE #define DIO0_PWM nullptr +#define PinE0 0 #define DIO1_PIN PINE1 #define DIO1_RPORT PINE #define DIO1_WPORT PORTE #define DIO1_DDR DDRE #define DIO1_PWM nullptr +#define PinE1 1 #define DIO2_PIN PINE4 #define DIO2_RPORT PINE #define DIO2_WPORT PORTE #define DIO2_DDR DDRE #define DIO2_PWM &OCR3BL +#define PinE4 2 #define DIO3_PIN PINE5 #define DIO3_RPORT PINE #define DIO3_WPORT PORTE #define DIO3_DDR DDRE #define DIO3_PWM &OCR3CL +#define PinE5 3 #define DIO4_PIN PING5 #define DIO4_RPORT PING #define DIO4_WPORT PORTG #define DIO4_DDR DDRG #define DIO4_PWM &OCR0B +#define PinG5 4 #define DIO5_PIN PINE3 #define DIO5_RPORT PINE #define DIO5_WPORT PORTE #define DIO5_DDR DDRE #define DIO5_PWM &OCR3AL +#define PinE3 5 #define DIO6_PIN PINH3 #define DIO6_RPORT PINH #define DIO6_WPORT PORTH #define DIO6_DDR DDRH #define DIO6_PWM &OCR4AL +#define PinH3 6 #define DIO7_PIN PINH4 #define DIO7_RPORT PINH #define DIO7_WPORT PORTH #define DIO7_DDR DDRH #define DIO7_PWM &OCR4BL +#define PinH4 7 #define DIO8_PIN PINH5 #define DIO8_RPORT PINH #define DIO8_WPORT PORTH #define DIO8_DDR DDRH #define DIO8_PWM &OCR4CL +#define PinH5 8 #define DIO9_PIN PINH6 #define DIO9_RPORT PINH #define DIO9_WPORT PORTH #define DIO9_DDR DDRH #define DIO9_PWM &OCR2B +#define PinH6 9 #define DIO10_PIN PINB4 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_DDR DDRB #define DIO10_PWM &OCR2A +#define PinB4 10 #define DIO11_PIN PINB5 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_DDR DDRB #define DIO11_PWM nullptr +#define PinB5 11 #define DIO12_PIN PINB6 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_DDR DDRB #define DIO12_PWM nullptr +#define PinB6 12 #define DIO13_PIN PINB7 #define DIO13_RPORT PINB #define DIO13_WPORT PORTB #define DIO13_DDR DDRB #define DIO13_PWM &OCR0A +#define PinB7 13 #define DIO14_PIN PINJ1 #define DIO14_RPORT PINJ #define DIO14_WPORT PORTJ #define DIO14_DDR DDRJ #define DIO14_PWM nullptr +#define PinJ1 14 #define DIO15_PIN PINJ0 #define DIO15_RPORT PINJ #define DIO15_WPORT PORTJ #define DIO15_DDR DDRJ #define DIO15_PWM nullptr +#define PinJ0 15 #define DIO16_PIN PINH1 #define DIO16_RPORT PINH #define DIO16_WPORT PORTH #define DIO16_DDR DDRH #define DIO16_PWM nullptr +#define PinH1 16 #define DIO17_PIN PINH0 #define DIO17_RPORT PINH #define DIO17_WPORT PORTH #define DIO17_DDR DDRH #define DIO17_PWM nullptr +#define PinH0 17 #define DIO18_PIN PIND3 #define DIO18_RPORT PIND #define DIO18_WPORT PORTD #define DIO18_DDR DDRD #define DIO18_PWM nullptr +#define PinD3 18 #define DIO19_PIN PIND2 #define DIO19_RPORT PIND #define DIO19_WPORT PORTD #define DIO19_DDR DDRD #define DIO19_PWM nullptr +#define PinD2 19 #define DIO20_PIN PIND1 #define DIO20_RPORT PIND #define DIO20_WPORT PORTD #define DIO20_DDR DDRD #define DIO20_PWM nullptr +#define PinD1 20 #define DIO21_PIN PIND0 #define DIO21_RPORT PIND #define DIO21_WPORT PORTD #define DIO21_DDR DDRD #define DIO21_PWM nullptr +#define PinD0 21 #define DIO22_PIN PINA0 #define DIO22_RPORT PINA #define DIO22_WPORT PORTA #define DIO22_DDR DDRA #define DIO22_PWM nullptr +#define PinA0 22 #define DIO23_PIN PINA1 #define DIO23_RPORT PINA #define DIO23_WPORT PORTA #define DIO23_DDR DDRA #define DIO23_PWM nullptr +#define PinA1 23 #define DIO24_PIN PINA2 #define DIO24_RPORT PINA #define DIO24_WPORT PORTA #define DIO24_DDR DDRA #define DIO24_PWM nullptr +#define PinA2 24 #define DIO25_PIN PINA3 #define DIO25_RPORT PINA #define DIO25_WPORT PORTA #define DIO25_DDR DDRA #define DIO25_PWM nullptr +#define PinA3 25 #define DIO26_PIN PINA4 #define DIO26_RPORT PINA #define DIO26_WPORT PORTA #define DIO26_DDR DDRA #define DIO26_PWM nullptr +#define PinA4 26 #define DIO27_PIN PINA5 #define DIO27_RPORT PINA #define DIO27_WPORT PORTA #define DIO27_DDR DDRA #define DIO27_PWM nullptr +#define PinA5 27 #define DIO28_PIN PINA6 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_DDR DDRA #define DIO28_PWM nullptr +#define PinA6 28 #define DIO29_PIN PINA7 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_DDR DDRA #define DIO29_PWM nullptr +#define PinA7 29 #define DIO30_PIN PINC7 #define DIO30_RPORT PINC #define DIO30_WPORT PORTC #define DIO30_DDR DDRC #define DIO30_PWM nullptr +#define PinC7 30 #define DIO31_PIN PINC6 #define DIO31_RPORT PINC #define DIO31_WPORT PORTC #define DIO31_DDR DDRC #define DIO31_PWM nullptr +#define PinC6 31 #define DIO32_PIN PINC5 #define DIO32_RPORT PINC #define DIO32_WPORT PORTC #define DIO32_DDR DDRC #define DIO32_PWM nullptr +#define PinC5 32 #define DIO33_PIN PINC4 #define DIO33_RPORT PINC #define DIO33_WPORT PORTC #define DIO33_DDR DDRC #define DIO33_PWM nullptr +#define PinC4 33 #define DIO34_PIN PINC3 #define DIO34_RPORT PINC #define DIO34_WPORT PORTC #define DIO34_DDR DDRC #define DIO34_PWM nullptr +#define PinC3 34 #define DIO35_PIN PINC2 #define DIO35_RPORT PINC #define DIO35_WPORT PORTC #define DIO35_DDR DDRC #define DIO35_PWM nullptr +#define PinC2 35 #define DIO36_PIN PINC1 #define DIO36_RPORT PINC #define DIO36_WPORT PORTC #define DIO36_DDR DDRC #define DIO36_PWM nullptr +#define PinC1 36 #define DIO37_PIN PINC0 #define DIO37_RPORT PINC #define DIO37_WPORT PORTC #define DIO37_DDR DDRC #define DIO37_PWM nullptr +#define PinC0 37 #define DIO38_PIN PIND7 #define DIO38_RPORT PIND #define DIO38_WPORT PORTD #define DIO38_DDR DDRD #define DIO38_PWM nullptr +#define PinD7 38 #define DIO39_PIN PING2 #define DIO39_RPORT PING #define DIO39_WPORT PORTG #define DIO39_DDR DDRG #define DIO39_PWM nullptr +#define PinG2 39 #define DIO40_PIN PING1 #define DIO40_RPORT PING #define DIO40_WPORT PORTG #define DIO40_DDR DDRG #define DIO40_PWM nullptr +#define PinG1 40 #define DIO41_PIN PING0 #define DIO41_RPORT PING #define DIO41_WPORT PORTG #define DIO41_DDR DDRG #define DIO41_PWM nullptr +#define PinG0 41 #define DIO42_PIN PINL7 #define DIO42_RPORT PINL #define DIO42_WPORT PORTL #define DIO42_DDR DDRL #define DIO42_PWM nullptr +#define PinL7 42 #define DIO43_PIN PINL6 #define DIO43_RPORT PINL #define DIO43_WPORT PORTL #define DIO43_DDR DDRL #define DIO43_PWM nullptr +#define PinL6 43 #define DIO44_PIN PINL5 #define DIO44_RPORT PINL #define DIO44_WPORT PORTL #define DIO44_DDR DDRL #define DIO44_PWM &OCR5CL +#define PinL5 44 #define DIO45_PIN PINL4 #define DIO45_RPORT PINL #define DIO45_WPORT PORTL #define DIO45_DDR DDRL #define DIO45_PWM &OCR5BL +#define PinL4 45 #define DIO46_PIN PINL3 #define DIO46_RPORT PINL #define DIO46_WPORT PORTL #define DIO46_DDR DDRL #define DIO46_PWM &OCR5AL +#define PinL3 46 #define DIO47_PIN PINL2 #define DIO47_RPORT PINL #define DIO47_WPORT PORTL #define DIO47_DDR DDRL #define DIO47_PWM nullptr +#define PinL2 47 #define DIO48_PIN PINL1 #define DIO48_RPORT PINL #define DIO48_WPORT PORTL #define DIO48_DDR DDRL #define DIO48_PWM nullptr +#define PinL1 48 #define DIO49_PIN PINL0 #define DIO49_RPORT PINL #define DIO49_WPORT PORTL #define DIO49_DDR DDRL #define DIO49_PWM nullptr +#define PinL0 49 #define DIO50_PIN PINB3 #define DIO50_RPORT PINB #define DIO50_WPORT PORTB #define DIO50_DDR DDRB #define DIO50_PWM nullptr +#define PinB3 50 #define DIO51_PIN PINB2 #define DIO51_RPORT PINB #define DIO51_WPORT PORTB #define DIO51_DDR DDRB #define DIO51_PWM nullptr +#define PinB2 51 #define DIO52_PIN PINB1 #define DIO52_RPORT PINB #define DIO52_WPORT PORTB #define DIO52_DDR DDRB #define DIO52_PWM nullptr +#define PinB1 52 #define DIO53_PIN PINB0 #define DIO53_RPORT PINB #define DIO53_WPORT PORTB #define DIO53_DDR DDRB #define DIO53_PWM nullptr +#define PinB0 53 #define DIO54_PIN PINF0 #define DIO54_RPORT PINF #define DIO54_WPORT PORTF #define DIO54_DDR DDRF #define DIO54_PWM nullptr +#define PinF0 54 #define DIO55_PIN PINF1 #define DIO55_RPORT PINF #define DIO55_WPORT PORTF #define DIO55_DDR DDRF #define DIO55_PWM nullptr +#define PinF1 55 #define DIO56_PIN PINF2 #define DIO56_RPORT PINF #define DIO56_WPORT PORTF #define DIO56_DDR DDRF #define DIO56_PWM nullptr +#define PinF2 56 #define DIO57_PIN PINF3 #define DIO57_RPORT PINF #define DIO57_WPORT PORTF #define DIO57_DDR DDRF #define DIO57_PWM nullptr +#define PinF3 57 #define DIO58_PIN PINF4 #define DIO58_RPORT PINF #define DIO58_WPORT PORTF #define DIO58_DDR DDRF #define DIO58_PWM nullptr +#define PinF4 58 #define DIO59_PIN PINF5 #define DIO59_RPORT PINF #define DIO59_WPORT PORTF #define DIO59_DDR DDRF #define DIO59_PWM nullptr +#define PinF5 59 #define DIO60_PIN PINF6 #define DIO60_RPORT PINF #define DIO60_WPORT PORTF #define DIO60_DDR DDRF #define DIO60_PWM nullptr +#define PinF6 60 #define DIO61_PIN PINF7 #define DIO61_RPORT PINF #define DIO61_WPORT PORTF #define DIO61_DDR DDRF #define DIO61_PWM nullptr +#define PinF7 61 #define DIO62_PIN PINK0 #define DIO62_RPORT PINK #define DIO62_WPORT PORTK #define DIO62_DDR DDRK #define DIO62_PWM nullptr +#define PinK0 62 #define DIO63_PIN PINK1 #define DIO63_RPORT PINK #define DIO63_WPORT PORTK #define DIO63_DDR DDRK #define DIO63_PWM nullptr +#define PinK1 63 #define DIO64_PIN PINK2 #define DIO64_RPORT PINK #define DIO64_WPORT PORTK #define DIO64_DDR DDRK #define DIO64_PWM nullptr +#define PinK2 64 #define DIO65_PIN PINK3 #define DIO65_RPORT PINK #define DIO65_WPORT PORTK #define DIO65_DDR DDRK #define DIO65_PWM nullptr +#define PinK3 65 #define DIO66_PIN PINK4 #define DIO66_RPORT PINK #define DIO66_WPORT PORTK #define DIO66_DDR DDRK #define DIO66_PWM nullptr +#define PinK4 66 #define DIO67_PIN PINK5 #define DIO67_RPORT PINK #define DIO67_WPORT PORTK #define DIO67_DDR DDRK #define DIO67_PWM nullptr +#define PinK5 67 #define DIO68_PIN PINK6 #define DIO68_RPORT PINK #define DIO68_WPORT PORTK #define DIO68_DDR DDRK #define DIO68_PWM nullptr +#define PinK6 68 #define DIO69_PIN PINK7 #define DIO69_RPORT PINK #define DIO69_WPORT PORTK #define DIO69_DDR DDRK #define DIO69_PWM nullptr - -//#define FASTIO_EXT_START 70 -//#define FASTIO_EXT_END 85 +#define PinK7 69 #define DIO70_PIN PING4 #define DIO70_RPORT PING #define DIO70_WPORT PORTG #define DIO70_DDR DDRG #define DIO70_PWM nullptr +#define PinG4 70 #define DIO71_PIN PING3 #define DIO71_RPORT PING #define DIO71_WPORT PORTG #define DIO71_DDR DDRG #define DIO71_PWM nullptr +#define PinG3 71 #define DIO72_PIN PINJ2 #define DIO72_RPORT PINJ #define DIO72_WPORT PORTJ #define DIO72_DDR DDRJ #define DIO72_PWM nullptr +#define PinJ2 72 #define DIO73_PIN PINJ3 #define DIO73_RPORT PINJ #define DIO73_WPORT PORTJ #define DIO73_DDR DDRJ #define DIO73_PWM nullptr +#define PinJ3 73 #define DIO74_PIN PINJ7 #define DIO74_RPORT PINJ #define DIO74_WPORT PORTJ #define DIO74_DDR DDRJ #define DIO74_PWM nullptr +#define PinJ7 74 #define DIO75_PIN PINJ4 #define DIO75_RPORT PINJ #define DIO75_WPORT PORTJ #define DIO75_DDR DDRJ #define DIO75_PWM nullptr +#define PinJ4 75 #define DIO76_PIN PINJ5 #define DIO76_RPORT PINJ #define DIO76_WPORT PORTJ #define DIO76_DDR DDRJ #define DIO76_PWM nullptr +#define PinJ5 76 #define DIO77_PIN PINJ6 #define DIO77_RPORT PINJ #define DIO77_WPORT PORTJ #define DIO77_DDR DDRJ #define DIO77_PWM nullptr +#define PinJ6 77 #define DIO78_PIN PINE2 #define DIO78_RPORT PINE #define DIO78_WPORT PORTE #define DIO78_DDR DDRE #define DIO78_PWM nullptr +#define PinE2 78 #define DIO79_PIN PINE6 #define DIO79_RPORT PINE #define DIO79_WPORT PORTE #define DIO79_DDR DDRE #define DIO79_PWM nullptr +#define PinE6 79 #define DIO80_PIN PINE7 #define DIO80_RPORT PINE #define DIO80_WPORT PORTE #define DIO80_DDR DDRE #define DIO80_PWM nullptr +#define PinE7 80 #define DIO81_PIN PIND4 #define DIO81_RPORT PIND #define DIO81_WPORT PORTD #define DIO81_DDR DDRD #define DIO81_PWM nullptr +#define PinD4 81 #define DIO82_PIN PIND5 #define DIO82_RPORT PIND #define DIO82_WPORT PORTD #define DIO82_DDR DDRD #define DIO82_PWM nullptr +#define PinD5 82 #define DIO83_PIN PIND6 #define DIO83_RPORT PIND #define DIO83_WPORT PORTD #define DIO83_DDR DDRD #define DIO83_PWM nullptr +#define PinD6 83 #define DIO84_PIN PINH2 #define DIO84_RPORT PINH #define DIO84_WPORT PORTH #define DIO84_DDR DDRH #define DIO84_PWM nullptr +#define PinH2 84 #define DIO85_PIN PINH7 #define DIO85_RPORT PINH #define DIO85_WPORT PORTH #define DIO85_DDR DDRH #define DIO85_PWM nullptr +#define PinH7 85 -#define DIO_NUM 86 - -#undef PA0 -#define PA0_PIN PINA0 -#define PA0_RPORT PINA -#define PA0_WPORT PORTA -#define PA0_DDR DDRA -#define PA0_PWM nullptr -#undef PA1 -#define PA1_PIN PINA1 -#define PA1_RPORT PINA -#define PA1_WPORT PORTA -#define PA1_DDR DDRA -#define PA1_PWM nullptr -#undef PA2 -#define PA2_PIN PINA2 -#define PA2_RPORT PINA -#define PA2_WPORT PORTA -#define PA2_DDR DDRA -#define PA2_PWM nullptr -#undef PA3 -#define PA3_PIN PINA3 -#define PA3_RPORT PINA -#define PA3_WPORT PORTA -#define PA3_DDR DDRA -#define PA3_PWM nullptr -#undef PA4 -#define PA4_PIN PINA4 -#define PA4_RPORT PINA -#define PA4_WPORT PORTA -#define PA4_DDR DDRA -#define PA4_PWM nullptr -#undef PA5 -#define PA5_PIN PINA5 -#define PA5_RPORT PINA -#define PA5_WPORT PORTA -#define PA5_DDR DDRA -#define PA5_PWM nullptr -#undef PA6 -#define PA6_PIN PINA6 -#define PA6_RPORT PINA -#define PA6_WPORT PORTA -#define PA6_DDR DDRA -#define PA6_PWM nullptr -#undef PA7 -#define PA7_PIN PINA7 -#define PA7_RPORT PINA -#define PA7_WPORT PORTA -#define PA7_DDR DDRA -#define PA7_PWM nullptr - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_DDR DDRB -#define PB0_PWM nullptr -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_DDR DDRB -#define PB1_PWM nullptr -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_DDR DDRB -#define PB2_PWM nullptr -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_DDR DDRB -#define PB3_PWM nullptr -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_DDR DDRB -#define PB4_PWM &OCR2A -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_DDR DDRB -#define PB5_PWM nullptr -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_DDR DDRB -#define PB6_PWM nullptr -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_DDR DDRB -#define PB7_PWM &OCR0A - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_DDR DDRC -#define PC0_PWM nullptr -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_DDR DDRC -#define PC1_PWM nullptr -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_DDR DDRC -#define PC2_PWM nullptr -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_DDR DDRC -#define PC3_PWM nullptr -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_DDR DDRC -#define PC4_PWM nullptr -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_DDR DDRC -#define PC5_PWM nullptr -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_DDR DDRC -#define PC6_PWM nullptr -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_DDR DDRC -#define PC7_PWM nullptr - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_DDR DDRD -#define PD0_PWM nullptr -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_DDR DDRD -#define PD1_PWM nullptr -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_DDR DDRD -#define PD2_PWM nullptr -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_DDR DDRD -#define PD3_PWM nullptr -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_DDR DDRD -#define PD4_PWM nullptr -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_DDR DDRD -#define PD5_PWM nullptr -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_DDR DDRD -#define PD6_PWM nullptr -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_DDR DDRD -#define PD7_PWM nullptr - -#undef PE0 -#define PE0_PIN PINE0 -#define PE0_RPORT PINE -#define PE0_WPORT PORTE -#define PE0_DDR DDRE -#define PE0_PWM nullptr -#undef PE1 -#define PE1_PIN PINE1 -#define PE1_RPORT PINE -#define PE1_WPORT PORTE -#define PE1_DDR DDRE -#define PE1_PWM nullptr -#undef PE2 -#define PE2_PIN PINE2 -#define PE2_RPORT PINE -#define PE2_WPORT PORTE -#define PE2_DDR DDRE -#define PE2_PWM nullptr -#undef PE3 -#define PE3_PIN PINE3 -#define PE3_RPORT PINE -#define PE3_WPORT PORTE -#define PE3_DDR DDRE -#define PE3_PWM &OCR3AL -#undef PE4 -#define PE4_PIN PINE4 -#define PE4_RPORT PINE -#define PE4_WPORT PORTE -#define PE4_DDR DDRE -#define PE4_PWM &OCR3BL -#undef PE5 -#define PE5_PIN PINE5 -#define PE5_RPORT PINE -#define PE5_WPORT PORTE -#define PE5_DDR DDRE -#define PE5_PWM &OCR3CL -#undef PE6 -#define PE6_PIN PINE6 -#define PE6_RPORT PINE -#define PE6_WPORT PORTE -#define PE6_DDR DDRE -#define PE6_PWM nullptr -#undef PE7 -#define PE7_PIN PINE7 -#define PE7_RPORT PINE -#define PE7_WPORT PORTE -#define PE7_DDR DDRE -#define PE7_PWM nullptr - -#undef PF0 -#define PF0_PIN PINF0 -#define PF0_RPORT PINF -#define PF0_WPORT PORTF -#define PF0_DDR DDRF -#define PF0_PWM nullptr -#undef PF1 -#define PF1_PIN PINF1 -#define PF1_RPORT PINF -#define PF1_WPORT PORTF -#define PF1_DDR DDRF -#define PF1_PWM nullptr -#undef PF2 -#define PF2_PIN PINF2 -#define PF2_RPORT PINF -#define PF2_WPORT PORTF -#define PF2_DDR DDRF -#define PF2_PWM nullptr -#undef PF3 -#define PF3_PIN PINF3 -#define PF3_RPORT PINF -#define PF3_WPORT PORTF -#define PF3_DDR DDRF -#define PF3_PWM nullptr -#undef PF4 -#define PF4_PIN PINF4 -#define PF4_RPORT PINF -#define PF4_WPORT PORTF -#define PF4_DDR DDRF -#define PF4_PWM nullptr -#undef PF5 -#define PF5_PIN PINF5 -#define PF5_RPORT PINF -#define PF5_WPORT PORTF -#define PF5_DDR DDRF -#define PF5_PWM nullptr -#undef PF6 -#define PF6_PIN PINF6 -#define PF6_RPORT PINF -#define PF6_WPORT PORTF -#define PF6_DDR DDRF -#define PF6_PWM nullptr -#undef PF7 -#define PF7_PIN PINF7 -#define PF7_RPORT PINF -#define PF7_WPORT PORTF -#define PF7_DDR DDRF -#define PF7_PWM nullptr - -#undef PG0 -#define PG0_PIN PING0 -#define PG0_RPORT PING -#define PG0_WPORT PORTG -#define PG0_DDR DDRG -#define PG0_PWM nullptr -#undef PG1 -#define PG1_PIN PING1 -#define PG1_RPORT PING -#define PG1_WPORT PORTG -#define PG1_DDR DDRG -#define PG1_PWM nullptr -#undef PG2 -#define PG2_PIN PING2 -#define PG2_RPORT PING -#define PG2_WPORT PORTG -#define PG2_DDR DDRG -#define PG2_PWM nullptr -#undef PG3 -#define PG3_PIN PING3 -#define PG3_RPORT PING -#define PG3_WPORT PORTG -#define PG3_DDR DDRG -#define PG3_PWM nullptr -#undef PG4 -#define PG4_PIN PING4 -#define PG4_RPORT PING -#define PG4_WPORT PORTG -#define PG4_DDR DDRG -#define PG4_PWM nullptr -#undef PG5 -#define PG5_PIN PING5 -#define PG5_RPORT PING -#define PG5_WPORT PORTG -#define PG5_DDR DDRG -#define PG5_PWM &OCR0B - -#undef PH0 -#define PH0_PIN PINH0 -#define PH0_RPORT PINH -#define PH0_WPORT PORTH -#define PH0_DDR DDRH -#define PH0_PWM nullptr -#undef PH1 -#define PH1_PIN PINH1 -#define PH1_RPORT PINH -#define PH1_WPORT PORTH -#define PH1_DDR DDRH -#define PH1_PWM nullptr -#undef PH2 -#define PH2_PIN PINH2 -#define PH2_RPORT PINH -#define PH2_WPORT PORTH -#define PH2_DDR DDRH -#define PH2_PWM nullptr -#undef PH3 -#define PH3_PIN PINH3 -#define PH3_RPORT PINH -#define PH3_WPORT PORTH -#define PH3_DDR DDRH -#define PH3_PWM &OCR4AL -#undef PH4 -#define PH4_PIN PINH4 -#define PH4_RPORT PINH -#define PH4_WPORT PORTH -#define PH4_DDR DDRH -#define PH4_PWM &OCR4BL -#undef PH5 -#define PH5_PIN PINH5 -#define PH5_RPORT PINH -#define PH5_WPORT PORTH -#define PH5_DDR DDRH -#define PH5_PWM &OCR4CL -#undef PH6 -#define PH6_PIN PINH6 -#define PH6_RPORT PINH -#define PH6_WPORT PORTH -#define PH6_DDR DDRH -#define PH6_PWM &OCR2B -#undef PH7 -#define PH7_PIN PINH7 -#define PH7_RPORT PINH -#define PH7_WPORT PORTH -#define PH7_DDR DDRH -#define PH7_PWM nullptr - -#undef PJ0 -#define PJ0_PIN PINJ0 -#define PJ0_RPORT PINJ -#define PJ0_WPORT PORTJ -#define PJ0_DDR DDRJ -#define PJ0_PWM nullptr -#undef PJ1 -#define PJ1_PIN PINJ1 -#define PJ1_RPORT PINJ -#define PJ1_WPORT PORTJ -#define PJ1_DDR DDRJ -#define PJ1_PWM nullptr -#undef PJ2 -#define PJ2_PIN PINJ2 -#define PJ2_RPORT PINJ -#define PJ2_WPORT PORTJ -#define PJ2_DDR DDRJ -#define PJ2_PWM nullptr -#undef PJ3 -#define PJ3_PIN PINJ3 -#define PJ3_RPORT PINJ -#define PJ3_WPORT PORTJ -#define PJ3_DDR DDRJ -#define PJ3_PWM nullptr -#undef PJ4 -#define PJ4_PIN PINJ4 -#define PJ4_RPORT PINJ -#define PJ4_WPORT PORTJ -#define PJ4_DDR DDRJ -#define PJ4_PWM nullptr -#undef PJ5 -#define PJ5_PIN PINJ5 -#define PJ5_RPORT PINJ -#define PJ5_WPORT PORTJ -#define PJ5_DDR DDRJ -#define PJ5_PWM nullptr -#undef PJ6 -#define PJ6_PIN PINJ6 -#define PJ6_RPORT PINJ -#define PJ6_WPORT PORTJ -#define PJ6_DDR DDRJ -#define PJ6_PWM nullptr -#undef PJ7 -#define PJ7_PIN PINJ7 -#define PJ7_RPORT PINJ -#define PJ7_WPORT PORTJ -#define PJ7_DDR DDRJ -#define PJ7_PWM nullptr - -#undef PK0 -#define PK0_PIN PINK0 -#define PK0_RPORT PINK -#define PK0_WPORT PORTK -#define PK0_DDR DDRK -#define PK0_PWM nullptr -#undef PK1 -#define PK1_PIN PINK1 -#define PK1_RPORT PINK -#define PK1_WPORT PORTK -#define PK1_DDR DDRK -#define PK1_PWM nullptr -#undef PK2 -#define PK2_PIN PINK2 -#define PK2_RPORT PINK -#define PK2_WPORT PORTK -#define PK2_DDR DDRK -#define PK2_PWM nullptr -#undef PK3 -#define PK3_PIN PINK3 -#define PK3_RPORT PINK -#define PK3_WPORT PORTK -#define PK3_DDR DDRK -#define PK3_PWM nullptr -#undef PK4 -#define PK4_PIN PINK4 -#define PK4_RPORT PINK -#define PK4_WPORT PORTK -#define PK4_DDR DDRK -#define PK4_PWM nullptr -#undef PK5 -#define PK5_PIN PINK5 -#define PK5_RPORT PINK -#define PK5_WPORT PORTK -#define PK5_DDR DDRK -#define PK5_PWM nullptr -#undef PK6 -#define PK6_PIN PINK6 -#define PK6_RPORT PINK -#define PK6_WPORT PORTK -#define PK6_DDR DDRK -#define PK6_PWM nullptr -#undef PK7 -#define PK7_PIN PINK7 -#define PK7_RPORT PINK -#define PK7_WPORT PORTK -#define PK7_DDR DDRK -#define PK7_PWM nullptr - -#undef PL0 -#define PL0_PIN PINL0 -#define PL0_RPORT PINL -#define PL0_WPORT PORTL -#define PL0_DDR DDRL -#define PL0_PWM nullptr -#undef PL1 -#define PL1_PIN PINL1 -#define PL1_RPORT PINL -#define PL1_WPORT PORTL -#define PL1_DDR DDRL -#define PL1_PWM nullptr -#undef PL2 -#define PL2_PIN PINL2 -#define PL2_RPORT PINL -#define PL2_WPORT PORTL -#define PL2_DDR DDRL -#define PL2_PWM nullptr -#undef PL3 -#define PL3_PIN PINL3 -#define PL3_RPORT PINL -#define PL3_WPORT PORTL -#define PL3_DDR DDRL -#define PL3_PWM &OCR5AL -#undef PL4 -#define PL4_PIN PINL4 -#define PL4_RPORT PINL -#define PL4_WPORT PORTL -#define PL4_DDR DDRL -#define PL4_PWM &OCR5BL -#undef PL5 -#define PL5_PIN PINL5 -#define PL5_RPORT PINL -#define PL5_WPORT PORTL -#define PL5_DDR DDRL -#define PL5_PWM &OCR5CL -#undef PL6 -#define PL6_PIN PINL6 -#define PL6_RPORT PINL -#define PL6_WPORT PORTL -#define PL6_DDR DDRL -#define PL6_PWM nullptr -#undef PL7 -#define PL7_PIN PINL7 -#define PL7_RPORT PINL -#define PL7_WPORT PORTL -#define PL7_DDR DDRL -#define PL7_PWM nullptr +#define DIO_NUM 86 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h index eec0b663178b..0a5bb350403b 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h @@ -64,654 +64,377 @@ #define DIO0_WPORT PORTE #define DIO0_DDR DDRE #define DIO0_PWM nullptr +#define PinE0 0 #define DIO1_PIN PINE1 #define DIO1_RPORT PINE #define DIO1_WPORT PORTE #define DIO1_DDR DDRE #define DIO1_PWM nullptr +#define PinE1 1 #define DIO2_PIN PINE4 #define DIO2_RPORT PINE #define DIO2_WPORT PORTE #define DIO2_DDR DDRE #define DIO2_PWM &OCR3BL +#define PinE4 2 #define DIO3_PIN PINE5 #define DIO3_RPORT PINE #define DIO3_WPORT PORTE #define DIO3_DDR DDRE #define DIO3_PWM &OCR3CL +#define PinE5 3 #define DIO4_PIN PING5 #define DIO4_RPORT PING #define DIO4_WPORT PORTG #define DIO4_DDR DDRG #define DIO4_PWM &OCR0B +#define PinG5 4 #define DIO5_PIN PINE3 #define DIO5_RPORT PINE #define DIO5_WPORT PORTE #define DIO5_DDR DDRE #define DIO5_PWM &OCR3AL +#define PinE3 5 #define DIO6_PIN PINB4 #define DIO6_RPORT PINB #define DIO6_WPORT PORTB #define DIO6_DDR DDRB #define DIO6_PWM &OCR2AL +#define PinB4 6 #define DIO7_PIN PINB5 #define DIO7_RPORT PINB #define DIO7_WPORT PORTB #define DIO7_DDR DDRB #define DIO7_PWM &OCR1AL +#define PinB5 7 #define DIO8_PIN PINB6 #define DIO8_RPORT PINB #define DIO8_WPORT PORTB #define DIO8_DDR DDRB #define DIO8_PWM &OCR1BL +#define PinB6 8 #define DIO9_PIN PINB7 #define DIO9_RPORT PINB #define DIO9_WPORT PORTB #define DIO9_DDR DDRB #define DIO9_PWM &OCR0AL +#define PinB7 9 #define DIO10_PIN PINB1 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_DDR DDRB #define DIO10_PWM nullptr +#define PinB1 10 #define DIO11_PIN PINB2 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_DDR DDRB #define DIO11_PWM nullptr +#define PinB2 11 #define DIO12_PIN PINB3 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_DDR DDRB #define DIO12_PWM nullptr +#define PinB3 12 #define DIO13_PIN PINE2 #define DIO13_RPORT PINE #define DIO13_WPORT PORTE #define DIO13_DDR DDRE #define DIO13_PWM nullptr +#define PinE2 13 #define DIO14_PIN PINE6 #define DIO14_RPORT PINE #define DIO14_WPORT PORTE #define DIO14_DDR DDRE #define DIO14_PWM nullptr +#define PinE6 14 #define DIO15_PIN PINE7 #define DIO15_RPORT PINE #define DIO15_WPORT PORTE #define DIO15_DDR DDRE #define DIO15_PWM nullptr +#define PinE7 15 #define DIO16_PIN PINB0 #define DIO16_RPORT PINB #define DIO16_WPORT PORTB #define DIO16_DDR DDRB #define DIO16_PWM nullptr +#define PinB0 16 #define DIO17_PIN PIND0 #define DIO17_RPORT PIND #define DIO17_WPORT PORTD #define DIO17_DDR DDRD #define DIO17_PWM nullptr +#define PinD0 17 #define DIO18_PIN PIND1 #define DIO18_RPORT PIND #define DIO18_WPORT PORTD #define DIO18_DDR DDRD #define DIO18_PWM nullptr +#define PinD1 18 #define DIO19_PIN PIND2 #define DIO19_RPORT PIND #define DIO19_WPORT PORTD #define DIO19_DDR DDRD #define DIO19_PWM nullptr +#define PinD2 19 #define DIO20_PIN PIND3 #define DIO20_RPORT PIND #define DIO20_WPORT PORTD #define DIO20_DDR DDRD #define DIO20_PWM nullptr +#define PinD3 20 #define DIO21_PIN PIND4 #define DIO21_RPORT PIND #define DIO21_WPORT PORTD #define DIO21_DDR DDRD #define DIO21_PWM nullptr +#define PinD4 21 #define DIO22_PIN PIND5 #define DIO22_RPORT PIND #define DIO22_WPORT PORTD #define DIO22_DDR DDRD #define DIO22_PWM nullptr +#define PinD5 22 #define DIO23_PIN PIND6 #define DIO23_RPORT PIND #define DIO23_WPORT PORTD #define DIO23_DDR DDRD #define DIO23_PWM nullptr +#define PinD6 23 #define DIO24_PIN PIND7 #define DIO24_RPORT PIND #define DIO24_WPORT PORTD #define DIO24_DDR DDRD #define DIO24_PWM nullptr +#define PinD7 24 #define DIO25_PIN PING0 #define DIO25_RPORT PING #define DIO25_WPORT PORTG #define DIO25_DDR DDRG #define DIO25_PWM nullptr +#define PinG0 25 #define DIO26_PIN PING1 #define DIO26_RPORT PING #define DIO26_WPORT PORTG #define DIO26_DDR DDRG #define DIO26_PWM nullptr +#define PinG1 26 #define DIO27_PIN PING2 #define DIO27_RPORT PING #define DIO27_WPORT PORTG #define DIO27_DDR DDRG #define DIO27_PWM nullptr +#define PinG2 27 #define DIO28_PIN PING3 #define DIO28_RPORT PING #define DIO28_WPORT PORTG #define DIO28_DDR DDRG #define DIO28_PWM nullptr +#define PinG3 28 #define DIO29_PIN PING4 #define DIO29_RPORT PING #define DIO29_WPORT PORTG #define DIO29_DDR DDRG #define DIO29_PWM nullptr +#define PinG4 29 #define DIO30_PIN PINC0 #define DIO30_RPORT PINC #define DIO30_WPORT PORTC #define DIO30_DDR DDRC #define DIO30_PWM nullptr +#define PinC0 30 #define DIO31_PIN PINC1 #define DIO31_RPORT PINC #define DIO31_WPORT PORTC #define DIO31_DDR DDRC #define DIO31_PWM nullptr +#define PinC1 31 #define DIO32_PIN PINC2 #define DIO32_RPORT PINC #define DIO32_WPORT PORTC #define DIO32_DDR DDRC #define DIO32_PWM nullptr +#define PinC2 32 #define DIO33_PIN PINC3 #define DIO33_RPORT PINC #define DIO33_WPORT PORTC #define DIO33_DDR DDRC #define DIO33_PWM nullptr +#define PinC3 33 #define DIO34_PIN PINC4 #define DIO34_RPORT PINC #define DIO34_WPORT PORTC #define DIO34_DDR DDRC #define DIO34_PWM nullptr +#define PinC4 34 #define DIO35_PIN PINC5 #define DIO35_RPORT PINC #define DIO35_WPORT PORTC #define DIO35_DDR DDRC #define DIO35_PWM nullptr +#define PinC5 35 #define DIO36_PIN PINC6 #define DIO36_RPORT PINC #define DIO36_WPORT PORTC #define DIO36_DDR DDRC #define DIO36_PWM nullptr +#define PinC6 36 #define DIO37_PIN PINC7 #define DIO37_RPORT PINC #define DIO37_WPORT PORTC #define DIO37_DDR DDRC #define DIO37_PWM nullptr +#define PinC7 37 #define DIO38_PIN PINA0 #define DIO38_RPORT PINA #define DIO38_WPORT PORTA #define DIO38_DDR DDRA #define DIO38_PWM nullptr +#define PinA0 38 #define DIO39_PIN PINA1 #define DIO39_RPORT PINA #define DIO39_WPORT PORTA #define DIO39_DDR DDRA #define DIO39_PWM nullptr +#define PinA1 39 #define DIO40_PIN PINA2 #define DIO40_RPORT PINA #define DIO40_WPORT PORTA #define DIO40_DDR DDRA #define DIO40_PWM nullptr +#define PinA2 40 #define DIO41_PIN PINA3 #define DIO41_RPORT PINA #define DIO41_WPORT PORTA #define DIO41_DDR DDRA #define DIO41_PWM nullptr +#define PinA3 41 #define DIO42_PIN PINA4 #define DIO42_RPORT PINA #define DIO42_WPORT PORTA #define DIO42_DDR DDRA #define DIO42_PWM nullptr +#define PinA4 42 #define DIO43_PIN PINA5 #define DIO43_RPORT PINA #define DIO43_WPORT PORTA #define DIO43_DDR DDRA #define DIO43_PWM nullptr +#define PinA5 43 #define DIO44_PIN PINA6 #define DIO44_RPORT PINA #define DIO44_WPORT PORTA #define DIO44_DDR DDRA #define DIO44_PWM nullptr +#define PinA6 44 #define DIO45_PIN PINA7 #define DIO45_RPORT PINA #define DIO45_WPORT PORTA #define DIO45_DDR DDRA #define DIO45_PWM nullptr +#define PinA7 45 #define DIO46_PIN PINF0 #define DIO46_RPORT PINF #define DIO46_WPORT PORTF #define DIO46_DDR DDRF #define DIO46_PWM nullptr +#define PinF0 46 #define DIO47_PIN PINF1 #define DIO47_RPORT PINF #define DIO47_WPORT PORTF #define DIO47_DDR DDRF #define DIO47_PWM nullptr +#define PinF1 47 #define DIO48_PIN PINF2 #define DIO48_RPORT PINF #define DIO48_WPORT PORTF #define DIO48_DDR DDRF #define DIO48_PWM nullptr +#define PinF2 48 #define DIO49_PIN PINF3 #define DIO49_RPORT PINF #define DIO49_WPORT PORTF #define DIO49_DDR DDRF #define DIO49_PWM nullptr +#define PinF3 49 #define DIO50_PIN PINF4 #define DIO50_RPORT PINF #define DIO50_WPORT PORTF #define DIO50_DDR DDRF #define DIO50_PWM nullptr +#define PinF4 50 #define DIO51_PIN PINF5 #define DIO51_RPORT PINF #define DIO51_WPORT PORTF #define DIO51_DDR DDRF #define DIO51_PWM nullptr +#define PinF5 51 #define DIO52_PIN PINF6 #define DIO52_RPORT PINF #define DIO52_WPORT PORTF #define DIO52_DDR DDRF #define DIO52_PWM nullptr +#define PinF6 52 #define DIO53_PIN PINF7 #define DIO53_RPORT PINF #define DIO53_WPORT PORTF #define DIO53_DDR DDRF #define DIO53_PWM nullptr +#define PinF7 53 -#define DIO_NUM 54 - -#undef PA0 -#define PA0_PIN PINA0 -#define PA0_RPORT PINA -#define PA0_WPORT PORTA -#define PA0_DDR DDRA -#define PA0_PWM nullptr -#undef PA1 -#define PA1_PIN PINA1 -#define PA1_RPORT PINA -#define PA1_WPORT PORTA -#define PA1_DDR DDRA -#define PA1_PWM nullptr -#undef PA2 -#define PA2_PIN PINA2 -#define PA2_RPORT PINA -#define PA2_WPORT PORTA -#define PA2_DDR DDRA -#define PA2_PWM nullptr -#undef PA3 -#define PA3_PIN PINA3 -#define PA3_RPORT PINA -#define PA3_WPORT PORTA -#define PA3_DDR DDRA -#define PA3_PWM nullptr -#undef PA4 -#define PA4_PIN PINA4 -#define PA4_RPORT PINA -#define PA4_WPORT PORTA -#define PA4_DDR DDRA -#define PA4_PWM nullptr -#undef PA5 -#define PA5_PIN PINA5 -#define PA5_RPORT PINA -#define PA5_WPORT PORTA -#define PA5_DDR DDRA -#define PA5_PWM nullptr -#undef PA6 -#define PA6_PIN PINA6 -#define PA6_RPORT PINA -#define PA6_WPORT PORTA -#define PA6_DDR DDRA -#define PA6_PWM nullptr -#undef PA7 -#define PA7_PIN PINA7 -#define PA7_RPORT PINA -#define PA7_WPORT PORTA -#define PA7_DDR DDRA -#define PA7_PWM nullptr - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_DDR DDRB -#define PB0_PWM nullptr -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_DDR DDRB -#define PB1_PWM nullptr -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_DDR DDRB -#define PB2_PWM nullptr -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_DDR DDRB -#define PB3_PWM nullptr -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_DDR DDRB -#define PB4_PWM &OCR2A -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_DDR DDRB -#define PB5_PWM nullptr -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_DDR DDRB -#define PB6_PWM nullptr -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_DDR DDRB -#define PB7_PWM &OCR0A - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_DDR DDRC -#define PC0_PWM nullptr -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_DDR DDRC -#define PC1_PWM nullptr -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_DDR DDRC -#define PC2_PWM nullptr -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_DDR DDRC -#define PC3_PWM nullptr -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_DDR DDRC -#define PC4_PWM nullptr -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_DDR DDRC -#define PC5_PWM nullptr -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_DDR DDRC -#define PC6_PWM nullptr -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_DDR DDRC -#define PC7_PWM nullptr - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_DDR DDRD -#define PD0_PWM nullptr -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_DDR DDRD -#define PD1_PWM nullptr -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_DDR DDRD -#define PD2_PWM nullptr -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_DDR DDRD -#define PD3_PWM nullptr -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_DDR DDRD -#define PD4_PWM nullptr -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_DDR DDRD -#define PD5_PWM nullptr -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_DDR DDRD -#define PD6_PWM nullptr -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_DDR DDRD -#define PD7_PWM nullptr - -#undef PE0 -#define PE0_PIN PINE0 -#define PE0_RPORT PINE -#define PE0_WPORT PORTE -#define PE0_DDR DDRE -#define PE0_PWM nullptr -#undef PE1 -#define PE1_PIN PINE1 -#define PE1_RPORT PINE -#define PE1_WPORT PORTE -#define PE1_DDR DDRE -#define PE1_PWM nullptr -#undef PE2 -#define PE2_PIN PINE2 -#define PE2_RPORT PINE -#define PE2_WPORT PORTE -#define PE2_DDR DDRE -#define PE2_PWM nullptr -#undef PE3 -#define PE3_PIN PINE3 -#define PE3_RPORT PINE -#define PE3_WPORT PORTE -#define PE3_DDR DDRE -#define PE3_PWM &OCR3AL -#undef PE4 -#define PE4_PIN PINE4 -#define PE4_RPORT PINE -#define PE4_WPORT PORTE -#define PE4_DDR DDRE -#define PE4_PWM &OCR3BL -#undef PE5 -#define PE5_PIN PINE5 -#define PE5_RPORT PINE -#define PE5_WPORT PORTE -#define PE5_DDR DDRE -#define PE5_PWM &OCR3CL -#undef PE6 -#define PE6_PIN PINE6 -#define PE6_RPORT PINE -#define PE6_WPORT PORTE -#define PE6_DDR DDRE -#define PE6_PWM nullptr -#undef PE7 -#define PE7_PIN PINE7 -#define PE7_RPORT PINE -#define PE7_WPORT PORTE -#define PE7_DDR DDRE -#define PE7_PWM nullptr - -#undef PF0 -#define PF0_PIN PINF0 -#define PF0_RPORT PINF -#define PF0_WPORT PORTF -#define PF0_DDR DDRF -#define PF0_PWM nullptr -#undef PF1 -#define PF1_PIN PINF1 -#define PF1_RPORT PINF -#define PF1_WPORT PORTF -#define PF1_DDR DDRF -#define PF1_PWM nullptr -#undef PF2 -#define PF2_PIN PINF2 -#define PF2_RPORT PINF -#define PF2_WPORT PORTF -#define PF2_DDR DDRF -#define PF2_PWM nullptr -#undef PF3 -#define PF3_PIN PINF3 -#define PF3_RPORT PINF -#define PF3_WPORT PORTF -#define PF3_DDR DDRF -#define PF3_PWM nullptr -#undef PF4 -#define PF4_PIN PINF4 -#define PF4_RPORT PINF -#define PF4_WPORT PORTF -#define PF4_DDR DDRF -#define PF4_PWM nullptr -#undef PF5 -#define PF5_PIN PINF5 -#define PF5_RPORT PINF -#define PF5_WPORT PORTF -#define PF5_DDR DDRF -#define PF5_PWM nullptr -#undef PF6 -#define PF6_PIN PINF6 -#define PF6_RPORT PINF -#define PF6_WPORT PORTF -#define PF6_DDR DDRF -#define PF6_PWM nullptr -#undef PF7 -#define PF7_PIN PINF7 -#define PF7_RPORT PINF -#define PF7_WPORT PORTF -#define PF7_DDR DDRF -#define PF7_PWM nullptr - -#undef PG0 -#define PG0_PIN PING0 -#define PG0_RPORT PING -#define PG0_WPORT PORTG -#define PG0_DDR DDRG -#define PG0_PWM nullptr -#undef PG1 -#define PG1_PIN PING1 -#define PG1_RPORT PING -#define PG1_WPORT PORTG -#define PG1_DDR DDRG -#define PG1_PWM nullptr -#undef PG2 -#define PG2_PIN PING2 -#define PG2_RPORT PING -#define PG2_WPORT PORTG -#define PG2_DDR DDRG -#define PG2_PWM nullptr -#undef PG3 -#define PG3_PIN PING3 -#define PG3_RPORT PING -#define PG3_WPORT PORTG -#define PG3_DDR DDRG -#define PG3_PWM nullptr -#undef PG4 -#define PG4_PIN PING4 -#define PG4_RPORT PING -#define PG4_WPORT PORTG -#define PG4_DDR DDRG -#define PG4_PWM nullptr -#undef PG5 -#define PG5_PIN PING5 -#define PG5_RPORT PING -#define PG5_WPORT PORTG -#define PG5_DDR DDRG -#define PG5_PWM &OCR0B +#define DIO_NUM 54 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h index ece6deb6311f..8c6a343731ca 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_168.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h @@ -61,299 +61,153 @@ #define DIO0_WPORT PORTD #define DIO0_DDR DDRD #define DIO0_PWM nullptr +#define PinD0 0 #define DIO1_PIN PIND1 #define DIO1_RPORT PIND #define DIO1_WPORT PORTD #define DIO1_DDR DDRD #define DIO1_PWM nullptr +#define PinD1 1 #define DIO2_PIN PIND2 #define DIO2_RPORT PIND #define DIO2_WPORT PORTD #define DIO2_DDR DDRD #define DIO2_PWM nullptr +#define PinD2 2 #define DIO3_PIN PIND3 #define DIO3_RPORT PIND #define DIO3_WPORT PORTD #define DIO3_DDR DDRD #define DIO3_PWM &OCR2B +#define PinD3 3 #define DIO4_PIN PIND4 #define DIO4_RPORT PIND #define DIO4_WPORT PORTD #define DIO4_DDR DDRD #define DIO4_PWM nullptr +#define PinD4 4 #define DIO5_PIN PIND5 #define DIO5_RPORT PIND #define DIO5_WPORT PORTD #define DIO5_DDR DDRD #define DIO5_PWM &OCR0B +#define PinD5 5 #define DIO6_PIN PIND6 #define DIO6_RPORT PIND #define DIO6_WPORT PORTD #define DIO6_DDR DDRD #define DIO6_PWM &OCR0A +#define PinD6 6 #define DIO7_PIN PIND7 #define DIO7_RPORT PIND #define DIO7_WPORT PORTD #define DIO7_DDR DDRD #define DIO7_PWM nullptr +#define PinD7 7 #define DIO8_PIN PINB0 #define DIO8_RPORT PINB #define DIO8_WPORT PORTB #define DIO8_DDR DDRB #define DIO8_PWM nullptr +#define PinB0 8 #define DIO9_PIN PINB1 #define DIO9_RPORT PINB #define DIO9_WPORT PORTB #define DIO9_DDR DDRB #define DIO9_PWM nullptr +#define PinB1 9 #define DIO10_PIN PINB2 #define DIO10_RPORT PINB #define DIO10_WPORT PORTB #define DIO10_DDR DDRB #define DIO10_PWM nullptr +#define PinB2 10 #define DIO11_PIN PINB3 #define DIO11_RPORT PINB #define DIO11_WPORT PORTB #define DIO11_DDR DDRB #define DIO11_PWM &OCR2A +#define PinB3 11 #define DIO12_PIN PINB4 #define DIO12_RPORT PINB #define DIO12_WPORT PORTB #define DIO12_DDR DDRB #define DIO12_PWM nullptr +#define PinB4 12 #define DIO13_PIN PINB5 #define DIO13_RPORT PINB #define DIO13_WPORT PORTB #define DIO13_DDR DDRB #define DIO13_PWM nullptr +#define PinB5 13 #define DIO14_PIN PINC0 #define DIO14_RPORT PINC #define DIO14_WPORT PORTC #define DIO14_DDR DDRC #define DIO14_PWM nullptr +#define PinC0 14 #define DIO15_PIN PINC1 #define DIO15_RPORT PINC #define DIO15_WPORT PORTC #define DIO15_DDR DDRC #define DIO15_PWM nullptr +#define PinC1 15 #define DIO16_PIN PINC2 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_DDR DDRC #define DIO16_PWM nullptr +#define PinC2 16 #define DIO17_PIN PINC3 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_DDR DDRC #define DIO17_PWM nullptr +#define PinC3 17 #define DIO18_PIN PINC4 #define DIO18_RPORT PINC #define DIO18_WPORT PORTC #define DIO18_DDR DDRC #define DIO18_PWM nullptr +#define PinC4 18 #define DIO19_PIN PINC5 #define DIO19_RPORT PINC #define DIO19_WPORT PORTC #define DIO19_DDR DDRC #define DIO19_PWM nullptr +#define PinC5 19 #define DIO20_PIN PINC6 #define DIO20_RPORT PINC #define DIO20_WPORT PORTC #define DIO20_DDR DDRC #define DIO20_PWM nullptr +#define PinC6 20 #define DIO21_PIN PINC7 #define DIO21_RPORT PINC #define DIO21_WPORT PORTC #define DIO21_DDR DDRC #define DIO21_PWM nullptr +#define PinC7 21 -#define DIO_NUM 22 - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_DDR DDRB -#define PB0_PWM nullptr - -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_DDR DDRB -#define PB1_PWM nullptr - -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_DDR DDRB -#define PB2_PWM nullptr - -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_DDR DDRB -#define PB3_PWM &OCR2A - -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_DDR DDRB -#define PB4_PWM nullptr - -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_DDR DDRB -#define PB5_PWM nullptr - -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_DDR DDRB -#define PB6_PWM nullptr - -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_DDR DDRB -#define PB7_PWM nullptr - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_DDR DDRC -#define PC0_PWM nullptr - -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_DDR DDRC -#define PC1_PWM nullptr - -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_DDR DDRC -#define PC2_PWM nullptr - -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_DDR DDRC -#define PC3_PWM nullptr - -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_DDR DDRC -#define PC4_PWM nullptr - -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_DDR DDRC -#define PC5_PWM nullptr - -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_DDR DDRC -#define PC6_PWM nullptr - -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_DDR DDRC -#define PC7_PWM nullptr - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_DDR DDRD -#define PD0_PWM nullptr - -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_DDR DDRD -#define PD1_PWM nullptr - -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_DDR DDRD -#define PD2_PWM nullptr - -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_DDR DDRD -#define PD3_PWM &OCR2B - -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_DDR DDRD -#define PD4_PWM nullptr - -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_DDR DDRD -#define PD5_PWM &OCR0B - -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_DDR DDRD -#define PD6_PWM &OCR0A - -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_DDR DDRD -#define PD7_PWM nullptr +#define DIO_NUM 22 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index 193c018ae2df..bf3bdb76f057 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -92,192 +92,224 @@ #define DIO0_WPORT PORTB #define DIO0_DDR DDRB #define DIO0_PWM nullptr +#define PinB0 0 #define DIO1_PIN PINB1 #define DIO1_RPORT PINB #define DIO1_WPORT PORTB #define DIO1_DDR DDRB #define DIO1_PWM nullptr +#define PinB1 1 #define DIO2_PIN PINB2 #define DIO2_RPORT PINB #define DIO2_WPORT PORTB #define DIO2_DDR DDRB #define DIO2_PWM nullptr +#define PinB2 2 #define DIO3_PIN PINB3 #define DIO3_RPORT PINB #define DIO3_WPORT PORTB #define DIO3_DDR DDRB #define DIO3_PWM &OCR0A +#define PinB3 3 #define DIO4_PIN PINB4 #define DIO4_RPORT PINB #define DIO4_WPORT PORTB #define DIO4_DDR DDRB #define DIO4_PWM &OCR0B +#define PinB4 4 #define DIO5_PIN PINB5 #define DIO5_RPORT PINB #define DIO5_WPORT PORTB #define DIO5_DDR DDRB #define DIO5_PWM nullptr +#define PinB5 5 #define DIO6_PIN PINB6 #define DIO6_RPORT PINB #define DIO6_WPORT PORTB #define DIO6_DDR DDRB #define DIO6_PWM nullptr +#define PinB6 6 #define DIO7_PIN PINB7 #define DIO7_RPORT PINB #define DIO7_WPORT PORTB #define DIO7_DDR DDRB #define DIO7_PWM nullptr +#define PinB7 7 #define DIO8_PIN PIND0 #define DIO8_RPORT PIND #define DIO8_WPORT PORTD #define DIO8_DDR DDRD #define DIO8_PWM nullptr +#define PinD0 8 #define DIO9_PIN PIND1 #define DIO9_RPORT PIND #define DIO9_WPORT PORTD #define DIO9_DDR DDRD #define DIO9_PWM nullptr +#define PinD1 9 #define DIO10_PIN PIND2 #define DIO10_RPORT PIND #define DIO10_WPORT PORTD #define DIO10_DDR DDRD #define DIO10_PWM nullptr +#define PinD2 10 #define DIO11_PIN PIND3 #define DIO11_RPORT PIND #define DIO11_WPORT PORTD #define DIO11_DDR DDRD #define DIO11_PWM nullptr +#define PinD3 11 #define DIO12_PIN PIND4 #define DIO12_RPORT PIND #define DIO12_WPORT PORTD #define DIO12_DDR DDRD #define DIO12_PWM &OCR1B +#define PinD4 12 #define DIO13_PIN PIND5 #define DIO13_RPORT PIND #define DIO13_WPORT PORTD #define DIO13_DDR DDRD #define DIO13_PWM &OCR1A +#define PinD5 13 #define DIO14_PIN PIND6 #define DIO14_RPORT PIND #define DIO14_WPORT PORTD #define DIO14_DDR DDRD #define DIO14_PWM &OCR2B +#define PinD6 14 #define DIO15_PIN PIND7 #define DIO15_RPORT PIND #define DIO15_WPORT PORTD #define DIO15_DDR DDRD #define DIO15_PWM &OCR2A +#define PinD7 15 #define DIO16_PIN PINC0 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_DDR DDRC #define DIO16_PWM nullptr +#define PinD0 16 #define DIO17_PIN PINC1 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_DDR DDRC #define DIO17_PWM nullptr +#define PinC1 17 #define DIO18_PIN PINC2 #define DIO18_RPORT PINC #define DIO18_WPORT PORTC #define DIO18_DDR DDRC #define DIO18_PWM nullptr +#define PinC2 18 #define DIO19_PIN PINC3 #define DIO19_RPORT PINC #define DIO19_WPORT PORTC #define DIO19_DDR DDRC #define DIO19_PWM nullptr +#define PinC3 19 #define DIO20_PIN PINC4 #define DIO20_RPORT PINC #define DIO20_WPORT PORTC #define DIO20_DDR DDRC #define DIO20_PWM nullptr +#define PinC4 20 #define DIO21_PIN PINC5 #define DIO21_RPORT PINC #define DIO21_WPORT PORTC #define DIO21_DDR DDRC #define DIO21_PWM nullptr +#define PinC5 21 #define DIO22_PIN PINC6 #define DIO22_RPORT PINC #define DIO22_WPORT PORTC #define DIO22_DDR DDRC #define DIO22_PWM nullptr +#define PinC6 22 #define DIO23_PIN PINC7 #define DIO23_RPORT PINC #define DIO23_WPORT PORTC #define DIO23_DDR DDRC #define DIO23_PWM nullptr +#define PinC7 23 #define DIO24_PIN PINA7 #define DIO24_RPORT PINA #define DIO24_WPORT PORTA #define DIO24_DDR DDRA #define DIO24_PWM nullptr +#define PinA7 24 #define DIO25_PIN PINA6 #define DIO25_RPORT PINA #define DIO25_WPORT PORTA #define DIO25_DDR DDRA #define DIO25_PWM nullptr +#define PinA6 25 #define DIO26_PIN PINA5 #define DIO26_RPORT PINA #define DIO26_WPORT PORTA #define DIO26_DDR DDRA #define DIO26_PWM nullptr +#define PinA5 26 #define DIO27_PIN PINA4 #define DIO27_RPORT PINA #define DIO27_WPORT PORTA #define DIO27_DDR DDRA #define DIO27_PWM nullptr +#define PinA4 27 #define DIO28_PIN PINA3 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_DDR DDRA #define DIO28_PWM nullptr +#define PinA3 28 #define DIO29_PIN PINA2 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_DDR DDRA #define DIO29_PWM nullptr +#define PinA2 29 #define DIO30_PIN PINA1 #define DIO30_RPORT PINA #define DIO30_WPORT PORTA #define DIO30_DDR DDRA #define DIO30_PWM nullptr +#define PinA1 30 #define DIO31_PIN PINA0 #define DIO31_RPORT PINA #define DIO31_WPORT PORTA #define DIO31_DDR DDRA #define DIO31_PWM nullptr +#define PinA0 31 #define DIO_NUM 32 @@ -327,228 +359,4 @@ #define AIO7_RPORT PINA #define AIO7_WPORT PORTA #define AIO7_DDR DDRA -#define AIO7_PWM nullptr - -#undef PA0 -#define PA0_PIN PINA0 -#define PA0_RPORT PINA -#define PA0_WPORT PORTA -#define PA0_DDR DDRA -#define PA0_PWM nullptr - -#undef PA1 -#define PA1_PIN PINA1 -#define PA1_RPORT PINA -#define PA1_WPORT PORTA -#define PA1_DDR DDRA -#define PA1_PWM nullptr - -#undef PA2 -#define PA2_PIN PINA2 -#define PA2_RPORT PINA -#define PA2_WPORT PORTA -#define PA2_DDR DDRA -#define PA2_PWM nullptr - -#undef PA3 -#define PA3_PIN PINA3 -#define PA3_RPORT PINA -#define PA3_WPORT PORTA -#define PA3_DDR DDRA -#define PA3_PWM nullptr - -#undef PA4 -#define PA4_PIN PINA4 -#define PA4_RPORT PINA -#define PA4_WPORT PORTA -#define PA4_DDR DDRA -#define PA4_PWM nullptr - -#undef PA5 -#define PA5_PIN PINA5 -#define PA5_RPORT PINA -#define PA5_WPORT PORTA -#define PA5_DDR DDRA -#define PA5_PWM nullptr - -#undef PA6 -#define PA6_PIN PINA6 -#define PA6_RPORT PINA -#define PA6_WPORT PORTA -#define PA6_DDR DDRA -#define PA6_PWM nullptr - -#undef PA7 -#define PA7_PIN PINA7 -#define PA7_RPORT PINA -#define PA7_WPORT PORTA -#define PA7_DDR DDRA -#define PA7_PWM nullptr - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_DDR DDRB -#define PB0_PWM nullptr - -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_DDR DDRB -#define PB1_PWM nullptr - -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_DDR DDRB -#define PB2_PWM nullptr - -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_DDR DDRB -#define PB3_PWM &OCR0A - -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_DDR DDRB -#define PB4_PWM &OCR0B - -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_DDR DDRB -#define PB5_PWM nullptr - -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_DDR DDRB -#define PB6_PWM nullptr - -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_DDR DDRB -#define PB7_PWM nullptr - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_DDR DDRC -#define PC0_PWM nullptr - -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_DDR DDRC -#define PC1_PWM nullptr - -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_DDR DDRC -#define PC2_PWM nullptr - -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_DDR DDRC -#define PC3_PWM nullptr - -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_DDR DDRC -#define PC4_PWM nullptr - -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_DDR DDRC -#define PC5_PWM nullptr - -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_DDR DDRC -#define PC6_PWM nullptr - -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_DDR DDRC -#define PC7_PWM nullptr - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_DDR DDRD -#define PD0_PWM nullptr - -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_DDR DDRD -#define PD1_PWM nullptr - -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_DDR DDRD -#define PD2_PWM nullptr - -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_DDR DDRD -#define PD3_PWM nullptr - -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_DDR DDRD -#define PD4_PWM nullptr - -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_DDR DDRD -#define PD5_PWM nullptr - -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_DDR DDRD -#define PD6_PWM &OCR2B - -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_DDR DDRD -#define PD7_PWM &OCR2A +#define AIO7_PWM nullptr \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index df10b58a2df2..5b380d2acfca 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -47,276 +47,345 @@ #define DIO0_WPORT PORTD #define DIO0_PWM 0 #define DIO0_DDR DDRD +#define PinD0 0 #define DIO1_PIN PIND1 #define DIO1_RPORT PIND #define DIO1_WPORT PORTD #define DIO1_PWM 0 #define DIO1_DDR DDRD +#define PinD1 1 #define DIO2_PIN PIND2 #define DIO2_RPORT PIND #define DIO2_WPORT PORTD #define DIO2_PWM 0 #define DIO2_DDR DDRD +#define PinD2 2 #define DIO3_PIN PIND3 #define DIO3_RPORT PIND #define DIO3_WPORT PORTD #define DIO3_PWM 0 #define DIO3_DDR DDRD +#define PinD3 3 #define DIO4_PIN PIND4 #define DIO4_RPORT PIND #define DIO4_WPORT PORTD #define DIO4_PWM 0 #define DIO4_DDR DDRD +#define PinD4 4 #define DIO5_PIN PIND5 #define DIO5_RPORT PIND #define DIO5_WPORT PORTD #define DIO5_PWM 0 #define DIO5_DDR DDRD +#define PinD5 5 #define DIO6_PIN PIND6 #define DIO6_RPORT PIND #define DIO6_WPORT PORTD #define DIO6_PWM 0 #define DIO6_DDR DDRD +#define PinD6 6 #define DIO7_PIN PIND7 #define DIO7_RPORT PIND #define DIO7_WPORT PORTD #define DIO7_PWM 0 #define DIO7_DDR DDRD +#define PinD7 7 #define DIO8_PIN PINE0 #define DIO8_RPORT PINE #define DIO8_WPORT PORTE #define DIO8_PWM 0 #define DIO8_DDR DDRE +#define PinD0 8 #define DIO9_PIN PINE1 #define DIO9_RPORT PINE #define DIO9_WPORT PORTE #define DIO9_PWM 0 #define DIO9_DDR DDRE +#define PinE1 9 #define DIO10_PIN PINC0 #define DIO10_RPORT PINC #define DIO10_WPORT PORTC #define DIO10_PWM 0 #define DIO10_DDR DDRC +#define PinC0 10 #define DIO11_PIN PINC1 #define DIO11_RPORT PINC #define DIO11_WPORT PORTC #define DIO11_PWM 0 #define DIO11_DDR DDRC +#define PinC1 11 #define DIO12_PIN PINC2 #define DIO12_RPORT PINC #define DIO12_WPORT PORTC #define DIO12_PWM 0 #define DIO12_DDR DDRC +#define PinC2 12 #define DIO13_PIN PINC3 #define DIO13_RPORT PINC #define DIO13_WPORT PORTC #define DIO13_PWM 0 #define DIO13_DDR DDRC +#define PinC3 13 #define DIO14_PIN PINC4 #define DIO14_RPORT PINC #define DIO14_WPORT PORTC #define DIO14_PWM 0 // OC3C #define DIO14_DDR DDRC +#define PinC4 14 #define DIO15_PIN PINC5 #define DIO15_RPORT PINC #define DIO15_WPORT PORTC #define DIO15_PWM 0 // OC3B #define DIO15_DDR DDRC +#define PinC5 15 #define DIO16_PIN PINC6 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC #define DIO16_PWM 0 // OC3A #define DIO16_DDR DDRC +#define PinC6 16 #define DIO17_PIN PINC7 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC #define DIO17_PWM 0 #define DIO17_DDR DDRC +#define PinC7 17 #define DIO18_PIN PINE6 #define DIO18_RPORT PINE #define DIO18_WPORT PORTE #define DIO18_PWM 0 #define DIO18_DDR DDRE +#define PinE6 18 #define DIO19_PIN PINE7 #define DIO19_RPORT PINE #define DIO19_WPORT PORTE #define DIO19_PWM 0 #define DIO19_DDR DDRE +#define PinE7 19 #define DIO20_PIN PINB0 #define DIO20_RPORT PINB #define DIO20_WPORT PORTB #define DIO20_PWM 0 #define DIO20_DDR DDRB +#define PinB0 20 #define DIO21_PIN PINB1 #define DIO21_RPORT PINB #define DIO21_WPORT PORTB #define DIO21_PWM 0 #define DIO21_DDR DDRB +#define PinB1 21 #define DIO22_PIN PINB2 #define DIO22_RPORT PINB #define DIO22_WPORT PORTB #define DIO22_PWM 0 #define DIO22_DDR DDRB +#define PinB2 22 #define DIO23_PIN PINB3 #define DIO23_RPORT PINB #define DIO23_WPORT PORTB #define DIO23_PWM 0 #define DIO23_DDR DDRB +#define PinB3 23 #define DIO24_PIN PINB4 #define DIO24_RPORT PINB #define DIO24_WPORT PORTB #define DIO24_PWM 0 // OC2A #define DIO24_DDR DDRB +#define PinB4 24 #define DIO25_PIN PINB5 #define DIO25_RPORT PINB #define DIO25_WPORT PORTB #define DIO25_PWM 0 // OC1A #define DIO25_DDR DDRB +#define PinB5 25 #define DIO26_PIN PINB6 #define DIO26_RPORT PINB #define DIO26_WPORT PORTB #define DIO26_PWM 0 // OC1B #define DIO26_DDR DDRB +#define PinB6 26 #define DIO27_PIN PINB7 #define DIO27_RPORT PINB #define DIO27_WPORT PORTB #define DIO27_PWM 0 // OC1C #define DIO27_DDR DDRB +#define PinB7 27 #define DIO28_PIN PINA0 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA #define DIO28_PWM 0 #define DIO28_DDR DDRA +#define PinA0 28 #define DIO29_PIN PINA1 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA #define DIO29_PWM 0 #define DIO29_DDR DDRA +#define PinA1 29 #define DIO30_PIN PINA2 #define DIO30_RPORT PINA #define DIO30_WPORT PORTA #define DIO30_PWM 0 #define DIO30_DDR DDRA +#define PinA2 30 #define DIO31_PIN PINA3 #define DIO31_RPORT PINA #define DIO31_WPORT PORTA #define DIO31_PWM 0 #define DIO31_DDR DDRA +#define PinA3 31 #define DIO32_PIN PINA4 #define DIO32_RPORT PINA #define DIO32_WPORT PORTA #define DIO32_PWM 0 #define DIO32_DDR DDRA +#define PinA4 32 #define DIO33_PIN PINA5 #define DIO33_RPORT PINA #define DIO33_WPORT PORTA #define DIO33_PWM 0 #define DIO33_DDR DDRA +#define PinA5 33 #define DIO34_PIN PINA6 #define DIO34_RPORT PINA #define DIO34_WPORT PORTA #define DIO34_PWM 0 #define DIO34_DDR DDRA +#define PinA6 34 #define DIO35_PIN PINA7 #define DIO35_RPORT PINA #define DIO35_WPORT PORTA #define DIO35_PWM 0 #define DIO35_DDR DDRA +#define PinA7 35 #define DIO36_PIN PINE4 #define DIO36_RPORT PINE #define DIO36_WPORT PORTE #define DIO36_PWM 0 #define DIO36_DDR DDRE +#define PinE4 36 #define DIO37_PIN PINE5 #define DIO37_RPORT PINE #define DIO37_WPORT PORTE #define DIO37_PWM 0 #define DIO37_DDR DDRE +#define PinE5 37 #define DIO38_PIN PINF0 #define DIO38_RPORT PINF #define DIO38_WPORT PORTF #define DIO38_PWM 0 #define DIO38_DDR DDRF +#define PinF0 38 #define DIO39_PIN PINF1 #define DIO39_RPORT PINF #define DIO39_WPORT PORTF #define DIO39_PWM 0 #define DIO39_DDR DDRF +#define PinF1 39 #define DIO40_PIN PINF2 #define DIO40_RPORT PINF #define DIO40_WPORT PORTF #define DIO40_PWM 0 #define DIO40_DDR DDRF +#define PinF2 40 #define DIO41_PIN PINF3 #define DIO41_RPORT PINF #define DIO41_WPORT PORTF #define DIO41_PWM 0 #define DIO41_DDR DDRF +#define PinF3 41 #define DIO42_PIN PINF4 #define DIO42_RPORT PINF #define DIO42_WPORT PORTF #define DIO42_PWM 0 #define DIO42_DDR DDRF +#define PinF4 42 #define DIO43_PIN PINF5 #define DIO43_RPORT PINF #define DIO43_WPORT PORTF #define DIO43_PWM 0 #define DIO43_DDR DDRF +#define PinF5 43 #define DIO44_PIN PINF6 #define DIO44_RPORT PINF #define DIO44_WPORT PORTF #define DIO44_PWM 0 #define DIO44_DDR DDRF +#define PinF6 44 #define DIO45_PIN PINF7 #define DIO45_RPORT PINF #define DIO45_WPORT PORTF #define DIO45_PWM 0 #define DIO45_DDR DDRF +#define PinF7 45 + +//-- Begin not supported by Teensyduino +//-- don't use Arduino functions on these pins pinMode/digitalWrite/etc +#define DIO46_PIN PINE2 +#define DIO46_RPORT PINE +#define DIO46_WPORT PORTE +#define DIO46_PWM 0 +#define DIO46_DDR DDRE +#define PinE2 46 + +#define DIO47_PIN PINE3 +#define DIO47_RPORT PINE +#define DIO47_WPORT PORTE +#define DIO47_PWM 0 +#define DIO47_DDR DDRE +#define PinE3 47 + +#define DIO_NUM 48 + +#define TEENSY_E2 46 +#define TEENSY_E3 47 + +//-- end not supported by Teensyduino #define AIO0_PIN PINF0 #define AIO0_RPORT PINF @@ -366,322 +435,6 @@ #define AIO7_PWM 0 #define AIO7_DDR DDRF -//-- Begin not supported by Teensyduino -//-- don't use Arduino functions on these pins pinMode/digitalWrite/etc -#define DIO46_PIN PINE2 -#define DIO46_RPORT PINE -#define DIO46_WPORT PORTE -#define DIO46_PWM 0 -#define DIO46_DDR DDRE - -#define DIO47_PIN PINE3 -#define DIO47_RPORT PINE -#define DIO47_WPORT PORTE -#define DIO47_PWM 0 -#define DIO47_DDR DDRE - -#define DIO_NUM 48 - -#define TEENSY_E2 46 -#define TEENSY_E3 47 - -//-- end not supported by Teensyduino - -#undef PA0 -#define PA0_PIN PINA0 -#define PA0_RPORT PINA -#define PA0_WPORT PORTA -#define PA0_PWM 0 -#define PA0_DDR DDRA -#undef PA1 -#define PA1_PIN PINA1 -#define PA1_RPORT PINA -#define PA1_WPORT PORTA -#define PA1_PWM 0 -#define PA1_DDR DDRA -#undef PA2 -#define PA2_PIN PINA2 -#define PA2_RPORT PINA -#define PA2_WPORT PORTA -#define PA2_PWM 0 -#define PA2_DDR DDRA -#undef PA3 -#define PA3_PIN PINA3 -#define PA3_RPORT PINA -#define PA3_WPORT PORTA -#define PA3_PWM 0 -#define PA3_DDR DDRA -#undef PA4 -#define PA4_PIN PINA4 -#define PA4_RPORT PINA -#define PA4_WPORT PORTA -#define PA4_PWM 0 -#define PA4_DDR DDRA -#undef PA5 -#define PA5_PIN PINA5 -#define PA5_RPORT PINA -#define PA5_WPORT PORTA -#define PA5_PWM 0 -#define PA5_DDR DDRA -#undef PA6 -#define PA6_PIN PINA6 -#define PA6_RPORT PINA -#define PA6_WPORT PORTA -#define PA6_PWM 0 -#define PA6_DDR DDRA -#undef PA7 -#define PA7_PIN PINA7 -#define PA7_RPORT PINA -#define PA7_WPORT PORTA -#define PA7_PWM 0 -#define PA7_DDR DDRA - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_PWM 0 -#define PB0_DDR DDRB -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_PWM 0 -#define PB1_DDR DDRB -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_PWM 0 -#define PB2_DDR DDRB -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_PWM 0 -#define PB3_DDR DDRB -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_PWM 0 -#define PB4_DDR DDRB -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_PWM 0 -#define PB5_DDR DDRB -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_PWM 0 -#define PB6_DDR DDRB -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_PWM 0 -#define PB7_DDR DDRB - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_PWM 0 -#define PC0_DDR DDRC -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_PWM 0 -#define PC1_DDR DDRC -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_PWM 0 -#define PC2_DDR DDRC -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_PWM 0 -#define PC3_DDR DDRC -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_PWM 0 -#define PC4_DDR DDRC -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_PWM 0 -#define PC5_DDR DDRC -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_PWM 0 -#define PC6_DDR DDRC -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_PWM 0 -#define PC7_DDR DDRC - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_PWM 0 // OC0B -#define PD0_DDR DDRD -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_PWM 0 // OC2B -#define PD1_DDR DDRD -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_PWM 0 -#define PD2_DDR DDRD -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_PWM 0 -#define PD3_DDR DDRD -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_PWM 0 -#define PD4_DDR DDRD -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_PWM 0 -#define PD5_DDR DDRD -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_PWM 0 -#define PD6_DDR DDRD -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_PWM 0 -#define PD7_DDR DDRD - -#undef PE0 -#define PE0_PIN PINE0 -#define PE0_RPORT PINE -#define PE0_WPORT PORTE -#define PE0_PWM 0 -#define PE0_DDR DDRE -#undef PE1 -#define PE1_PIN PINE1 -#define PE1_RPORT PINE -#define PE1_WPORT PORTE -#define PE1_PWM 0 -#define PE1_DDR DDRE -#undef PE2 -#define PE2_PIN PINE2 -#define PE2_RPORT PINE -#define PE2_WPORT PORTE -#define PE2_PWM 0 -#define PE2_DDR DDRE -#undef PE3 -#define PE3_PIN PINE3 -#define PE3_RPORT PINE -#define PE3_WPORT PORTE -#define PE3_PWM 0 -#define PE3_DDR DDRE -#undef PE4 -#define PE4_PIN PINE4 -#define PE4_RPORT PINE -#define PE4_WPORT PORTE -#define PE4_PWM 0 -#define PE4_DDR DDRE -#undef PE5 -#define PE5_PIN PINE5 -#define PE5_RPORT PINE -#define PE5_WPORT PORTE -#define PE5_PWM 0 -#define PE5_DDR DDRE -#undef PE6 -#define PE6_PIN PINE6 -#define PE6_RPORT PINE -#define PE6_WPORT PORTE -#define PE6_PWM 0 -#define PE6_DDR DDRE -#undef PE7 -#define PE7_PIN PINE7 -#define PE7_RPORT PINE -#define PE7_WPORT PORTE -#define PE7_PWM 0 -#define PE7_DDR DDRE - -#undef PF0 -#define PF0_PIN PINF0 -#define PF0_RPORT PINF -#define PF0_WPORT PORTF -#define PF0_PWM 0 -#define PF0_DDR DDRF -#undef PF1 -#define PF1_PIN PINF1 -#define PF1_RPORT PINF -#define PF1_WPORT PORTF -#define PF1_PWM 0 -#define PF1_DDR DDRF -#undef PF2 -#define PF2_PIN PINF2 -#define PF2_RPORT PINF -#define PF2_WPORT PORTF -#define PF2_PWM 0 -#define PF2_DDR DDRF -#undef PF3 -#define PF3_PIN PINF3 -#define PF3_RPORT PINF -#define PF3_WPORT PORTF -#define PF3_PWM 0 -#define PF3_DDR DDRF -#undef PF4 -#define PF4_PIN PINF4 -#define PF4_RPORT PINF -#define PF4_WPORT PORTF -#define PF4_PWM 0 -#define PF4_DDR DDRF -#undef PF5 -#define PF5_PIN PINF5 -#define PF5_RPORT PINF -#define PF5_WPORT PORTF -#define PF5_PWM 0 -#define PF5_DDR DDRF -#undef PF6 -#define PF6_PIN PINF6 -#define PF6_RPORT PINF -#define PF6_WPORT PORTF -#define PF6_PWM 0 -#define PF6_DDR DDRF -#undef PF7 -#define PF7_PIN PINF7 -#define PF7_RPORT PINF -#define PF7_WPORT PORTF -#define PF7_PWM 0 -#define PF7_DDR DDRF - - /** * Some of the pin mapping functions of the Teensduino extension to the Arduino IDE * do not function the same as the other Arduino extensions. diff --git a/Marlin/src/HAL/AVR/registers.cpp b/Marlin/src/HAL/AVR/registers.cpp index 3188edb3084d..53576b0c76cb 100644 --- a/Marlin/src/HAL/AVR/registers.cpp +++ b/Marlin/src/HAL/AVR/registers.cpp @@ -30,8 +30,10 @@ // we want to off-load the function definitions that define static memory into this solitary compilation unit. // This way the ROM is NOT bloated (who knows if the compiler is optimizing same-content constant objects into one?) -ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { - ATmegaPinInfo info = _ATmega_getPinInfo(pin); +ATmegaPinFunctions _ATmega_getPinFunctions(int pin) { + if (pin < 0) return {}; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); #if defined(__AVR_TRM01__) if (info.port == eATmegaPort::PORT_A) { @@ -70,19 +72,19 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_B) { if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0A, eATmegaPinFunc::OC1C, eATmegaPinFunc::PCI7 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI6 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI5 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI4 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { @@ -180,15 +182,15 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::OC3C }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOC3C }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::OC3B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOC3B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::OC3A }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC3A }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { @@ -240,7 +242,7 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_G) { if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { @@ -270,19 +272,19 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4C }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4C }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC4A }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4A }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { @@ -364,15 +366,15 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_L) { if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5C }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5C }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC5A }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5A }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { @@ -425,11 +427,11 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_B) { if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::OC3B, eATmegaPinFunc::PCI15 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::TOC3B, eATmegaPinFunc::PCI15 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::OC3A, eATmegaPinFunc::PCI14 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::TOC3A, eATmegaPinFunc::PCI14 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { @@ -437,11 +439,11 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::OC0B, eATmegaPinFunc::PCI12 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI12 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::OC0A, eATmegaPinFunc::PCI11 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI11 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { @@ -493,19 +495,19 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_D) { if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI31 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI31 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::OC2B, eATmegaPinFunc::PCI30 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI30 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI29 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI29 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { @@ -544,15 +546,15 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI3 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI3 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI2 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI2 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI1 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI1 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 0) { @@ -596,11 +598,11 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::OC0A, eATmegaPinFunc::PCI22 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI22 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::OC0B, eATmegaPinFunc::PCI21 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI21 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { @@ -608,7 +610,7 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::OC2B, eATmegaPinFunc::PCI19 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI19 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { @@ -661,19 +663,19 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { } else if (info.port == eATmegaPort::PORT_B) { if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC0A, eATmegaPinFunc::OC1C, eATmegaPinFunc::PCI7 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1B, eATmegaPinFunc::PCI6 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC1A, eATmegaPinFunc::PCI5 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::OC2A, eATmegaPinFunc::PCI4 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { @@ -699,15 +701,15 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::OC3A }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::TOC3A }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::OC3B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::TOC3B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::OC3C }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::TOC3C }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { @@ -753,11 +755,11 @@ ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin) { return { funcs, countof(funcs) }; } else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::OC2B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TOC2B }; return { funcs, countof(funcs) }; } else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::OC0B }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TOC0B }; return { funcs, countof(funcs) }; } } diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 12d43de7673c..5aae44ba72f2 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -1526,23 +1526,27 @@ static_assert(sizeof(PLLCSR_reg_t) == 1, "invalid size of ATUSB90 PLLCSR_reg_t") REGISTER MEMORY MAP */ +#define __AVR_DEFREG(tn,n,a) static tn& n = *(tn*)a +#define _AVR_DEFREG(n,a) __AVR_DEFREG(n##_reg_t, _##n, a) + #if defined(__AVR_TRM01__) // page 399ff of ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf -static PORT_dev_t& _PORTA = *(PORT_dev_t*)0x20; -static PORT_dev_t& _PORTB = *(PORT_dev_t*)0x23; -static PORT_dev_t& _PORTC = *(PORT_dev_t*)0x26; -static PORT_dev_t& _PORTD = *(PORT_dev_t*)0x29; -static PORT_dev_t& _PORTE = *(PORT_dev_t*)0x2C; -static PORT_dev_t& _PORTF = *(PORT_dev_t*)0x2F; -static PORTG_dev_t& _PORTG = *(PORTG_dev_t*)0x32; -static PORT_dev_t& _PORTH = *(PORT_dev_t*)0x100; -static PORT_dev_t& _PORTJ = *(PORT_dev_t*)0x103; -static PORT_dev_t& _PORTK = *(PORT_dev_t*)0x106; -static PORT_dev_t& _PORTL = *(PORT_dev_t*)0x109; -static TIFR0_reg_t& _TIFR0 = *(TIFR0_reg_t*)0x35; -static TIFR1_reg_t& _TIFR1 = *(TIFR1_reg_t*)0x36; -static TIFR2_reg_t& _TIFR2 = *(TIFR2_reg_t*)0x37; -static TIFR3_reg_t& _TIFR3 = *(TIFR3_reg_t*)0x38; + +__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); +__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); +__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); +__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); +__AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); +__AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); +__AVR_DEFREG(PORTG_dev_t, _PORTG, 0x32); +__AVR_DEFREG(PORT_dev_t, _PORTH, 0x100); +__AVR_DEFREG(PORT_dev_t, _PORTJ, 0x103); +__AVR_DEFREG(PORT_dev_t, _PORTK, 0x106); +__AVR_DEFREG(PORT_dev_t, _PORTL, 0x109); +__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); +__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); +__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); +__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); static TIFR4_reg_t& _TIFR4 = *(TIFR4_reg_t*)0x39; static TIFR5_reg_t& _TIFR5 = *(TIFR5_reg_t*)0x3A; static PCIFR_reg_t& _PCIFR = *(PCIFR_reg_t*)0x3B; @@ -1698,6 +1702,7 @@ static _bit_reg_t& _GPIOR1 = *(_bit_reg_t*)0x4A; static _bit_reg_t& _GPIOR2 = *(_bit_reg_t*)0x4B; static SPCR_reg_t& _SPCR = *(SPCR_reg_t*)0x4C; static SPSR_reg_t& _SPSR = *(SPSR_reg_t*)0x4D; +static uint8_t& _SPDR = *(uint8_t*)0x4E; static ACSR_reg_t& _ACSR = *(ACSR_reg_t*)0x50; static SMCR_reg_t& _SMCR = *(SMCR_reg_t*)0x53; static MCUSR_reg_t& _MCUSR = *(MCUSR_reg_t*)0x54; @@ -1803,7 +1808,6 @@ static UPINTX_reg_t& _UPINTX = *(UPINTX_reg_t*)0xA6; static UPNUM_reg_t& _UPNUM = *(UPNUM_reg_t*)0xA7; static UPRST_reg_t& _UPRST = *(UPRST_reg_t*)0xA8; static UPCONX_reg_t& _UPCONX = *(UPCONX_reg_t*)0xA9; -#define _AVR_DEFREG(n,a) static n##_reg_t& _##n = *(n##_reg_t*)a _AVR_DEFREG(UPCFG0X, 0xAA); _AVR_DEFREG(UPCFG1X, 0xAB); _AVR_DEFREG(UPSTAX, 0xAC); @@ -3984,7 +3988,7 @@ enum class eATmegaPinFunc { EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - OC0A, OC0B, OC1A, OC1B, OC1C, OC2A, OC2B, OC3C, OC3B, OC3A, OC4C, OC4B, OC4A, OC5C, OC5B, OC5A, + TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, PCI8, PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, @@ -4010,7 +4014,7 @@ enum class eATmegaPinFunc { TIMER3_ICP, TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, TIMER1_ICP, - OC3B, OC3A, OC2A, OC2B, OC1A, OC1B, OC0B, OC0A, + TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, AIN1, AIN0, USART0_CLK, USART1_CLK, USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, @@ -4022,7 +4026,7 @@ enum class eATmegaPinFunc { XTAL2, XTAL1, TOSC2, TOSC1, SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, - OC2B, OC2A, OC1B, OC1A, OC0A, OC0B, + TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, TIMER1_ICP, TIMER1_ECI, TIMER0_ECI, TWI_CLK, TWI_SDA, @@ -4038,7 +4042,7 @@ enum class eATmegaPinFunc { EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - OC0B, OC0A, OC1C, OC1B, OC1A, OC2B, OC2A, OC3A, OC3B, OC3C, + TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, CLK0, PDO, PDI, SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, TIMER3_ICP, TIMER1_ICP, @@ -4061,6 +4065,454 @@ struct ATmegaPinFunctions { const eATmegaPinFunc *funcs = nullptr; uint8_t cnt = 0; + + inline bool hasFunc(eATmegaPinFunc query) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + + if (func == query) + return true; + } + return false; + } +}; + +ATmegaPinFunctions _ATmega_getPinFunctions(int pin); + +#ifndef LOW +#define LOW 0 +#endif +#ifndef HIGH +#define HIGH 1 +#endif + +inline void _ATmega_digitalWrite(int pin, int state) { + if (pin < 0) return; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + +#if defined(__AVR_TRM01__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._PORT.setValue(info.pinidx, state == HIGH); + } +#elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } +#elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPOrt::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } +#endif +} + +inline int _ATmega_digitalRead(int pin) { + int value = LOW; + + if (pin < 0) return value; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + +#if defined(__AVR_TRM01__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_G) { + value = _PORTG._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_H) { + value = _PORTH._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_J) { + value = _PORTJ._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_K) { + value = _PORTK._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_L) { + value = _PORTL._PIN.getValue(info.pinidx); + } +#elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } +#elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPOrt::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } +#endif + + return value; +} + +#ifndef OUTPUT +#define OUTPUT 1 +#endif +#ifndef INPUT +#define INPUT 0 +#endif + +inline void _ATmega_pinMode(int pin, int mode) { + if (pin < 0) return; + + ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); + +#if defined(__AVR_TRM01__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._DDR.setValue(info.pinidx, mode == OUTPUT); + } +#elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } +#elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPOrt::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } +#elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } +#endif +} + +#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) +struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; +}; + +struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; +}; + +struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; +}; + +#ifndef AVR_LFUSE_VALUE +#define AVR_LFUSE_VALUE 0xFF +#endif +#ifndef AVR_HFUSE_VALUE +#define AVR_HFUSE_VALUE 0x99 +#endif +#ifndef AVR_LFUSE_VALUE +#define AVR_LFUSE_VALUE 0x62 +#endif + +#elif defined(__AVR_TRM03__) +#if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) +struct _ATmega_efuse { + uint8_t _SELFPRGEN : 1; + uint8_t reserved1 : 7; +}; + +#ifndef AVR_EFUSE_VALUE +#define AVR_EFUSE_VALUE 0xFF +#endif + +#elif defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) +struct _ATmega_efuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t reserved1 : 5; +}; + +#ifndef AVR_EFUSE_VALUE +#define AVR_EFUSE_VALUE 0xF9 +#endif + +#elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; +}; + +#ifndef AVR_EFUSE_VALUE +#define AVR_EFUSE_VALUE 0xFF +#endif + +#endif + +#if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) +struct _ATmega_hfuse { + uint8_t _BODLEVEL : 3; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; }; -ATmegaPinFunctions _ATmega_getPinFunctions(uint8_t pin); \ No newline at end of file +#ifndef AVR_HFUSE_VALUE +#define AVR_HFUSE_VALUE 0xCF +#endif + +#elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; +}; + +#ifndef AVR_HFUSE_VALUE +#define AVR_HFUSE_VALUE 0xC9 +#endif + +#endif + +struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; +}; + +#ifndef AVR_LFUSE_VALUE +#define AVR_LFUSE_VALUE 0xC9 +#endif + +#elif defined(__AVR_TRM04__) +struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t _HWBE : 1; + uint8_t reserved1 : 4; +}; + +struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; +}; + +struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; +}; + +// Default values if not already defined. +#ifndef AVR_EFUSE_VALUE +#define AVR_EFUSE_VALUE 0xF3 +#endif +#ifndef AVR_HFUSE_VALUE +#define AVR_HFUSE_VALUE 0x99 +#endif +#ifndef AVR_LFUSE_VALUE +#define AVR_LFUSE_VALUE 0x62 +#endif + +#endif + +struct ATmega_efuse : public _ATmega_efuse { + inline ATmega_efuse(uint8_t val = 0) { + *(uint8_t*)this = val; + } + inline ATmega_efuse(const ATmega_efuse&) = default; +}; +struct ATmega_hfuse : public _ATmega_hfuse { + inline ATmega_hfuse(uint8_t val = 0) { + *(uint8_t*)this = val; + } + inline ATmega_hfuse(const ATmega_hfuse&) = default; +}; +struct ATmega_lfuse : public _ATmega_lfuse { + inline ATmega_lfuse(uint8_t val = 0) { + *(uint8_t*)this = val; + } + inline ATmega_lfuse(const ATmega_lfuse&) = default; +}; \ No newline at end of file diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index fe05758fae57..be38907325ad 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -491,6 +491,8 @@ } } + void spiEstablish() { /* do nothing */ } + uint8_t spiRec(uint8_t txval) { _SS_WRITE(LOW); WRITE(SD_MOSI_PIN, HIGH); // Output 1s 1 @@ -748,6 +750,8 @@ spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); } + void spiEstablish() { /* do nothing */ } + uint8_t spiRec(uint8_t txval) { if (_has_spi_pins) SPI.beginTransaction(_spi_pin_cs, spiConfig); @@ -986,6 +990,8 @@ } } + void spiEstablish() { /* do nothing */ } + // Read single byte from SPI uint8_t spiRec(uint8_t txval) { // write dummy byte with address and end transmission flag @@ -1231,6 +1237,8 @@ } } + void spiEstablish() { /* do nothing */ } + static uint8_t spiTransfer(uint8_t data) { WHILE_TX(0); SPI0->SPI_TDR = (uint32_t)data | 0x00070000UL; // Add TMC2130 PCS bits to every byte (use SPI0->SPI_CSR[3]) diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index a7e9e6f747da..145f8396e058 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -88,6 +88,52 @@ static void _spi_on_error(uint32_t code = 0) { } } +#ifndef HALSPI_LOOPBEEP_TIMEOUT +#define HALSPI_LOOPBEEP_TIMEOUT 3000 +#endif + +struct spi_monitored_loop +{ +private: +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; +#endif +public: + inline spi_monitored_loop() { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); +#endif + } + inline void update(unsigned int beep_code) { +#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); +#endif + } +}; + static void __attribute__((unused)) _spi_infobeep(uint32_t code) { #if PIN_EXISTS(BEEPER) OUT_WRITE(BEEPER_PIN, HIGH); @@ -1239,8 +1285,10 @@ static void SPITransaction(spi_dev_t& SPI, uint32_t txcount) { SPI.SPI_CMD_REG.SPI_USR = true; + spi_monitored_loop usrw; while (SPI.SPI_CMD_REG.SPI_USR) { /* wait until transfer has finished */ + usrw.update(1); } } @@ -1672,7 +1720,8 @@ static void SPIAsyncInitialize() { static void SPIStartRawAsync(spi_dev_t& SPI, const void *buf, uint32_t txlen, uint8_t txunitsize, void (*completeCallback)(void*), void *ud) { volatile spi_async_process_t& proc = _current_spi_proc; - while (proc.is_active) { /* wait for any async process to conclude before we start another */ } + spi_monitored_loop asyncw; + while (proc.is_active) { asyncw.update(2); /* wait for any async process to conclude before we start another */ } cli(); @@ -1762,6 +1811,7 @@ inline void DMAInitializeMachine() { if (DMAIsValidDescriptor(&desc) == false) { _spi_on_error(3); } + desc.owner = SPIDMA_OWNER_CPU; } #else void *dmabuf = heap_caps_malloc( sizeof(dma_descriptor_t)*HALSPI_ESP32_DMADESC_COUNT, MALLOC_CAP_DMA ); @@ -1771,6 +1821,11 @@ inline void DMAInitializeMachine() { _usable_dma_descs_count = HALSPI_ESP32_DMADESC_COUNT; if (DMAIsValidDescriptor(_usable_dma_descs_dynamic) == false) _spi_on_error(3); + for (uint32_t n = 0; n < _usable_dma_descs_count; n++) { + dma_descriptor_t& desc = _usable_dma_descs_dynamic[n]; + + desc.owner = SPIDMA_OWNER_CPU; + } #endif } @@ -1963,18 +2018,25 @@ static void DMASendBlocking(spi_dev_t& SPI, const void *buf, size_t bufsize, siz // Generate a transfer chain. dma_descriptor_t *chain = DMAGenerateAcquireChain(proc); + if (chain == nullptr) + _spi_on_error(14); + // Configure the transfer. SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = ((uint32_t)chain - ESP32_DMA_BASE); SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = true; // Kick it off. SPI.SPI_CMD_REG.SPI_USR = true; + + spi_monitored_loop usrw; while (SPI.SPI_CMD_REG.SPI_USR) { /* wait until DMA transfer has finished */ - _spi_infobeep(3); + usrw.update(3); } } + _spi_infobeep(4); + proc.is_active = false; DMABusShutdown(SPI); @@ -1986,7 +2048,8 @@ static void DMASendBlocking(spi_dev_t& SPI, const void *buf, size_t bufsize, siz static void _spiAsyncBarrier() { #ifdef HAL_SPI_SUPPORTS_ASYNC - while (MarlinESP32::_current_spi_proc.is_active) { /* wait until any async-SPI process has finished */ } + spi_monitored_loop asyncw; + while (MarlinESP32::_current_spi_proc.is_active) { asyncw.update(4); /* wait until any async-SPI process has finished */ } #endif } @@ -2050,7 +2113,8 @@ void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi #endif #ifdef HAL_SPI_SUPPORTS_ASYNC - while (_spi_is_active) { /* wait until any other transaction has finished */ } + spi_monitored_loop actw; + while (_spi_is_active) { actw.update(5); /* wait until any other transaction has finished */ } #else if (_spi_is_active) _spi_on_error(6); @@ -2205,6 +2269,10 @@ void spiSetClockMode(int mode) { MarlinESP32::SPIConfigureClock(SPI, mode, _spi_gpiomap.datasig_is_direct_iomux, _spi_clkcnt); } +void spiEstablish() { + _maybe_start_transaction(); +} + void spiSend(uint8_t txval) { MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp index c8dbfd832046..9291d2952b45 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp @@ -210,6 +210,10 @@ void spiSetClockMode(int mode) { } } +void spiEstablish() { + _maybe_start_transaction(); +} + uint8_t spiRec(uint8_t txval) { _maybe_start_transaction(); uint8_t returnByte = SPI.transfer(txval); diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 659e0dedec44..a8d970d224e8 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -1638,6 +1638,10 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { } } + void spiEstablish() { + _maybe_start_transaction(); + } + // Internal. inline void _spiSetFrameSize(uint8_t fsize) { if (_ssp_framesize != fsize) { diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp index 933a3553cbea..8ccd265f9ffb 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp @@ -144,6 +144,10 @@ } } + void spiEstablish() { + _maybe_start_transaction(); + } + uint8_t spiRec(uint8_t txval) { return (_spi_bit_order == SPI_BITORDER_MSB) ? spiTransfer(txval) : _flip_bits_8(spiTransfer(_flip_bits_8(txval))); } uint16_t spiRec16(uint16_t txval) { diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index e4c894c7835e..69e499da50d4 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -129,6 +129,8 @@ spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); } + void spiEstablish() { /* do nothing */ } + /** * @brief Receives a single byte from the SPI port. * diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp index 7ea6cc6f9acd..b7d5f9c43395 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp @@ -989,6 +989,10 @@ extern "C" { } } + void spiEstablish() { + _HAL_SPI_UpdateTransaction(SPI_DATASIZE_8BIT); + } + #if ENABLED(HAL_SPI_SUPPORTS_ASYNC) static void _DMA_Interrupt( void ) { diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp index 084764eaa510..0c9868a74d4d 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp @@ -138,6 +138,8 @@ SPI.setDataMode(SPI_MODE3); } + void spiEstablish() { /* do nothing */ } + /** * @brief Receives a single byte from the SPI port. * diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index f8c5e4bf12e7..3fdb72874f8c 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -101,6 +101,8 @@ void spiSetClockMode(int clockMode) { spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); } +void spiEstablish() { /* do nothing */ } + // SPI receive a byte uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index af12e44e09ad..2458a40ec3d1 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -100,6 +100,8 @@ void spiSetClockMode(int clockMode) { spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); } +void spiEstablish() { /* do nothing */ } + uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); uint8_t returnByte = SPI.transfer(txval); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 09fec4f2650e..9c36696b3891 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -114,6 +114,8 @@ void spiSetClockMode(int clockMode) { spiConfig = SPISettings(_spi_clock, _spi_bitOrder, _spi_clockMode); } +void spiEstablish() { /* do nothing */ } + uint8_t spiRec(uint8_t txval) { SPI.beginTransaction(spiConfig); uint8_t returnByte = SPI.transfer(txval); diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index e47e68bf91cc..db0cabe18b15 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -90,6 +90,12 @@ void spiSetBitOrder(int bitOrder); // Specifies the CLKMODE. void spiSetClockMode(int mode); +// Forces the initialization of the SPI transfer (setting SCK, etc). +// Needed when certain machines have no chip-select pin but require signal stabilization before init +// (AVR flashing, etc). +// Done implicitly by SPI transaction functions (spiSend, spiRec, etc). +void spiEstablish(); + // Write single byte to SPI. // The byte is sent in the requested bit-order. void spiSend(uint8_t b); diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h index 8bcb263bc1fd..690df5b3d7a5 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h @@ -23,6 +23,7 @@ /** * Cheaptronic v1.0 pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -31,46 +32,46 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 2 -#define Z_STOP_PIN 5 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinE4 +#define Z_STOP_PIN PinE3 // // Steppers // -#define X_STEP_PIN 14 -#define X_DIR_PIN 15 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinJ1 +#define X_DIR_PIN PinJ0 +#define X_ENABLE_PIN PinA2 -#define Y_STEP_PIN 35 -#define Y_DIR_PIN 36 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN PinC2 +#define Y_DIR_PIN PinC1 +#define Y_ENABLE_PIN PinC6 -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 41 -#define Z_ENABLE_PIN 37 +#define Z_STEP_PIN PinG1 +#define Z_DIR_PIN PinG0 +#define Z_ENABLE_PIN PinC0 -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 25 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA3 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC4 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 // // Temperature sensors // -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 14 // Analog Input -#define TEMP_BED_PIN 13 // Analog Input +#define TEMP_0_PIN PinJ0 // Analog Input +#define TEMP_1_PIN PinJ1 // Analog Input +#define TEMP_BED_PIN PinB7 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 19 // EXTRUDER 1 -#define HEATER_1_PIN 23 // EXTRUDER 2 -#define HEATER_BED_PIN 22 +#define HEATER_0_PIN PinD2 // EXTRUDER 1 +#define HEATER_1_PIN PinA1 // EXTRUDER 2 +#define HEATER_BED_PIN PinA0 // // LCD / Controller diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index 01438975b979..9c2b1d82de03 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -25,6 +25,7 @@ * Cheaptronic v2.0 pin assignments * Built and sold by Michal Dyntar - RRO * www.reprapobchod.cz + * ATmega2560 */ #include "env_validate.h" @@ -34,88 +35,88 @@ // // Limit Switches // -#define X_MIN_PIN 30 -#define X_MAX_PIN 31 -#define Y_MIN_PIN 32 -#define Y_MAX_PIN 33 -#define Z_MIN_PIN 34 -#define Z_MAX_PIN 35 +#define X_MIN_PIN PinC7 +#define X_MAX_PIN PinC6 +#define Y_MIN_PIN PinC5 +#define Y_MAX_PIN PinC4 +#define Z_MIN_PIN PinC3 +#define Z_MAX_PIN PinC2 // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN PinH0 +#define X_DIR_PIN PinH1 +#define X_ENABLE_PIN PinL1 -#define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 -#define Y_ENABLE_PIN 55 +#define Y_STEP_PIN PinF0 +#define Y_DIR_PIN PinL2 +#define Y_ENABLE_PIN PinF1 -#define Z_STEP_PIN 57 -#define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinF3 +#define Z_DIR_PIN PinF2 +#define Z_ENABLE_PIN PinK0 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 22 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA1 +#define E0_DIR_PIN PinA0 +#define E0_ENABLE_PIN PinA2 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 25 -#define E1_ENABLE_PIN 27 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA3 +#define E1_ENABLE_PIN PinA5 -#define E2_STEP_PIN 29 -#define E2_DIR_PIN 28 -#define E2_ENABLE_PIN 39 +#define E2_STEP_PIN PinA7 +#define E2_DIR_PIN PinA6 +#define E2_ENABLE_PIN PinG2 // // Temperature sensors // -#define TEMP_0_PIN 15 -#define TEMP_1_PIN 13 -#define TEMP_2_PIN 14 -#define TEMP_3_PIN 11 // should be used for chamber temperature control -#define TEMP_BED_PIN 12 +#define TEMP_0_PIN PinJ0 +#define TEMP_1_PIN PinB7 +#define TEMP_2_PIN PinJ1 +#define TEMP_3_PIN PinB5 // should be used for chamber temperature control +#define TEMP_BED_PIN PinB6 // // Heaters / Fans // -#define HEATER_0_PIN 6 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 8 -#define HEATER_BED_PIN 9 +#define HEATER_0_PIN PinH3 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinH5 +#define HEATER_BED_PIN PinH6 #ifndef FAN_PIN - #define FAN_PIN 3 + #define FAN_PIN PinE5 #endif -#define FAN2_PIN 58 // additional fan or light control output +#define FAN2_PIN PinF4 // additional fan or light control output // // Other board specific pins // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 37 // board input labeled as F-DET + #define FIL_RUNOUT_PIN PinC0 // board input labeled as F-DET #endif -#define Z_MIN_PROBE_PIN 36 // additional external board input labeled as E-SENS (should be used for Z-probe) -#define LED_PIN 13 -#define SPINDLE_ENABLE_PIN 4 // additional PWM pin 1 at JP1 connector - should be used for laser control too -#define EXT_2 5 // additional PWM pin 2 at JP1 connector -#define EXT_3 2 // additional PWM pin 3 at JP1 connector -#define PS_ON_PIN 45 -#define KILL_PIN 46 +#define Z_MIN_PROBE_PIN PinC1 // additional external board input labeled as E-SENS (should be used for Z-probe) +#define LED_PIN PinB7 +#define SPINDLE_ENABLE_PIN PinG5 // additional PWM pin 1 at JP1 connector - should be used for laser control too +#define EXT_2 PinE3 // additional PWM pin 2 at JP1 connector +#define EXT_3 PinE4 // additional PWM pin 3 at JP1 connector +#define PS_ON_PIN PinL4 +#define KILL_PIN PinL3 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 11 // shared with TEMP_3 analog input + #define FILWIDTH_PIN PinB5 // shared with TEMP_3 analog input #endif // // LCD / Controller // -#define LCD_PINS_RS 19 -#define LCD_PINS_ENABLE 42 -#define LCD_PINS_D4 18 -#define LCD_PINS_D5 38 -#define LCD_PINS_D6 41 -#define LCD_PINS_D7 40 +#define LCD_PINS_RS PinD2 +#define LCD_PINS_ENABLE PinL7 +#define LCD_PINS_D4 PinD3 +#define LCD_PINS_D5 PinD7 +#define LCD_PINS_D6 PinG0 +#define LCD_PINS_D7 PinG1 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder @@ -124,15 +125,15 @@ // // Beeper, SD Card, Encoder // -#define BEEPER_PIN 44 +#define BEEPER_PIN PinL5 #if ENABLED(SDSUPPORT) - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS PinB0 + #define SD_DETECT_PIN PinL0 #endif #if IS_NEWPANEL - #define BTN_EN1 11 - #define BTN_EN2 12 - #define BTN_ENC 43 + #define BTN_EN1 PinB5 + #define BTN_EN2 PinB6 + #define BTN_ENC PinL6 #endif diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index 5f7a534d115b..b6453167602a 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -23,6 +23,7 @@ /** * CartesioV11 pin assignments + * ATmega2560, ATmega1280 */ #define ALLOW_MEGA1280 @@ -33,71 +34,71 @@ // // Limit Switches // -#define X_STOP_PIN 43 -#define Y_STOP_PIN 45 -#define Z_STOP_PIN 42 +#define X_STOP_PIN PinL6 +#define Y_STOP_PIN PinL4 +#define Z_STOP_PIN PinL7 // // Steppers // -#define X_STEP_PIN 34 -#define X_DIR_PIN 36 -#define X_ENABLE_PIN 35 +#define X_STEP_PIN PinC3 +#define X_DIR_PIN PinC1 +#define X_ENABLE_PIN PinC2 -#define Y_STEP_PIN 37 -#define Y_DIR_PIN 39 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN PinC0 +#define Y_DIR_PIN PinG2 +#define Y_ENABLE_PIN PinD7 -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 41 +#define Z_STEP_PIN PinG1 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinG0 -#define E0_STEP_PIN 29 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 3 +#define E0_STEP_PIN PinA7 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinE5 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define E1_ENABLE_PIN 60 +#define E1_STEP_PIN PinF7 +#define E1_DIR_PIN PinK0 +#define E1_ENABLE_PIN PinF6 -#define E2_STEP_PIN 15 -#define E2_DIR_PIN 14 -#define E2_ENABLE_PIN 16 +#define E2_STEP_PIN PinJ0 +#define E2_DIR_PIN PinJ1 +#define E2_ENABLE_PIN PinH1 -#define E3_STEP_PIN 44 -#define E3_DIR_PIN 49 -#define E3_ENABLE_PIN 47 +#define E3_STEP_PIN PinL5 +#define E3_DIR_PIN PinL0 +#define E3_ENABLE_PIN PinL2 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 3 // Analog Input. 3 for tool2 -> 2 for chambertemp -#define TEMP_2_PIN 2 // Analog Input. 9 for tool3 -> 2 for chambertemp -#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 2 for chambertemp -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_1_PIN PinE5 // Analog Input. 3 for tool2 -> 2 for chambertemp +#define TEMP_2_PIN PinE4 // Analog Input. 9 for tool3 -> 2 for chambertemp +#define TEMP_3_PIN PinB5 // Analog Input. 11 for tool4 -> 2 for chambertemp +#define TEMP_BED_PIN PinE1 // Analog Input #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 2 // Analog Input + //#define TEMP_CHAMBER_PIN PinE4 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 5 -#define HEATER_1_PIN 58 -#define HEATER_2_PIN 64 -#define HEATER_3_PIN 46 -#define HEATER_BED_PIN 2 +#define HEATER_0_PIN PinE3 +#define HEATER_1_PIN PinF4 +#define HEATER_2_PIN PinK2 +#define HEATER_3_PIN PinL3 +#define HEATER_BED_PIN PinE4 #ifndef FAN_PIN - //#define FAN_PIN 7 // common PWM pin for all tools + //#define FAN_PIN PinH4 // common PWM pin for all tools #endif // // Auto fans // -#define AUTO_FAN_PIN 7 +#define AUTO_FAN_PIN PinH4 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN AUTO_FAN_PIN #endif @@ -114,49 +115,49 @@ // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 13 +#define SDSS PinB0 +#define SD_DETECT_PIN PinB7 // Tools -//#define TOOL_0_PIN 4 -//#define TOOL_1_PIN 59 -//#define TOOL_2_PIN 8 -//#define TOOL_3_PIN 30 -//#define TOOL_PWM_PIN 7 // common PWM pin for all tools +//#define TOOL_0_PIN PinG5 +//#define TOOL_1_PIN PinF5 +//#define TOOL_2_PIN PinH5 +//#define TOOL_3_PIN PinC7 +//#define TOOL_PWM_PIN PinH4 // common PWM pin for all tools // Common I/O //#define FIL_RUNOUT_PIN -1 -//#define PWM_1_PIN 11 -//#define PWM_2_PIN 10 -//#define SPARE_IO 12 +//#define PWM_1_PIN PinB5 +//#define PWM_2_PIN PinB4 +//#define SPARE_IO PinB6 // // LCD / Controller // #if HAS_WIRED_LCD - #define BEEPER_PIN 6 + #define BEEPER_PIN PinH3 - #define BTN_EN1 23 - #define BTN_EN2 25 - #define BTN_ENC 27 + #define BTN_EN1 PinA1 + #define BTN_EN2 PinA3 + #define BTN_ENC PinA5 #if HAS_MARLINUI_U8GLIB - #define DOGLCD_A0 26 - #define DOGLCD_CS 24 + #define DOGLCD_A0 PinA4 + #define DOGLCD_CS PinA2 #define DOGLCD_MOSI -1 // Prevent auto-define by Conditionals_post.h #define DOGLCD_SCK -1 #endif #endif // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT_PIN 19 -#define SHIFT_LD_PIN 18 -#define SHIFT_CLK_PIN 17 +#define SHIFT_OUT_PIN PinD2 +#define SHIFT_LD_PIN PinD3 +#define SHIFT_CLK_PIN PinH0 -//#define UI1 31 -//#define UI2 22 +//#define UI1 PinC6 +//#define UI2 PinA0 #define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 31 +#define STAT_LED_RED_PIN PinC6 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 0aa0b59ca945..0bfab09187ec 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -23,6 +23,7 @@ /** * CartesioV12 pin assignments + * ATmega2560, ATmega1280 */ #define ALLOW_MEGA1280 @@ -33,71 +34,71 @@ // // Limit Switches // -#define X_STOP_PIN 19 -#define Y_STOP_PIN 22 -#define Z_STOP_PIN 23 +#define X_STOP_PIN PinD2 +#define Y_STOP_PIN PinA0 +#define Z_STOP_PIN PinA1 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 27 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA5 +#define X_ENABLE_PIN PinA4 -#define Y_STEP_PIN 28 -#define Y_DIR_PIN 30 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinA6 +#define Y_DIR_PIN PinC7 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 31 -#define Z_DIR_PIN 33 -#define Z_ENABLE_PIN 32 +#define Z_STEP_PIN PinC6 +#define Z_DIR_PIN PinC4 +#define Z_ENABLE_PIN PinC5 -#define E0_STEP_PIN 57 -#define E0_DIR_PIN 55 -#define E0_ENABLE_PIN 58 +#define E0_STEP_PIN PinF3 +#define E0_DIR_PIN PinF1 +#define E0_ENABLE_PIN PinF4 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define E1_ENABLE_PIN 60 +#define E1_STEP_PIN PinF7 +#define E1_DIR_PIN PinK0 +#define E1_ENABLE_PIN PinF6 -#define E2_STEP_PIN 46 -#define E2_DIR_PIN 66 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN PinL3 +#define E2_DIR_PIN PinK4 +#define E2_ENABLE_PIN PinL5 -#define E3_STEP_PIN 45 -#define E3_DIR_PIN 69 -#define E3_ENABLE_PIN 47 +#define E3_STEP_PIN PinL4 +#define E3_DIR_PIN PinK7 +#define E3_ENABLE_PIN PinL2 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 9 // Analog Input. 9 for tool2 -> 13 for chambertemp -#define TEMP_2_PIN 13 // Analog Input. 10 for tool3 -> 13 for chambertemp -#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 13 for chambertemp -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_1_PIN PinH6 // Analog Input. 9 for tool2 -> 13 for chambertemp +#define TEMP_2_PIN PinB7 // Analog Input. 10 for tool3 -> 13 for chambertemp +#define TEMP_3_PIN PiNB5 // Analog Input. 11 for tool4 -> 13 for chambertemp +#define TEMP_BED_PIN PinJ1 // Analog Input #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 13 // Analog Input + //#define TEMP_CHAMBER_PIN PinB7 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 11 -#define HEATER_1_PIN 9 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 3 -#define HEATER_BED_PIN 24 +#define HEATER_0_PIN PinB5 +#define HEATER_1_PIN PinH6 +#define HEATER_2_PIN PinH3 +#define HEATER_3_PIN PinE5 +#define HEATER_BED_PIN PinA2 #ifndef FAN_PIN - #define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools + #define FAN_PIN PinE3 // 5 is PWMtool3 -> 7 is common PWM pin for all tools #endif // // Auto fans // -#define AUTO_FAN_PIN 7 +#define AUTO_FAN_PIN PinH4 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN AUTO_FAN_PIN #endif @@ -114,56 +115,56 @@ // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 15 +#define SDSS PinB0 +#define SD_DETECT_PIN PinJ0 // Tools -//#define TOOL_0_PIN 56 -//#define TOOL_0_PWM_PIN 10 // red warning led at dual extruder -//#define TOOL_1_PIN 59 -//#define TOOL_1_PWM_PIN 8 // lights at dual extruder -//#define TOOL_2_PIN 4 -//#define TOOL_2_PWM_PIN 5 -//#define TOOL_3_PIN 14 -//#define TOOL_3_PWM_PIN 2 +//#define TOOL_0_PIN PinF2 +//#define TOOL_0_PWM_PIN PinB4 // red warning led at dual extruder +//#define TOOL_1_PIN PinF5 +//#define TOOL_1_PWM_PIN PinH5 // lights at dual extruder +//#define TOOL_2_PIN PinG5 +//#define TOOL_2_PWM_PIN PinE3 +//#define TOOL_3_PIN PinJ1 +//#define TOOL_3_PWM_PIN PinE4 // Common I/O #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 18 + #define FIL_RUNOUT_PIN PinD3 #endif -//#define PWM_1_PIN 12 -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 +//#define PWM_1_PIN PinB6 +//#define PWM_2_PIN PinB7 +//#define SPARE_IO PinH0 // // LCD / Controller // #if HAS_WIRED_LCD - #define BEEPER_PIN 16 + #define BEEPER_PIN PinH1 - #define BTN_EN1 36 - #define BTN_EN2 34 - #define BTN_ENC 38 + #define BTN_EN1 PinC1 + #define BTN_EN2 PinC3 + #define BTN_ENC PinD7 #if HAS_MARLINUI_U8GLIB - #define DOGLCD_A0 39 - #define DOGLCD_CS 35 - #define DOGLCD_MOSI 48 - #define DOGLCD_SCK 49 + #define DOGLCD_A0 PinG2 + #define DOGLCD_CS PinC2 + #define DOGLCD_MOSI PinL1 + #define DOGLCD_SCK PinL0 #endif #endif // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT_PIN 42 -#define SHIFT_LD_PIN 41 -#define SHIFT_CLK_PIN 40 +#define SHIFT_OUT_PIN PinL7 +#define SHIFT_LD_PIN PinG0 +#define SHIFT_CLK_PIN PinG1 -//#define UI1 43 -//#define UI2 37 +//#define UI1 PinL6 +//#define UI2 PinC0 #define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 10 // TOOL_0_PWM_PIN +#define STAT_LED_RED_PIN PinB4 // TOOL_0_PWM_PIN #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index 6de3b7172eb0..8ab256afd83d 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -23,6 +23,7 @@ /** * CNControls V15 for HMS434 pin assignments + * ATmega2560, ATmega1280 */ #define ALLOW_MEGA1280 @@ -33,65 +34,65 @@ // // Servos // -#define SERVO0_PIN 6 +#define SERVO0_PIN PinH3 // // Limit Switches // -#define X_STOP_PIN 34 -#define Y_STOP_PIN 39 -#define Z_STOP_PIN 62 +#define X_STOP_PIN PinC3 +#define Y_STOP_PIN PinG2 +#define Z_STOP_PIN PinK0 #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 49 + #define Z_MIN_PROBE_PIN PinL0 #endif // // Steppers // -#define X_STEP_PIN 14 -#define X_DIR_PIN 25 -#define X_ENABLE_PIN 26 +#define X_STEP_PIN PinJ1 +#define X_DIR_PIN PinA3 +#define X_ENABLE_PIN PinA4 -#define Y_STEP_PIN 11 -#define Y_DIR_PIN 12 -#define Y_ENABLE_PIN 15 +#define Y_STEP_PIN PinB5 +#define Y_DIR_PIN PinB6 +#define Y_ENABLE_PIN PinJ0 -#define Z_STEP_PIN 24 -#define Z_DIR_PIN 27 -#define Z_ENABLE_PIN 28 +#define Z_STEP_PIN PinA2 +#define Z_DIR_PIN PinA5 +#define Z_ENABLE_PIN PinA6 -#define E0_STEP_PIN 64 -#define E0_DIR_PIN 65 -#define E0_ENABLE_PIN 63 +#define E0_STEP_PIN PinK2 +#define E0_DIR_PIN PinK3 +#define E0_ENABLE_PIN PinK1 // // Temperature Sensors // Analog Inputs // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 4 // Analog Input +#define TEMP_0_PIN PinE4 // Analog Input +#define TEMP_BED_PIN PinG5 // Analog Input #ifndef TEMP_CHAMBER_PIN - #define TEMP_CHAMBER_PIN 5 // Analog Input + #define TEMP_CHAMBER_PIN PinE3 // Analog Input #endif // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 32 -#define HEATER_CHAMBER_PIN 33 +#define HEATER_0_PIN PinG5 +#define HEATER_BED_PIN PinC5 +#define HEATER_CHAMBER_PIN PinC4 // // Fans // -#define FAN_PIN 8 +#define FAN_PIN PinH5 // // Auto fans // -#define AUTO_FAN_PIN 30 +#define AUTO_FAN_PIN PinC7 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN AUTO_FAN_PIN #endif @@ -105,22 +106,22 @@ #define E3_AUTO_FAN_PIN AUTO_FAN_PIN #endif #ifndef CHAMBER_AUTO_FAN_PIN - //#define CHAMBER_AUTO_FAN_PIN 10 + //#define CHAMBER_AUTO_FAN_PIN PinB4 #endif // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 40 +#define SDSS PinB0 +#define SD_DETECT_PIN PinG1 // Common I/O -#define FIL_RUNOUT_PIN 9 -//#define FIL_RUNOUT_PIN 29 // encoder sensor -//#define PWM_1_PIN 12 -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 -#define BEEPER_PIN 13 +#define FIL_RUNOUT_PIN PinH6 +//#define FIL_RUNOUT_PIN PinA7 // encoder sensor +//#define PWM_1_PIN PinB6 +//#define PWM_2_PIN PinB7 +//#define SPARE_IO PinH0 +#define BEEPER_PIN PinB7 #define STAT_LED_BLUE_PIN -1 -#define STAT_LED_RED_PIN 10 // 31 +#define STAT_LED_RED_PIN PinB4 // 31 diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index c8cbee674011..2964e7c17ed9 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -23,6 +23,7 @@ /** * Einstart-S pin assignments + * ATmega2560, ATmega1280 * PCB Silkscreen: 3DPrinterCon_v3.5 */ @@ -34,48 +35,48 @@ // // Limit Switches // -#define X_STOP_PIN 44 -#define Y_STOP_PIN 43 -#define Z_STOP_PIN 42 +#define X_STOP_PIN PinL5 +#define Y_STOP_PIN PinL6 +#define Z_STOP_PIN PinL7 // // Steppers // -#define X_STEP_PIN 76 -#define X_DIR_PIN 75 -#define X_ENABLE_PIN 73 +#define X_STEP_PIN PinJ5 +#define X_DIR_PIN PinJ4 +#define X_ENABLE_PIN PinJ3 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 32 -#define Y_ENABLE_PIN 72 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC5 +#define Y_ENABLE_PIN PinJ2 -#define Z_STEP_PIN 34 -#define Z_DIR_PIN 35 -#define Z_ENABLE_PIN 33 +#define Z_STEP_PIN PinC3 +#define Z_DIR_PIN PinC2 +#define Z_ENABLE_PIN PinC4 -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 37 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC0 +#define E0_ENABLE_PIN PinC7 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_BED_PIN PinE1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 83 -#define HEATER_BED_PIN 38 +#define HEATER_0_PIN PinD6 +#define HEATER_BED_PIN PinD7 -#define FAN_PIN 82 +#define FAN_PIN PinD5 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 4 +#define SDSS PinB0 +#define LED_PIN PinG5 ////////////////////////// // LCDs and Controllers // @@ -89,24 +90,24 @@ // u8glib constructor // U8GLIB_SH1106_128X64 u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, LCD_PINS_DC, LCD_PINS_RS); -#define LCD_PINS_DC 78 -#define LCD_PINS_RS 79 +#define LCD_PINS_DC PinE2 +#define LCD_PINS_RS PinE6 // DOGM SPI LCD Support -#define DOGLCD_CS 3 -#define DOGLCD_MOSI 2 -#define DOGLCD_SCK 5 -#define DOGLCD_A0 2 +#define DOGLCD_CS PinE5 +#define DOGLCD_MOSI PinE4 +#define DOGLCD_SCK PinE3 +#define DOGLCD_A0 PinE4 // // LCD Display input pins // -#define BTN_UP 25 -#define BTN_DOWN 26 -#define BTN_LEFT 27 -#define BTN_RIGHT 28 +#define BTN_UP PinA3 +#define BTN_DOWN PinA4 +#define BTN_LEFT PinA5 +#define BTN_RIGHT PinA6 // 'OK' button -#define BTN_ENC 29 +#define BTN_ENC PinA7 // Set Kill to right arrow, same as RIGID_PANEL -#define KILL_PIN 28 +#define KILL_PIN PinA6 diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index f5e146cff99c..223f2a9520c3 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -23,6 +23,7 @@ /** * Elefu RA Board Pin Assignments + * ATmega2560 */ #include "env_validate.h" @@ -32,96 +33,96 @@ // // Limit Switches // -#define X_MIN_PIN 35 -#define X_MAX_PIN 34 -#define Y_MIN_PIN 33 -#define Y_MAX_PIN 32 -#define Z_MIN_PIN 31 -#define Z_MAX_PIN 30 +#define X_MIN_PIN PinC2 +#define X_MAX_PIN PinC3 +#define Y_MIN_PIN PinC4 +#define Y_MAX_PIN PinC5 +#define Z_MIN_PIN PinC6 +#define Z_MAX_PIN PinC7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN PinC7 #endif // // Steppers // -#define X_STEP_PIN 49 -#define X_DIR_PIN 13 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN PinL0 +#define X_DIR_PIN PinB7 +#define X_ENABLE_PIN PinL1 -#define Y_STEP_PIN 11 -#define Y_DIR_PIN 9 -#define Y_ENABLE_PIN 12 +#define Y_STEP_PIN PinB5 +#define Y_DIR_PIN PinH6 +#define Y_ENABLE_PIN PinB6 -#define Z_STEP_PIN 7 -#define Z_DIR_PIN 6 -#define Z_ENABLE_PIN 8 +#define Z_STEP_PIN PinH4 +#define Z_DIR_PIN PinH3 +#define Z_ENABLE_PIN PinH5 -#define E0_STEP_PIN 40 -#define E0_DIR_PIN 41 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN PinG1 +#define E0_DIR_PIN PinG0 +#define E0_ENABLE_PIN PinC0 -#define E1_STEP_PIN 18 -#define E1_DIR_PIN 19 -#define E1_ENABLE_PIN 38 +#define E1_STEP_PIN PinD3 +#define E1_DIR_PIN PinD2 +#define E1_ENABLE_PIN PinD7 -#define E2_STEP_PIN 43 -#define E2_DIR_PIN 47 -#define E2_ENABLE_PIN 42 +#define E2_STEP_PIN PinL6 +#define E2_DIR_PIN PinL2 +#define E2_ENABLE_PIN PinL7 // // Temperature Sensors // -#define TEMP_0_PIN 3 // Analog Input -#define TEMP_1_PIN 2 // Analog Input -#define TEMP_2_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN PinE5 // Analog Input +#define TEMP_1_PIN PinE4 // Analog Input +#define TEMP_2_PIN PinE1 // Analog Input +#define TEMP_BED_PIN PinE0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 45 // 12V PWM1 -#define HEATER_1_PIN 46 // 12V PWM2 -#define HEATER_2_PIN 17 // 12V PWM3 -#define HEATER_BED_PIN 44 // DOUBLE 12V PWM +#define HEATER_0_PIN PinL4 // 12V PWM1 +#define HEATER_1_PIN PinL3 // 12V PWM2 +#define HEATER_2_PIN PinH0 // 12V PWM3 +#define HEATER_BED_PIN PinL5 // DOUBLE 12V PWM #ifndef FAN_PIN - #define FAN_PIN 16 // 5V PWM + #define FAN_PIN PinH1 // 5V PWM #endif // // Misc. Functions // -#define PS_ON_PIN 10 // Set to -1 if using a manual switch on the PWRSW Connector -#define SLEEP_WAKE_PIN 26 // This feature still needs work -#define PHOTOGRAPH_PIN 29 +#define PS_ON_PIN PinB4 // Set to -1 if using a manual switch on the PWRSW Connector +#define SLEEP_WAKE_PIN PinA4 // This feature still needs work +#define PHOTOGRAPH_PIN PinA7 // // LCD / Controller // -#define BEEPER_PIN 36 +#define BEEPER_PIN PinC1 #if ENABLED(RA_CONTROL_PANEL) - #define SDSS 53 - #define SD_DETECT_PIN 28 + #define SDSS PinB0 + #define SD_DETECT_PIN PinA6 - #define BTN_EN1 14 - #define BTN_EN2 39 - #define BTN_ENC 15 + #define BTN_EN1 PinJ1 + #define BTN_EN2 PinG2 + #define BTN_ENC PinJ0 #endif // RA_CONTROL_PANEL #if ENABLED(RA_DISCO) // variables for which pins the TLC5947 is using - #define TLC_CLOCK_PIN 25 - #define TLC_BLANK_PIN 23 - #define TLC_XLAT_PIN 22 - #define TLC_DATA_PIN 24 + #define TLC_CLOCK_PIN PinA3 + #define TLC_BLANK_PIN PinA1 + #define TLC_XLAT_PIN PinA0 + #define TLC_DATA_PIN PinA2 // We also need to define pin to port number mapping for the 2560 to match the pins listed above. // If you change the TLC pins, update this as well per the 2560 datasheet! This currently only works with the RA Board. diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index 99e8704ea558..eb7191e70c5a 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -25,6 +25,7 @@ * Geeetech GT2560 Revision A board pin assignments, based on the work of * George Robles (https://georges3dprinters.com) and * Richard Smith + * ATmega2560 */ #define ALLOW_MEGA1280 @@ -35,128 +36,137 @@ #endif #define DEFAULT_MACHINE_NAME "Prusa i3 Pro B" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + +// See page 327 of the ATmega2560 technical reference manual (DS40002211A). +// For CPU speed calculations it is necessary to give the programmed "fuse bits", that are internally programmed +// MCU configuration data structures not accessible by the MCU instruction pipeline itself. +#define AVR_EFUSE_VALUE 0xFD +#define AVR_HFUSE_VALUE 0xD8 +#define AVR_LFUSE_VALUE 0xFF + // // Limit Switches // -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 -#define Z_MIN_PIN 30 +#define X_MIN_PIN PinA0 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinA4 +#define Y_MAX_PIN PinA6 +#define Z_MIN_PIN PinC7 #if ENABLED(BLTOUCH) #if MB(GT2560_REV_A_PLUS) - #define SERVO0_PIN 11 - #define Z_MAX_PIN 32 + #define SERVO0_PIN PinB5 + #define Z_MAX_PIN PinC5 #else - #define SERVO0_PIN 32 + #define SERVO0_PIN PinC5 #define Z_MAX_PIN -1 #endif #else - #define Z_MAX_PIN 32 + #define Z_MAX_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN PinC0 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinC2 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN PinL6 +#define E0_DIR_PIN PinL4 +#define E0_ENABLE_PIN PinG0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 // // Temperature Sensors // -#define TEMP_0_PIN 8 -#define TEMP_1_PIN 9 -#define TEMP_BED_PIN 10 +#define TEMP_0_PIN PinH5 +#define TEMP_1_PIN PinH6 +#define TEMP_BED_PIN PinB4 // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN PinH4 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 +#define SUICIDE_PIN PinF0 // Must be enabled at startup to keep power flowing #define KILL_PIN -1 #if HAS_WIRED_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN PinD3 #if IS_NEWPANEL #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 5 - #define DOGLCD_CS 21 - #define BTN_EN1 40 - #define BTN_EN2 42 + #define DOGLCD_A0 PinE3 + #define DOGLCD_CS PinD0 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinL7 #elif ENABLED(FYSETC_MINI_12864) // Disconnect EXP2-1 and EXP2-2, otherwise future firmware upload won't work. - #define DOGLCD_A0 20 - #define DOGLCD_CS 17 + #define DOGLCD_A0 PinD1 + #define DOGLCD_CS PinH0 - #define NEOPIXEL_PIN 21 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define NEOPIXEL_PIN PinD0 + #define BTN_EN1 PinL7 + #define BTN_EN2 PinG1 - #define LCD_RESET_PIN 16 + #define LCD_RESET_PIN PinH1 #define LCD_CONTRAST_INIT 220 #define LCD_BACKLIGHT_PIN -1 #else - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 - #define BTN_EN1 42 - #define BTN_EN2 40 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinH1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 + #define BTN_EN1 PinL7 + #define BTN_EN2 PinG1 #endif - #define BTN_ENC 19 - #define SD_DETECT_PIN 38 + #define BTN_ENC PinD2 + #define SD_DETECT_PIN PinD7 #else // !IS_NEWPANEL - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define SHIFT_CLK_PIN PinD7 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinH3 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinD1 + #define LCD_PINS_D7 PinD2 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h index 7e2ce20c6798..27b7accb0b24 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h @@ -23,6 +23,7 @@ /** * Geeetech GT2560 Revision A+ board pin assignments + * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 Rev.A+" @@ -30,5 +31,5 @@ #include "pins_GT2560_REV_A.h" #if DISABLED(BLTOUCH) - #define SERVO0_PIN 32 + #define SERVO0_PIN PinC5 #endif diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_B.h b/Marlin/src/pins/mega/pins_GT2560_REV_B.h index be71ec4902dc..d2732e34dc26 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_B.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_B.h @@ -23,6 +23,7 @@ /** * Geeetech GT2560 Rev B Pins + * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 Rev B" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 46b4ebf4287e..5c94f6360979 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -23,6 +23,7 @@ /** * Geeetech GT2560 3.0/3.1 pin assignments + * ATmega2560 * * Also GT2560 RevB and GT2560 4.0/4.1 */ @@ -37,33 +38,33 @@ // // Servos // -#define SERVO0_PIN 11 // 13 untested 3Dtouch +#define SERVO0_PIN PinB5 // 13 untested 3Dtouch // // Limit Switches // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 24 + #define X_MIN_PIN PinA2 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 22 + #define X_MAX_PIN PinA0 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 28 + #define Y_MIN_PIN PinA6 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 26 + #define Y_MAX_PIN PinA4 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 30 + #define Z_MIN_PIN PinC7 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 32 + #define Z_MAX_PIN PinC5 #endif #endif @@ -71,147 +72,147 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 66 + #define FIL_RUNOUT_PIN PinK4 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN 67 + #define FIL_RUNOUT2_PIN PinK5 #endif #ifndef FIL_RUNOUT3_PIN - #define FIL_RUNOUT3_PIN 54 + #define FIL_RUNOUT3_PIN PinF0 #endif // // Power Recovery // -#define POWER_LOSS_PIN 69 // Pin to detect power loss -#define POWER_LOSS_STATE LOW +#define POWER_LOSS_PIN PinK7 // Pin to detect power loss +#define POWER_LOSS_STATE LOW // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 39 -#define X_ENABLE_PIN 35 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinG2 +#define X_ENABLE_PIN PinC2 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 25 -#define Z_DIR_PIN 23 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN PinA3 +#define Z_DIR_PIN PinA1 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN 46 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 12 +#define E0_STEP_PIN PinL3 +#define E0_DIR_PIN PinL5 +#define E0_ENABLE_PIN PinB6 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 -#define E2_STEP_PIN 43 -#define E2_DIR_PIN 45 -#define E2_ENABLE_PIN 41 +#define E2_STEP_PIN PinL6 +#define E2_DIR_PIN PinL4 +#define E2_ENABLE_PIN PinG0 // // Temperature Sensors // -#define TEMP_0_PIN 11 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_2_PIN 8 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinB5 // Analog Input +#define TEMP_1_PIN PiNH6 // Analog Input +#define TEMP_2_PIN PinH5 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 3 -#define HEATER_2_PIN 2 -#define HEATER_BED_PIN 4 -#define FAN_PIN 9 -#define FAN1_PIN 8 -#define FAN2_PIN 7 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinE5 +#define HEATER_2_PIN PinE4 +#define HEATER_BED_PIN PinG5 +#define FAN_PIN PinH6 +#define FAN1_PIN PinH5 +#define FAN2_PIN PinH4 // // Misc. Functions // -#define SD_DETECT_PIN 38 -#define SDSS 53 -#define LED_PIN 13 // Use 6 (case light) for external LED. 13 is internal (yellow) LED. -#define PS_ON_PIN 12 +#define SD_DETECT_PIN PinD7 +#define SDSS PinB0 +#define LED_PIN PinB7 // Use 6 (case light) for external LED. 13 is internal (yellow) LED. +#define PS_ON_PIN PinB6 #if NUM_RUNOUT_SENSORS < 3 - #define SUICIDE_PIN 54 // This pin must be enabled at boot to keep power flowing + #define SUICIDE_PIN PinF0 // This pin must be enabled at boot to keep power flowing #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 6 // 21 + #define CASE_LIGHT_PIN PinH3 // 21 #endif // // LCD Controller // -#define BEEPER_PIN 18 +#define BEEPER_PIN PinD3 #if ENABLED(YHCB2004) #ifndef YHCB2004_CLK - #define YHCB2004_CLK 5 + #define YHCB2004_CLK PinE3 #define DIO52 YHCB2004_CLK #endif #ifndef YHCB2004_MOSI - #define YHCB2004_MOSI 21 + #define YHCB2004_MOSI PinD0 #define DIO50 YHCB2004_MOSI #endif #ifndef YHCB2004_MISO - #define YHCB2004_MISO 36 + #define YHCB2004_MISO PinC1 #define DIO51 YHCB2004_MISO #endif #elif HAS_WIRED_LCD #ifndef LCD_PINS_RS - #define LCD_PINS_RS 20 + #define LCD_PINS_RS PinD1 #endif #ifndef LCD_PINS_ENABLE - #define LCD_PINS_ENABLE 17 + #define LCD_PINS_ENABLE PinH0 #endif #ifndef LCD_PINS_D4 - #define LCD_PINS_D4 16 + #define LCD_PINS_D4 PinH1 #endif #ifndef LCD_PINS_D5 - #define LCD_PINS_D5 21 + #define LCD_PINS_D5 PinD0 #endif #ifndef LCD_PINS_D6 - #define LCD_PINS_D6 5 + #define LCD_PINS_D6 PinE3 #endif #ifndef LCD_PINS_D7 - #define LCD_PINS_D7 36 + #define LCD_PINS_D7 PinC1 #endif #endif #if ENABLED(YHCB2004) #ifndef BTN_EN1 - #define BTN_EN1 16 + #define BTN_EN1 PinH1 #endif #ifndef BTN_EN2 - #define BTN_EN2 17 + #define BTN_EN2 PinH0 #endif #ifndef BTN_ENC - #define BTN_ENC 19 + #define BTN_ENC PinD2 #endif #elif IS_NEWPANEL #ifndef BTN_EN1 - #define BTN_EN1 42 + #define BTN_EN1 PinL7 #endif #ifndef BTN_EN2 - #define BTN_EN2 40 + #define BTN_EN2 PinG1 #endif #ifndef BTN_ENC - #define BTN_ENC 19 + #define BTN_ENC PinD3 #endif #endif diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h index 986dd1cb04bb..1e1eccdac392 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_A20.h @@ -23,19 +23,20 @@ /** * Geeetech A20M board pin assignments + * ATmega2560 */ -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS PinE3 +#define LCD_PINS_ENABLE PinC1 +#define LCD_PINS_D4 PinD0 +#define LCD_PINS_D7 PinH3 #define SPEAKER // The speaker can produce tones #if IS_NEWPANEL - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 19 + #define BTN_EN1 PinH1 + #define BTN_EN2 PinH0 + #define BTN_ENC PinD2 #endif #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h index e683d4dfda4b..c63b8e9c591a 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3_MC2.h @@ -23,13 +23,14 @@ /** * Geeetech GT2560 V 3.0 board pin assignments (for Mecreator 2) + * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 V3.0 (MC2)" -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 +#define X_MIN_PIN PinA0 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinA4 +#define Y_MAX_PIN PinA6 #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V4_A20.h b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h index 83a612e67cdc..5427bacbea59 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V4_A20.h +++ b/Marlin/src/pins/mega/pins_GT2560_V4_A20.h @@ -23,21 +23,22 @@ /** * Geeetech A20 GT2560 V4.x board pin assignments + * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 4.x" -#define LCD_PINS_RS 5 -#define LCD_PINS_ENABLE 36 -#define LCD_PINS_D4 21 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS PinE3 +#define LCD_PINS_ENABLE PinC1 +#define LCD_PINS_D4 PinD0 +#define LCD_PINS_D7 PinH3 #define SPEAKER // The speaker can produce tones #if IS_NEWPANEL - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 19 + #define BTN_EN1 PinH1 + #define BTN_EN2 PinH0 + #define BTN_ENC PinD2 #endif #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 5c3b1dc9f6d6..11a65da03332 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -23,6 +23,7 @@ /** * Geeetech HJC2560-C Rev 2.x board pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -34,43 +35,43 @@ // Servos // //#ifndef SERVO0_PIN -// #define SERVO0_PIN 11 +// #define SERVO0_PIN PinB5 //#endif // // Limit Switches // -#define X_STOP_PIN 22 -#define Y_STOP_PIN 26 -#define Z_STOP_PIN 29 -//#define EXP_STOP_PIN 28 +#define X_STOP_PIN PinA0 +#define Y_STOP_PIN PinA4 +#define Z_STOP_PIN PinA7 +//#define EXP_STOP_PIN PinA6 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 32 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN PinC5 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinC6 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 36 -#define Z_ENABLE_PIN 34 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinC1 +#define Z_ENABLE_PIN PinC3 -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN PinL7 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinC0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 -#define MOTOR_CURRENT_PWM_XY_PIN 44 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 46 +#define MOTOR_CURRENT_PWM_XY_PIN PinL5 +#define MOTOR_CURRENT_PWM_Z_PIN PinL4 +#define MOTOR_CURRENT_PWM_E_PIN PinL3 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE #define MOTOR_CURRENT_PWM_RANGE 2000 @@ -80,42 +81,42 @@ // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +#define TEMP_1_PIN PinH6 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 7 //默认ä¸ä½¿ç”¨PWM_FAN冷å´å–·å˜´ï¼Œå¦‚果需è¦ï¼Œåˆ™å–消注释 + #define FAN_PIN PinH4 //默认ä¸ä½¿ç”¨PWM_FAN冷å´å–·å˜´ï¼Œå¦‚果需è¦ï¼Œåˆ™å–消注释 #endif // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 39 -//#define LED_PIN 8 +#define SDSS PinB0 +#define SD_DETECT_PIN PinG2 +//#define LED_PIN PinH5 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 8 // 8 默认挤出机风扇作为Case LED,如果需è¦PWM FAN,则需è¦å°†FAN_PIN置为7,LED_PIN置为8 + #define CASE_LIGHT_PIN PinH5 // 8 默认挤出机风扇作为Case LED,如果需è¦PWM FAN,则需è¦å°†FAN_PIN置为7,LED_PIN置为8 #endif -//#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered -//#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. +//#define SAFETY_TRIGGERED_PIN PinA6 // PIN to detect the safety circuit has triggered +//#define MAIN_VOLTAGE_MEASURE_PIN PinJ1 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pin should have a pullup! - #define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM + #define SPINDLE_DIR_PIN PinH1 + #define SPINDLE_LASER_ENA_PIN PinH0 // Pin should have a pullup! + #define SPINDLE_LASER_PWM_PIN PinH6 // Hardware PWM #endif // @@ -123,48 +124,48 @@ // #if HAS_WIRED_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN PinD3 #if IS_NEWPANEL - #define LCD_PINS_RS 20 // LCD_CS - #define LCD_PINS_ENABLE 15 // LCD_SDA - #define LCD_PINS_D4 14 // LCD_SCK + #define LCD_PINS_RS PinD1 // LCD_CS + #define LCD_PINS_ENABLE PinJ0 // LCD_SDA + #define LCD_PINS_D4 PinJ1 // LCD_SCK #if ENABLED(HJC_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 5 // LCD_Backlight + #define LCD_BACKLIGHT_PIN PinE3 // LCD_Backlight //#ifndef LCD_CONTRAST_PIN - // #define LCD_CONTRAST_PIN 5 // LCD_Contrast + // #define LCD_CONTRAST_PIN PinE3 // LCD_Contrast //#endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 24 // Filament runout + #define FIL_RUNOUT_PIN PinA2 // Filament runout #endif #else - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 #endif - #define BTN_EN1 41 - #define BTN_EN2 40 - #define BTN_ENC 19 + #define BTN_EN1 PinG0 + #define BTN_EN2 PinG1 + #define BTN_ENC PinD2 - #define SD_DETECT_PIN 39 + #define SD_DETECT_PIN PinG2 #else // Buttons attached to a shift register - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define SHIFT_CLK_PIN PinD7 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinH3 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinD1 + #define LCD_PINS_D7 PinD2 #endif // !IS_NEWPANEL diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index 2e2a9b85db14..9217b307ad97 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -23,6 +23,7 @@ /** * Intamsys Funmat HT V4.0 Mainboard + * ATmega2560 * 4988 Drivers Tested * 2208 version exists and may or may not work */ @@ -34,49 +35,49 @@ // // Servos // -#define SERVO0_PIN 12 // Uses High Temp Present Jumper Pin +#define SERVO0_PIN PinB6 // Uses High Temp Present Jumper Pin // // Limit Switches // -#define X_STOP_PIN 22 -#define Y_STOP_PIN 26 -#define Z_MIN_PIN 29 -#define Z_MAX_PIN 69 +#define X_STOP_PIN PinA0 +#define Y_STOP_PIN PinA4 +#define Z_MIN_PIN PinA7 +#define Z_MAX_PIN PinK7 #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 69 + #define Z_MIN_PROBE_PIN PinK7 #endif -#define FIL_RUNOUT_PIN 10 +#define FIL_RUNOUT_PIN PinB4 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 // 44 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 // 44 -#define Y_STEP_PIN 32 // 33 -#define Y_DIR_PIN 33 // 31, 32 -#define Y_ENABLE_PIN 31 // 32 +#define Y_STEP_PIN PinC5 // 33 +#define Y_DIR_PIN PinC4 // 31, 32 +#define Y_ENABLE_PIN PinC6 // 32 -#define Z_STEP_PIN 35 // 35 -#define Z_DIR_PIN 36 -#define Z_ENABLE_PIN 34 // 34 +#define Z_STEP_PIN PinC2 // 35 +#define Z_DIR_PIN PinC1 +#define Z_ENABLE_PIN PinC3 // 34 -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN PinL7 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinC0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 -#define MOTOR_CURRENT_PWM_X_PIN 11 -#define MOTOR_CURRENT_PWM_Y_PIN 44 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 46 +#define MOTOR_CURRENT_PWM_X_PIN PinB5 +#define MOTOR_CURRENT_PWM_Y_PIN PinL5 +#define MOTOR_CURRENT_PWM_Z_PIN PinL4 +#define MOTOR_CURRENT_PWM_E_PIN PinL3 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE @@ -87,49 +88,49 @@ // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input D62 -#define TEMP_BED_PIN 10 // Analog Input D64 +#define TEMP_0_PIN PinH5 // Analog Input D62 +#define TEMP_BED_PIN PinB4 // Analog Input D64 -#define TEMP_CHAMBER_PIN 9 // Analog Input D63 +#define TEMP_CHAMBER_PIN PinH6 // Analog Input D63 // // Heaters / Fans // -#define HEATER_0_PIN 2 // PWM -#define HEATER_BED_PIN 4 // PWM -#define HEATER_CHAMBER_PIN 3 // PWM -#define FAN_PIN 7 // PWM +#define HEATER_0_PIN PinE4 // PWM +#define HEATER_BED_PIN PinG5 // PWM +#define HEATER_CHAMBER_PIN PinE5 // PWM +#define FAN_PIN PinH4 // PWM // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 39 +#define SDSS PinB0 +#define SD_DETECT_PIN PinG2 #if ENABLED(CASE_LIGHT_ENABLE) - #define CASE_LIGHT_PIN 8 + #define CASE_LIGHT_PIN PinH5 #endif #if ENABLED(PSU_CONTROL) - #define PS_ON_PIN 38 // UPS Module + #define PS_ON_PIN PinD7 // UPS Module #endif // // LCD Controller // -#define BEEPER_PIN 18 +#define BEEPER_PIN PinD3 #if HAS_WIRED_LCD - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 30 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 - #define BTN_EN1 40 - #define BTN_EN2 41 - #define BTN_ENC 19 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_ENABLE PinC7 + #define LCD_PINS_D4 PinJ1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinG0 + #define BTN_ENC PinD2 #endif ///////////////////// SPARE HEADERS ////////////// diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index 4700fd6729bd..21d63aa9b622 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -23,6 +23,7 @@ /** * Leapfrog Driver board pin assignments + * ATmega2560, ATmega1280 */ #define ALLOW_MEGA1280 @@ -33,59 +34,59 @@ // // Limit Switches // -#define X_MIN_PIN 47 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 48 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 49 +#define X_MIN_PIN PinL2 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinL1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinL0 #define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN 28 -#define X_DIR_PIN 63 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN PinA6 +#define X_DIR_PIN PinK1 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 14 // A6 -#define Y_DIR_PIN 15 // A0 -#define Y_ENABLE_PIN 39 +#define Y_STEP_PIN PinJ1 // A6 +#define Y_DIR_PIN PinJ0 // A0 +#define Y_ENABLE_PIN PinG2 -#define Z_STEP_PIN 31 // A2 -#define Z_DIR_PIN 32 // A6 -#define Z_ENABLE_PIN 30 // A1 +#define Z_STEP_PIN PinC6 // A2 +#define Z_DIR_PIN PinC5 // A6 +#define Z_ENABLE_PIN PinC7 // A1 -#define E0_STEP_PIN 34 // 34 -#define E0_DIR_PIN 35 // 35 -#define E0_ENABLE_PIN 33 // 33 +#define E0_STEP_PIN PinC4 // 34 +#define E0_DIR_PIN PinC2 // 35 +#define E0_ENABLE_PIN PinC4 // 33 -#define E1_STEP_PIN 37 // 37 -#define E1_DIR_PIN 40 // 40 -#define E1_ENABLE_PIN 36 // 36 +#define E1_STEP_PIN PinC0 // 37 +#define E1_DIR_PIN PinG1 // 40 +#define E1_ENABLE_PIN PinC1 // 36 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input (D27) -#define TEMP_1_PIN 15 // Analog Input (1) -#define TEMP_BED_PIN 14 // Analog Input (1,2 or I2C) +#define TEMP_0_PIN PinB7 // Analog Input (D27) +#define TEMP_1_PIN PinJ0 // Analog Input (1) +#define TEMP_BED_PIN PinJ1 // Analog Input (1,2 or I2C) // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 // 12 -#define HEATER_2_PIN 11 // 13 -#define HEATER_BED_PIN 10 // 14/15 +#define HEATER_0_PIN PinH6 +#define HEATER_1_PIN PinH5 // 12 +#define HEATER_2_PIN PinB5 // 13 +#define HEATER_BED_PIN PinB4 // 14/15 -#define FAN_PIN 7 +#define FAN_PIN PinH4 // // Misc. Functions // -#define SDSS 11 -#define LED_PIN 13 -#define SOL1_PIN 16 -#define SOL2_PIN 17 +#define SDSS PinB5 +#define LED_PIN PinB7 +#define SOL1_PIN PinH1 +#define SOL2_PIN PinH0 /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index 4a32472949a3..d17382f4d494 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -23,6 +23,7 @@ /** * Leapfrog Xeed Driver board pin assignments + * ATmega2560 * * This board is used by other Leapfrog printers in addition to the Xeed, * such as the Creatr HS and Bolt. The pin assignments vary wildly between @@ -36,9 +37,9 @@ // // Limit Switches // -#define X_STOP_PIN 47 // 'X Min' -#define Y_STOP_PIN 48 // 'Y Min' -#define Z_STOP_PIN 49 // 'Z Min' +#define X_STOP_PIN PinL2 // 'X Min' +#define Y_STOP_PIN PinL1 // 'Y Min' +#define Z_STOP_PIN PinL0 // 'Z Min' // // Steppers @@ -49,65 +50,65 @@ // // X-axis signal-level connector -#define X_STEP_PIN 65 -#define X_DIR_PIN 64 -#define X_ENABLE_PIN 66 // Not actually used on Xeed, could be repurposed +#define X_STEP_PIN PinK3 +#define X_DIR_PIN PinK2 +#define X_ENABLE_PIN PinK4 // Not actually used on Xeed, could be repurposed // Y-axis signal-level connector -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 // Not actually used on Xeed, could be repurposed +#define Y_STEP_PIN PinA1 +#define Y_DIR_PIN PinA0 +#define Y_ENABLE_PIN PinA2 // Not actually used on Xeed, could be repurposed // ZMOT connector (Front Right Z Motor) -#define Z_STEP_PIN 31 -#define Z_DIR_PIN 32 -#define Z_ENABLE_PIN 30 +#define Z_STEP_PIN PinC6 +#define Z_DIR_PIN PinC5 +#define Z_ENABLE_PIN PinC7 // XMOT connector (Rear Z Motor) -#define Z2_STEP_PIN 28 -#define Z2_DIR_PIN 63 -#define Z2_ENABLE_PIN 29 +#define Z2_STEP_PIN PinA6 +#define Z2_DIR_PIN PinK1 +#define Z2_ENABLE_PIN PinA7 // YMOT connector (Front Left Z Motor) -#define Z3_STEP_PIN 14 -#define Z3_DIR_PIN 15 -#define Z3_ENABLE_PIN 39 +#define Z3_STEP_PIN PinJ1 +#define Z3_DIR_PIN PinJ0 +#define Z3_ENABLE_PIN PinG2 // EMOT2 connector -#define E0_STEP_PIN 37 -#define E0_DIR_PIN 40 -#define E0_ENABLE_PIN 36 +#define E0_STEP_PIN PinC0 +#define E0_DIR_PIN PinG1 +#define E0_ENABLE_PIN PinC1 // EMOT connector -#define E1_STEP_PIN 34 -#define E1_DIR_PIN 35 -#define E1_ENABLE_PIN 33 +#define E1_STEP_PIN PinC3 +#define E1_DIR_PIN PinC2 +#define E1_ENABLE_PIN PinC4 // // Filament Runout Sensor // -#define FIL_RUNOUT_PIN 42 // ROT2 Connector -#define FIL_RUNOUT2_PIN 44 // ROT1 Connector +#define FIL_RUNOUT_PIN PinL7 // ROT2 Connector +#define FIL_RUNOUT2_PIN PinL5 // ROT1 Connector // // Temperature Sensors // -#define TEMP_0_PIN 15 // T3 Connector -#define TEMP_1_PIN 13 // T1 Connector -#define TEMP_BED_PIN 14 // BED Connector (Between T1 and T3) +#define TEMP_0_PIN PinJ0 // T3 Connector +#define TEMP_1_PIN PinB7 // T1 Connector +#define TEMP_BED_PIN PinJ1 // BED Connector (Between T1 and T3) // // Heaters / Fans // -#define HEATER_0_PIN 8 // Misc Connector, pins 3 and 4 (Out2) -#define HEATER_1_PIN 9 // Misc Connector, pins 5 and 6 (Out3) -#define HEATER_BED_PIN 6 // Misc Connector, pins 9(-) and 10(+) (OutA) +#define HEATER_0_PIN PinH5 // Misc Connector, pins 3 and 4 (Out2) +#define HEATER_1_PIN PinH6 // Misc Connector, pins 5 and 6 (Out3) +#define HEATER_BED_PIN PinH3 // Misc Connector, pins 9(-) and 10(+) (OutA) -#define FAN_PIN 10 // Misc Connector, pins 7(-) and 8 (+) (Out4) +#define FAN_PIN PinB4 // Misc Connector, pins 7(-) and 8 (+) (Out4) -#define LED_PIN 13 +#define LED_PIN PinB7 -#define SOL1_PIN 7 // Misc Connector, pins 1(-) and 2(+) (Out1) +#define SOL1_PIN PinH4 // Misc Connector, pins 1(-) and 2(+) (Out1) // Door Closed Sensor -//#define DOOR_PIN 45 // HM1 Connector +//#define DOOR_PIN PinL4 // HM1 Connector diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h index 19095a53799f..4d8c42f12259 100644 --- a/Marlin/src/pins/mega/pins_MALYAN_M180.h +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -24,6 +24,8 @@ /** * Malyan M180 pin assignments * Contributed by Timo Birnschein (timo.birnschein@microforge.de) + * @Timo: sind diese Pin Definitionen immernoch korrekt? (Antwort an turningtides@outlook.de bitte) + * ATmega2560 */ #include "env_validate.h" @@ -32,9 +34,9 @@ // // Limit Switches // -#define X_STOP_PIN 48 -#define Y_STOP_PIN 46 -#define Z_STOP_PIN 42 +#define X_STOP_PIN PinL1 +#define Y_STOP_PIN PinL3 +#define Z_STOP_PIN PinL7 // // Z Probe (when not Z_MIN_PIN) @@ -46,40 +48,40 @@ // // Steppers // -#define X_STEP_PIN 55 -#define X_DIR_PIN 54 -#define X_ENABLE_PIN 56 +#define X_STEP_PIN PinF1 +#define X_DIR_PIN PinF0 +#define X_ENABLE_PIN PinF2 -#define Y_STEP_PIN 59 -#define Y_DIR_PIN 58 -#define Y_ENABLE_PIN 60 +#define Y_STEP_PIN PinF5 +#define Y_DIR_PIN PinF4 +#define Y_ENABLE_PIN PinF6 -#define Z_STEP_PIN 63 -#define Z_DIR_PIN 62 -#define Z_ENABLE_PIN 64 +#define Z_STEP_PIN PinK1 +#define Z_DIR_PIN PinK0 +#define Z_ENABLE_PIN PinK2 -#define E0_STEP_PIN 25 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN PinA3 +#define E0_DIR_PIN PinA2 +#define E0_ENABLE_PIN PinA4 -#define E1_STEP_PIN 29 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 39 +#define E1_STEP_PIN PinA7 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinG2 // // Temperature Sensors // -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_BED_PIN PinJ0 // Analog Input // Extruder thermocouples 0 and 1 are read out by two separate ICs using // SPI for MAX Thermocouple // Uses a separate SPI bus -#define TEMP_0_CS_PIN 5 // E3 - CS0 -#define TEMP_0_SCK_PIN 78 // E2 - SCK -#define TEMP_0_MISO_PIN 3 // E5 - MISO +#define TEMP_0_CS_PIN PinE3 // E3 - CS0 +#define TEMP_0_SCK_PIN PinE2 // E2 - SCK +#define TEMP_0_MISO_PIN PinE5 // E5 - MISO //#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define TEMP_1_CS_PIN 2 // E4 - CS1 +#define TEMP_1_CS_PIN PinE4 // E4 - CS1 #define TEMP_1_SCK_PIN TEMP_0_SCK_PIN #define TEMP_1_MISO_PIN TEMP_0_MISO_PIN //#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN @@ -87,14 +89,14 @@ // // Heaters / Fans // -#define HEATER_0_PIN 6 -#define HEATER_1_PIN 11 -#define HEATER_BED_PIN 45 +#define HEATER_0_PIN PinH3 +#define HEATER_1_PIN PinB5 +#define HEATER_BED_PIN PinL4 #ifndef FAN_PIN - #define FAN_PIN 7 // M106 Sxxx command supported and tested. M107 as well. + #define FAN_PIN PinH4 // M106 Sxxx command supported and tested. M107 as well. #endif #ifndef FAN_PIN1 - #define FAN_PIN1 12 // Currently Unsupported by Marlin + #define FAN_PIN1 PinB6 // Currently Unsupported by Marlin #endif diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 7ebef6e281cf..d0e117a2c467 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -23,6 +23,7 @@ /** * Mega controller pin assignments + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -36,86 +37,86 @@ // // Servos // -#define SERVO0_PIN 30 -#define SERVO1_PIN 31 -#define SERVO2_PIN 32 -#define SERVO3_PIN 33 +#define SERVO0_PIN PinC7 +#define SERVO1_PIN PinC6 +#define SERVO2_PIN PinC5 +#define SERVO3_PIN PinC4 // // Limit Switches // -#define X_MIN_PIN 43 -#define X_MAX_PIN 42 -#define Y_MIN_PIN 38 -#define Y_MAX_PIN 41 -#define Z_MIN_PIN 40 -#define Z_MAX_PIN 37 +#define X_MIN_PIN PinL6 +#define X_MAX_PIN PinL7 +#define Y_MIN_PIN PinD7 +#define Y_MAX_PIN PinG0 +#define Z_MIN_PIN PinG1 +#define Z_MAX_PIN PinC0 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 37 + #define Z_MIN_PROBE_PIN PinC0 #endif // // Steppers // -#define X_STEP_PIN 62 // A8 -#define X_DIR_PIN 63 // A9 -#define X_ENABLE_PIN 61 // A7 +#define X_STEP_PIN PinK0 // A8 +#define X_DIR_PIN PinK1 // A9 +#define X_ENABLE_PIN PinF7 // A7 -#define Y_STEP_PIN 65 // A11 -#define Y_DIR_PIN 66 // A12 -#define Y_ENABLE_PIN 64 // A10 +#define Y_STEP_PIN PinK3 // A11 +#define Y_DIR_PIN PinK4 // A12 +#define Y_ENABLE_PIN PinK2 // A10 -#define Z_STEP_PIN 68 // A14 -#define Z_DIR_PIN 69 // A15 -#define Z_ENABLE_PIN 67 // A13 +#define Z_STEP_PIN PinK6 // A14 +#define Z_DIR_PIN PinK7 // A15 +#define Z_ENABLE_PIN PinK5 // A13 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 22 +#define E0_STEP_PIN PinA1 +#define E0_DIR_PIN PinA2 +#define E0_ENABLE_PIN PinA0 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 27 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA5 +#define E1_ENABLE_PIN PinA3 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // Analog Input + #define TEMP_0_PIN PinG5 // Analog Input #else - #define TEMP_0_PIN 0 // Analog Input + #define TEMP_0_PIN PinE0 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // Analog Input + #define TEMP_1_PIN PinE3 // Analog Input #else - #define TEMP_1_PIN 2 // Analog Input + #define TEMP_1_PIN PinE4 // Analog Input #endif -#define TEMP_2_PIN 3 // Analog Input +#define TEMP_2_PIN PinE5 // Analog Input #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 6 // Analog Input + #define TEMP_BED_PIN PinH3 // Analog Input #else - #define TEMP_BED_PIN 1 // Analog Input + #define TEMP_BED_PIN PinE1 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 29 -#define HEATER_1_PIN 34 -#define HEATER_BED_PIN 28 +#define HEATER_0_PIN PinA7 +#define HEATER_1_PIN PinC3 +#define HEATER_BED_PIN PinA6 #ifndef FAN_PIN - #define FAN_PIN 39 + #define FAN_PIN PinG2 #endif -#define FAN1_PIN 35 -#define FAN2_PIN 36 +#define FAN1_PIN PinC2 +#define FAN2_PIN PinC1 #ifndef CONTROLLER_FAN_PIN #define CONTROLLER_FAN_PIN FAN2_PIN @@ -126,11 +127,11 @@ // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 2 + #define CASE_LIGHT_PIN PinE4 #endif // @@ -138,19 +139,19 @@ // #if ENABLED(MINIPANEL) - #define BEEPER_PIN 46 + #define BEEPER_PIN PinL3 - #define DOGLCD_A0 47 - #define DOGLCD_CS 45 - #define LCD_BACKLIGHT_PIN 44 // backlight LED on PA3 + #define DOGLCD_A0 PinL2 + #define DOGLCD_CS PinL4 + #define LCD_BACKLIGHT_PIN PinL5 // backlight LED on PA3 - #define KILL_PIN 12 + #define KILL_PIN PinB6 - #define BTN_EN1 48 - #define BTN_EN2 11 - #define BTN_ENC 10 + #define BTN_EN1 PinL1 + #define BTN_EN2 PinB5 + #define BTN_ENC PinB4 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN PinL0 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -159,6 +160,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 7 // Pullup! -#define SPINDLE_DIR_PIN 8 +#define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinH4 // Pullup! +#define SPINDLE_DIR_PIN PinH5 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index ac0ba4eea662..bf7dfe143f48 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -23,6 +23,7 @@ /** * MegaTronics pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -31,94 +32,94 @@ // // Limit Switches // -#define X_MIN_PIN 41 -#define X_MAX_PIN 37 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinG0 +#define X_MAX_PIN PinC0 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinA4 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinA2 -#define Y_STEP_PIN 60 // A6 -#define Y_DIR_PIN 61 // A7 -#define Y_ENABLE_PIN 22 +#define Y_STEP_PIN PinF6 // A6 (TODO: wtf? pin assignment? ff.) +#define Y_DIR_PIN PinF7 // A7 +#define Y_ENABLE_PIN -#define Z_STEP_PIN 54 // A0 -#define Z_DIR_PIN 55 // A1 -#define Z_ENABLE_PIN 56 // A2 +#define Z_STEP_PIN PinF0 // A0 +#define Z_DIR_PIN PinF1 // A1 +#define Z_ENABLE_PIN PinF2 // A2 -#define E0_STEP_PIN 31 -#define E0_DIR_PIN 32 -#define E0_ENABLE_PIN 38 +#define E0_STEP_PIN PinC6 +#define E0_DIR_PIN PinC5 +#define E0_ENABLE_PIN PinD7 -#define E1_STEP_PIN 34 -#define E1_DIR_PIN 36 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC3 +#define E1_DIR_PIN PinC1 +#define E1_ENABLE_PIN PinC7 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 8 // Analog Input + #define TEMP_0_PIN PinH5 // Analog Input #else - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN PinH6 +#define HEATER_1_PIN PinH5 +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 7 // IO pin. Buffer needed + #define FAN_PIN PinH4 // IO pin. Buffer needed #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 2 + #define CASE_LIGHT_PIN PinE4 #endif // // LCD / Controller // -#define BEEPER_PIN 33 +#define BEEPER_PIN PinC4 #if HAS_WIRED_LCD && IS_NEWPANEL - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 // Buttons directly attached to AUX-2 - #define BTN_EN1 59 - #define BTN_EN2 64 - #define BTN_ENC 43 + #define BTN_EN1 PinF5 + #define BTN_EN2 PinK2 + #define BTN_ENC PinL6 #define SD_DETECT_PIN -1 // RAMPS doesn't use this @@ -127,6 +128,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 4 // Pullup! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_PWM_PIN PinE5 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! +#define SPINDLE_DIR_PIN PinB5 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index e52703591063..bb5d2112f3eb 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -23,6 +23,7 @@ /** * MegaTronics v2.0 pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -31,123 +32,123 @@ // // Limit Switches // -#define X_MIN_PIN 37 -#define X_MAX_PIN 40 -#define Y_MIN_PIN 41 -#define Y_MAX_PIN 38 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinC0 +#define X_MAX_PIN PinG1 +#define Y_MIN_PIN PinG0 +#define Y_MAX_PIN PinD7 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 27 -#define X_ENABLE_PIN 25 +#define X_STEP_PIN PinA4 +#define X_DIR_PIN PinA5 +#define X_ENABLE_PIN PinA3 -#define Y_STEP_PIN 4 // A6 -#define Y_DIR_PIN 54 // A0 -#define Y_ENABLE_PIN 5 +#define Y_STEP_PIN PinG5 // A6 (??? pin mismatch!!!) +#define Y_DIR_PIN PinF0 // A0 +#define Y_ENABLE_PIN PinE3 -#define Z_STEP_PIN 56 // A2 -#define Z_DIR_PIN 60 // A6 -#define Z_ENABLE_PIN 55 // A1 +#define Z_STEP_PIN PinF2 // A2 +#define Z_DIR_PIN PinF6 // A6 +#define Z_ENABLE_PIN PinF1 // A1 -#define E0_STEP_PIN 35 -#define E0_DIR_PIN 36 -#define E0_ENABLE_PIN 34 +#define E0_STEP_PIN PinC2 +#define E0_DIR_PIN PinC1 +#define E0_ENABLE_PIN PinC3 -#define E1_STEP_PIN 29 -#define E1_DIR_PIN 39 -#define E1_ENABLE_PIN 28 - -#define E2_STEP_PIN 23 // ? schematic says 24 -#define E2_DIR_PIN 24 // ? schematic says 23 -#define E2_ENABLE_PIN 22 +#define E1_STEP_PIN PinA7 +#define E1_DIR_PIN PinG2 +#define E1_ENABLE_PIN PinA6 + +#define E2_STEP_PIN PinA1 // ? schematic says 24 (this comment is a sign of confusion by maintainers about the internal schematic numbering VS the internal numbering of AVR Marlin FW which should not matter!) +#define E2_DIR_PIN PinA2 // ? schematic says 23 +#define E2_ENABLE_PIN PinA0 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // Analog Input + #define TEMP_0_PIN PinG5 // Analog Input #else - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 8 // Analog Input + #define TEMP_1_PIN PinH5 // Analog Input #else - #define TEMP_1_PIN 15 // Analog Input + #define TEMP_1_PIN PinJ0 // Analog Input #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // Analog Input + #define TEMP_BED_PIN PinH5 // Analog Input #else - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN PinH6 +#define HEATER_1_PIN PinH5 +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN PinH4 #endif -#define FAN1_PIN 6 +#define FAN1_PIN PinH3 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 2 + #define CASE_LIGHT_PIN PinE4 #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 3 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 16 // Pullup! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_PWM_PIN PinE5 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinH1 // Pullup! +#define SPINDLE_DIR_PIN PinB5 // // LCD / Controller // -#define BEEPER_PIN 64 +#define BEEPER_PIN PinK2 #if HAS_WIRED_LCD - #define LCD_PINS_RS 14 - #define LCD_PINS_ENABLE 15 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 31 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 33 + #define LCD_PINS_RS PinJ1 + #define LCD_PINS_ENABLE PinJ0 + #define LCD_PINS_D4 PinC7 + #define LCD_PINS_D5 PinC6 + #define LCD_PINS_D6 PinC5 + #define LCD_PINS_D7 PinC4 #if IS_NEWPANEL // Buttons are directly attached using keypad - #define BTN_EN1 61 - #define BTN_EN2 59 - #define BTN_ENC 43 + #define BTN_EN1 PinF7 + #define BTN_EN2 PinF5 + #define BTN_ENC PinL6 #else // Buttons attached to shift register of reprapworld keypad v1.1 - #define SHIFT_CLK_PIN 63 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 17 - #define SHIFT_EN_PIN 17 + #define SHIFT_CLK_PIN PinK1 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinH0 + #define SHIFT_EN_PIN PinH0 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 86aff16f920e..ffe9a54e7d05 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -23,6 +23,7 @@ /** * MegaTronics v3.0 / v3.1 / v3.2 pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -38,141 +39,141 @@ // // Servos // -#define SERVO0_PIN 46 // AUX3-6 -#define SERVO1_PIN 47 // AUX3-5 -#define SERVO2_PIN 48 // AUX3-4 -#define SERVO3_PIN 49 // AUX3-3 +#define SERVO0_PIN PinL3 // AUX3-6 +#define SERVO1_PIN PinL2 // AUX3-5 +#define SERVO2_PIN PinL1 // AUX3-4 +#define SERVO3_PIN PinL0 // AUX3-3 // // Limit Switches // -#define X_MIN_PIN 37 // No INT -#define X_MAX_PIN 40 // No INT -#define Y_MIN_PIN 41 // No INT -#define Y_MAX_PIN 38 // No INT -#define Z_MIN_PIN 18 // No INT -#define Z_MAX_PIN 19 // No INT +#define X_MIN_PIN PinC0 // No INT +#define X_MAX_PIN PinG1 // No INT +#define Y_MIN_PIN PinG0 // No INT +#define Y_MAX_PIN PinD7 // No INT +#define Z_MIN_PIN PinD3 // No INT +#define Z_MAX_PIN PinD2 // No INT // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 58 -#define X_DIR_PIN 57 -#define X_ENABLE_PIN 59 +#define X_STEP_PIN PinF4 +#define X_DIR_PIN PinF3 +#define X_ENABLE_PIN PinF5 #if ENABLED(REPRAPWORLD_KEYPAD) && EXTRUDERS <= 2 - #define Y_ENABLE_PIN 23 - #define Y_STEP_PIN 22 - #define Y_DIR_PIN 60 + #define Y_ENABLE_PIN PinA1 + #define Y_STEP_PIN PinA0 + #define Y_DIR_PIN PinF6 #else - #define Y_STEP_PIN 5 - #define Y_DIR_PIN 17 - #define Y_ENABLE_PIN 4 + #define Y_STEP_PIN PinE3 + #define Y_DIR_PIN PinH0 + #define Y_ENABLE_PIN PinG5 - #define E2_STEP_PIN 22 - #define E2_DIR_PIN 60 - #define E2_ENABLE_PIN 23 + #define E2_STEP_PIN PinA0 + #define E2_DIR_PIN PinF6 + #define E2_ENABLE_PIN PinA1 #endif -#define Z_STEP_PIN 16 -#define Z_DIR_PIN 11 -#define Z_ENABLE_PIN 3 +#define Z_STEP_PIN PinH1 +#define Z_DIR_PIN PinB5 +#define Z_ENABLE_PIN PinE5 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 29 +#define E0_STEP_PIN PinA6 +#define E0_DIR_PIN PinA5 +#define E0_ENABLE_PIN PinA7 -#define E1_STEP_PIN 25 -#define E1_DIR_PIN 24 -#define E1_ENABLE_PIN 26 +#define E1_STEP_PIN PinA3 +#define E1_DIR_PIN PinA2 +#define E1_ENABLE_PIN PinA4 // // Temperature Sensors // #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 11 // Analog Input + #define TEMP_0_PIN PinB5 // Analog Input #else - #define TEMP_0_PIN 15 // Analog Input + #define TEMP_0_PIN PinJ0 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 10 // Analog Input + #define TEMP_1_PIN PinB4 // Analog Input #else - #define TEMP_1_PIN 13 // Analog Input + #define TEMP_1_PIN PinB7 // Analog Input #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 9 // Analog Input + #define TEMP_2_PIN PinH6 // Analog Input #else - #define TEMP_2_PIN 12 // Analog Input + #define TEMP_2_PIN PinB6 // Analog Input #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // Analog Input + #define TEMP_BED_PIN PinH5 // Analog Input #else - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 9 -#define HEATER_2_PIN 8 -#define HEATER_BED_PIN 10 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinH6 +#define HEATER_2_PIN PinH5 +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 6 + #define FAN_PIN PinH3 #endif -#define FAN1_PIN 7 +#define FAN1_PIN PinH4 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 45 // Try the keypad connector + #define CASE_LIGHT_PIN PinL4 // Try the keypad connector #endif // // LCD / Controller // -#define BEEPER_PIN 61 +#define BEEPER_PIN PinF7 -#define BTN_EN1 44 -#define BTN_EN2 45 -#define BTN_ENC 33 +#define BTN_EN1 PinL5 +#define BTN_EN2 PinL4 +#define BTN_ENC PinC4 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 56 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock - #define SD_DETECT_PIN 35 + #define LCD_PINS_RS PinF2 // CS chip select / SS chip slave select + #define LCD_PINS_ENABLE PinB2 // SID (MOSI) + #define LCD_PINS_D4 PinB1 // SCK (CLK) clock + #define SD_DETECT_PIN PinC2 #else - #define LCD_PINS_RS 32 - #define LCD_PINS_ENABLE 31 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 30 - #define LCD_PINS_D6 39 - #define LCD_PINS_D7 15 + #define LCD_PINS_RS PinC5 + #define LCD_PINS_ENABLE PinC6 + #define LCD_PINS_D4 PinJ1 + #define LCD_PINS_D5 PinC7 + #define LCD_PINS_D6 PinG2 + #define LCD_PINS_D7 PinJ0 - #define SHIFT_CLK_PIN 43 - #define SHIFT_LD_PIN 35 - #define SHIFT_OUT_PIN 34 - #define SHIFT_EN_PIN 44 + #define SHIFT_CLK_PIN PinL6 + #define SHIFT_LD_PIN PinC2 + #define SHIFT_OUT_PIN PinC3 + #define SHIFT_EN_PIN PinL5 #if MB(MEGATRONICS_31, MEGATRONICS_32) - #define SD_DETECT_PIN 56 + #define SD_DETECT_PIN PinF2 #endif #endif @@ -181,13 +182,13 @@ // M3/M4/M5 - Spindle/Laser Control // #if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 43 // Pullup! - #define SPINDLE_DIR_PIN 42 + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinL6 // Pullup! + #define SPINDLE_DIR_PIN PinL7 #elif EXTRUDERS <= 2 // Hijack the last extruder so that we can get the PWM signal off the Y breakout // Move Y to the E2 plug. This makes dual Y steppers harder - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_LASER_PWM_PIN PinG5 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinH0 // Pullup! + #define SPINDLE_DIR_PIN PinE3 #endif diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index cff3a11af16f..8b8d171d8c10 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -43,63 +43,65 @@ #define BOARD_INFO_NAME "Mightyboard" #define DEFAULT_MACHINE_NAME "MB Replicator" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // -#define SERVO0_PIN 36 // C1 (1280-EX1) -#define SERVO1_PIN 37 // C0 (1280-EX2) -#define SERVO2_PIN 40 // G1 (1280-EX3) -#define SERVO3_PIN 41 // G0 (1280-EX4) +#define SERVO0_PIN PinC1 // C1 (1280-EX1) +#define SERVO1_PIN PinC0 // C0 (1280-EX2) +#define SERVO2_PIN PinG1 // G1 (1280-EX3) +#define SERVO3_PIN PinG0 // G0 (1280-EX4) // // Limit Switches // -#define X_MIN_PIN 49 // L0 -#define X_MAX_PIN 48 // L1 -#define Y_MIN_PIN 47 // L2 -#define Y_MAX_PIN 46 // L3 -#define Z_MIN_PIN 43 // L6 -#define Z_MAX_PIN 42 // L7 +#define X_MIN_PIN PinL0 // L0 +#define X_MAX_PIN PinL1 // L1 +#define Y_MIN_PIN PinL2 // L2 +#define Y_MAX_PIN PinL3 // L3 +#define Z_MIN_PIN PinL6 // L6 +#define Z_MAX_PIN PinL7 // L7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 42 + #define Z_MIN_PROBE_PIN PinL7 #endif // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 49 + #define FIL_RUNOUT_PIN PinL0 #endif #ifndef FIL_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN 47 + #define FIL_RUNOUT2_PIN PinL2 #endif // // Steppers // -#define X_STEP_PIN 55 // F1 -#define X_DIR_PIN 54 // F0 -#define X_ENABLE_PIN 56 // F2 +#define X_STEP_PIN PinF1 // F1 +#define X_DIR_PIN PinF0 // F0 +#define X_ENABLE_PIN PinF2 // F2 -#define Y_STEP_PIN 59 // F5 -#define Y_DIR_PIN 58 // F4 -#define Y_ENABLE_PIN 60 // F6 +#define Y_STEP_PIN PinF5 // F5 +#define Y_DIR_PIN PinF4 // F4 +#define Y_ENABLE_PIN PinF6 // F6 -#define Z_STEP_PIN 63 // K1 -#define Z_DIR_PIN 62 // K0 -#define Z_ENABLE_PIN 64 // K2 +#define Z_STEP_PIN PinK1 // K1 +#define Z_DIR_PIN PinK0 // K0 +#define Z_ENABLE_PIN PinK2 // K2 -#define E0_STEP_PIN 25 // A3 -#define E0_DIR_PIN 24 // A2 -#define E0_ENABLE_PIN 26 // A4 +#define E0_STEP_PIN PinA3 // A3 +#define E0_DIR_PIN PinA2 // A2 +#define E0_ENABLE_PIN PinA4 // A4 -#define E1_STEP_PIN 29 // A7 -#define E1_DIR_PIN 28 // A6 -#define E1_ENABLE_PIN 39 // G2 +#define E1_STEP_PIN PinA7 // A7 +#define E1_DIR_PIN PinA6 // A6 +#define E1_ENABLE_PIN PinG2 // G2 // // I2C Digipots - MCP4018 @@ -107,12 +109,12 @@ // Set from 0 - 127 with stop bit. // (Ex. 3F << 1 | 1) // -#define DIGIPOTS_I2C_SCL 76 // J5 -#define DIGIPOTS_I2C_SDA_X 57 // F3 -#define DIGIPOTS_I2C_SDA_Y 61 // F7 -#define DIGIPOTS_I2C_SDA_Z 65 // K3 -#define DIGIPOTS_I2C_SDA_E0 27 // A5 -#define DIGIPOTS_I2C_SDA_E1 77 // J6 +#define DIGIPOTS_I2C_SCL PinJ5 // J5 +#define DIGIPOTS_I2C_SDA_X PinF3 // F3 +#define DIGIPOTS_I2C_SDA_Y PinF7 // F7 +#define DIGIPOTS_I2C_SDA_Z PinK3 // K3 +#define DIGIPOTS_I2C_SDA_E0 PinA5 // A5 +#define DIGIPOTS_I2C_SDA_E1 PinJ6 // J6 #ifndef DIGIPOT_I2C_ADDRESS_A #define DIGIPOT_I2C_ADDRESS_A 0x2F // unshifted slave address (5E <- 2F << 1) @@ -123,7 +125,7 @@ // Temperature Sensors // // K7 - 69 / ADC15 - 15 -#define TEMP_BED_PIN 15 +#define TEMP_BED_PIN PinJ0 // SPI for MAX Thermocouple // Uses a separate SPI bus @@ -133,12 +135,12 @@ // 2 E4 CS2 // 78 E2 SCK // -#define TEMP_0_CS_PIN 5 // E3 -#define TEMP_0_SCK_PIN 78 // E2 -#define TEMP_0_MISO_PIN 3 // E5 +#define TEMP_0_CS_PIN PinE3 // E3 +#define TEMP_0_SCK_PIN PinE2 // E2 +#define TEMP_0_MISO_PIN PinE5 // E5 //#define TEMP_0_MOSI_PIN ... // For MAX31865 -#define TEMP_1_CS_PIN 2 // E4 +#define TEMP_1_CS_PIN PinE4 // E4 #define TEMP_1_SCK_PIN TEMP_0_SCK_PIN #define TEMP_1_MISO_PIN TEMP_0_MISO_PIN //#define TEMP_1_MOSI_PIN TEMP_0_MOSI_PIN @@ -147,12 +149,12 @@ // FET Pin Mapping - FET 1 is closest to the input power connector // -#define MOSFET_1_PIN 6 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 -#define MOSFET_2_PIN 7 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 -#define MOSFET_3_PIN 11 // Plug EX2 1-2 -> PB5 #24 -> Logical 11 -#define MOSFET_4_PIN 12 // Plug EX2 3-4 -> PB6 #25 -> Logical 12 -#define MOSFET_5_PIN 45 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 -#define MOSFET_6_PIN 44 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) +#define MOSFET_1_PIN PinH3 // Plug EX1 Pin 1-2 -> PH3 #15 -> Logical 06 +#define MOSFET_2_PIN PinH4 // Plug EX1 Pin 3-4 -> PH4 #16 -> Logical 07 +#define MOSFET_3_PIN PinB5 // Plug EX2 1-2 -> PB5 #24 -> Logical 11 +#define MOSFET_4_PIN PinB6 // Plug EX2 3-4 -> PB6 #25 -> Logical 12 +#define MOSFET_5_PIN PinL4 // Plug HBD 1-2 -> PL4 #39 -> Logical 45 +#define MOSFET_6_PIN PinL5 // Plug Extra 1-2 -> PL5 #40 -> Logical 44 (FET not soldered in all boards) // // Heaters / Fans (24V) @@ -182,10 +184,10 @@ // // Misc. Functions // -#define LED_PIN 13 // B7 -#define CUTOFF_RESET_PIN 16 // H1 -#define CUTOFF_TEST_PIN 17 // H0 -#define CUTOFF_SR_CHECK_PIN 70 // G4 (TOSC1) +#define LED_PIN PinB7 // B7 +#define CUTOFF_RESET_PIN PinH1 // H1 +#define CUTOFF_TEST_PIN PinH0 // H0 +#define CUTOFF_SR_CHECK_PIN PinG4 // G4 (TOSC1) // // LCD / Controller @@ -194,56 +196,64 @@ #if IS_RRD_FG_SC - #define LCD_PINS_RS 33 // C4: LCD-STROBE - #define LCD_PINS_ENABLE 72 // J2: LEFT - #define LCD_PINS_D4 35 // C2: LCD-CLK - #define LCD_PINS_D5 32 // C5: RLED - #define LCD_PINS_D6 34 // C3: LCD-DATA - #define LCD_PINS_D7 31 // C6: GLED + #define LCD_PINS_RS PinC4 // C4: LCD-STROBE + #define LCD_PINS_ENABLE PinJ2 // J2: LEFT + #define LCD_PINS_D4 PinC2 // C2: LCD-CLK + #define LCD_PINS_D5 PinC5 // C5: RLED + #define LCD_PINS_D6 PinC3 // C3: LCD-DATA + #define LCD_PINS_D7 PinC6 // C6: GLED - #define BTN_EN2 75 // J4, UP - #define BTN_EN1 73 // J3, DOWN + #define BTN_EN2 PinJ4 // J4, UP + #define BTN_EN1 PinJ3 // J3, DOWN // STOP button connected as KILL_PIN - #define KILL_PIN 14 // J1, RIGHT (not connected) + #define KILL_PIN PinJ1 // J1, RIGHT (not connected) - #define BEEPER_PIN 8 // H5, SD_WP + #ifndef FORCE_ONBOARD_BEEPER + #define BEEPER_PIN PinH5 // H5, SD_WP + #endif // Onboard leds #define STAT_LED_RED_PIN SERVO0_PIN // C1 (1280-EX1, DEBUG2) #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) + #elif ENABLED(MKS_TS35_V2_0) + + + #else // Replicator uses a 3-wire SR controller with HD44780 - #define SR_DATA_PIN 34 // C3 - #define SR_CLK_PIN 35 // C2 - #define SR_STROBE_PIN 33 // C4 + #define SR_DATA_PIN PinC3 // C3 + #define SR_CLK_PIN PinC2 // C2 + #define SR_STROBE_PIN PinC4 // C4 - #define BTN_UP 75 // J4 - #define BTN_DOWN 73 // J3 - #define BTN_LEFT 72 // J2 - #define BTN_RIGHT 14 // J1 + #define BTN_UP PinJ4 // J4 + #define BTN_DOWN PinJ3 // J3 + #define BTN_LEFT PinJ2 // J2 + #define BTN_RIGHT PinJ1 // J1 // Disable encoder #undef BTN_EN1 #undef BTN_EN2 - #define BEEPER_PIN 4 // G5 - - #define STAT_LED_RED_PIN 32 // C5 - #define STAT_LED_BLUE_PIN 31 // C6 (Actually green) + #define STAT_LED_RED_PIN PinC5 // C5 + #define STAT_LED_BLUE_PIN PinC6 // C6 (Actually green) #endif - #define BTN_CENTER 15 // J0 + #define BTN_CENTER PinJ0 // J0 #define BTN_ENC BTN_CENTER #endif // HAS_WIRED_LCD +#ifndef BEEPER_PIN + #define BEEPER_PIN PinG5 // G5 +#endif + // // SD Card // -#define SDSS 53 // B0 -#define SD_DETECT_PIN 9 // H6 +#define SDSS PinB0 // B0 +#define SD_DETECT_PIN PinH6 // H6 #if HAS_TMC_UART /** @@ -259,19 +269,19 @@ * Software serial */ - #define X_SERIAL_TX_PIN 16 - #define X_SERIAL_RX_PIN 17 + #define X_SERIAL_TX_PIN PinH1 + #define X_SERIAL_RX_PIN PinH0 - #define Y_SERIAL_TX_PIN 18 - #define Y_SERIAL_RX_PIN 19 + #define Y_SERIAL_TX_PIN PinD3 + #define Y_SERIAL_RX_PIN PinD2 - #define Z_SERIAL_TX_PIN 41 - #define Z_SERIAL_RX_PIN 66 + #define Z_SERIAL_TX_PIN PinG0 + #define Z_SERIAL_RX_PIN PinK4 - #define E0_SERIAL_TX_PIN 40 - #define E0_SERIAL_RX_PIN 67 + #define E0_SERIAL_TX_PIN PinG1 + #define E0_SERIAL_RX_PIN PinK5 - #define E1_SERIAL_TX_PIN 37 - #define E1_SERIAL_RX_PIN 68 + #define E1_SERIAL_TX_PIN PinC0 + #define E1_SERIAL_RX_PIN PinK6 #endif diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index ec712a3b90e5..5fd6ebbcb0d9 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -23,6 +23,7 @@ /** * Minitronics v1.0/1.1 pin assignments + * ATmega1281 */ /** @@ -41,59 +42,59 @@ // // Limit Switches // -#define X_MIN_PIN 5 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 2 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 6 +#define X_MIN_PIN PinE3 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinE4 +#define Y_MAX_PIN PinE7 +#define Z_MIN_PIN PinB4 #define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN 48 -#define X_DIR_PIN 47 -#define X_ENABLE_PIN 49 +#define X_STEP_PIN PinF2 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinF3 -#define Y_STEP_PIN 39 // A6 -#define Y_DIR_PIN 40 // A0 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN PinA1 // A6 +#define Y_DIR_PIN PinA2 // A0 +#define Y_ENABLE_PIN PinA0 -#define Z_STEP_PIN 42 // A2 -#define Z_DIR_PIN 43 // A6 -#define Z_ENABLE_PIN 41 // A1 +#define Z_STEP_PIN PinA4 // A2 +#define Z_DIR_PIN PinA5 // A6 +#define Z_ENABLE_PIN PinA3 // A1 -#define E0_STEP_PIN 45 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 27 +#define E0_STEP_PIN PinA7 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinG2 -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 35 -#define E1_ENABLE_PIN 37 +#define E1_STEP_PIN PinC6 +#define E1_DIR_PIN PinC5 +#define E1_ENABLE_PIN PinC7 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input -#define TEMP_1_PIN 6 // Analog Input -#define TEMP_BED_PIN 6 // Analog Input +#define TEMP_0_PIN PinB5 // Analog Input +#define TEMP_1_PIN PinB4 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 7 // EXTRUDER 1 -#define HEATER_1_PIN 8 // EXTRUDER 2 -#define HEATER_BED_PIN 3 // BED +#define HEATER_0_PIN PinB5 // EXTRUDER 1 +#define HEATER_1_PIN PinB6 // EXTRUDER 2 +#define HEATER_BED_PIN PinE5 // BED #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN PinB7 #endif // // Misc. Functions // -#define SDSS 16 -#define LED_PIN 46 +#define SDSS PinB0 +#define LED_PIN PinF0 // // LCD / Controller @@ -102,15 +103,15 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 15 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 11 // SID (MOSI) - #define LCD_PINS_D4 10 // SCK (CLK) clock + #define LCD_PINS_RS PinE7 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinB2 // SID (MOSI) + #define LCD_PINS_D4 PinB1 // SCK (CLK) clock - #define BTN_EN1 18 - #define BTN_EN2 17 - #define BTN_ENC 25 + #define BTN_EN1 PinD1 + #define BTN_EN2 PinD0 + #define BTN_ENC PinG0 - #define SD_DETECT_PIN 30 + #define SD_DETECT_PIN PinC0 #else @@ -133,10 +134,10 @@ #undef TEMP_BED_PIN // need to free up some pins but also need to #undef TEMP_0_PIN // re-assign them (to unused pins) because Marlin #undef TEMP_1_PIN // requires the presence of certain pins or else it - #define HEATER_BED_PIN 4 // won't compile - #define TEMP_BED_PIN 50 - #define TEMP_0_PIN 51 - #define SPINDLE_LASER_ENA_PIN 52 // using A6 because it already has a pullup - #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage - #define SPINDLE_DIR_PIN 53 + #define HEATER_BED_PIN PinG5 // won't compile + #define TEMP_BED_PIN PinF4 + #define TEMP_0_PIN PinF5 + #define SPINDLE_LASER_ENA_PIN PinF6 // using A6 because it already has a pullup + #define SPINDLE_LASER_PWM_PIN PinE5 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_DIR_PIN PinF7 #endif diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index 49accf9f7c4c..dc73261d7fa8 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -23,6 +23,7 @@ /** * Dreammaker Overlord v1.1 pin assignments + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -37,83 +38,83 @@ // // Limit Switches // -#define X_STOP_PIN 24 -#define Y_STOP_PIN 28 -#define Z_MIN_PIN 46 -#define Z_MAX_PIN 32 +#define X_STOP_PIN PinA2 +#define Y_STOP_PIN PinA6 +#define Z_MIN_PIN PinL3 +#define Z_MAX_PIN PinC5 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 46 // JP4, Tfeed1 + #define Z_MIN_PROBE_PIN PinL3 // JP4, Tfeed1 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 44 // JP3, Tfeed2 + #define FIL_RUNOUT_PIN PinL5 // JP3, Tfeed2 #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN PinC0 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinC2 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN PinL6 +#define E0_DIR_PIN PinL4 +#define E0_ENABLE_PIN PinG0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input - Redundant temp sensor -#define TEMP_2_PIN 12 // Analog Input -#define TEMP_3_PIN 14 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +#define TEMP_1_PIN PinH6 // Analog Input - Redundant temp sensor +#define TEMP_2_PIN PinB6 // Analog Input +#define TEMP_3_PIN PinJ1 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 -#define FAN_PIN 7 // material cooling fan +#define FAN_PIN PinH4 // material cooling fan // // SD Card // -#define SDSS 53 -#define SD_DETECT_PIN 38 +#define SDSS PinB0 +#define SD_DETECT_PIN PinD7 // // Misc. Functions // -#define LED_PIN 13 // On PCB status led -#define PS_ON_PIN 12 // For stepper/heater/fan power. Active HIGH. -#define POWER_LOSS_PIN 34 // Power check - whether hotends/steppers/fans have power +#define LED_PIN PinB7 // On PCB status led +#define PS_ON_PIN PinB6 // For stepper/heater/fan power. Active HIGH. +#define POWER_LOSS_PIN PinC3 // Power check - whether hotends/steppers/fans have power #if ENABLED(BATTERY_STATUS_AVAILABLE) #undef BATTERY_STATUS_PIN - #define BATTERY_STATUS_PIN 26 // Status of power loss battery, whether it is charged (low) or charging (high) + #define BATTERY_STATUS_PIN PinA4 // Status of power loss battery, whether it is charged (low) or charging (high) #endif #if ENABLED(INPUT_VOLTAGE_AVAILABLE) #undef VOLTAGE_DETECTION_PIN - #define VOLTAGE_DETECTION_PIN 11 // Analog Input - ADC Voltage level of main input + #define VOLTAGE_DETECTION_PIN PinB5 // Analog Input - ADC Voltage level of main input #endif // @@ -121,24 +122,24 @@ // #if HAS_WIRED_LCD // OVERLORD OLED pins - #define LCD_PINS_RS 20 - #define LCD_PINS_D5 21 - #define LCD_PINS_ENABLE 15 - #define LCD_PINS_D4 14 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_ENABLE PinJ0 + #define LCD_PINS_D4 PinJ1 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 #ifndef LCD_RESET_PIN - #define LCD_RESET_PIN 5 // LCD_PINS_D6 + #define LCD_RESET_PIN PinE3 // LCD_PINS_D6 #endif #endif #if IS_NEWPANEL - #define BTN_ENC 16 // Enter Pin - #define BTN_UP 19 // Button UP Pin - #define BTN_DOWN 17 // Button DOWN Pin + #define BTN_ENC PinH1 // Enter Pin + #define BTN_UP PinD2 // Button UP Pin + #define BTN_DOWN PinH0 // Button DOWN Pin #endif // Additional connectors/pins on the Overlord V1.X board -#define PCB_VERSION_PIN 22 -#define APPROACH_PIN 11 // JP7, Tpd -#define GATE_PIN 36 // Threshold, JP6, Tg +#define PCB_VERSION_PIN PinA0 +#define APPROACH_PIN PinB5 // JP7, Tpd +#define GATE_PIN PinC1 // Threshold, JP6, Tg diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 0e29d8dffe75..b69c6787a46d 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -23,6 +23,7 @@ /** * Arduino Mega with PICA pin assignments + * ATmega2560 * * PICA is Power, Interface, and Control Adapter and is open source hardware. * See https://github.com/mjrice/PICA for schematics etc. @@ -48,68 +49,68 @@ // // Servos // -#define SERVO0_PIN 3 -#define SERVO1_PIN 4 -#define SERVO2_PIN 5 +#define SERVO0_PIN PinE5 +#define SERVO1_PIN PinG5 +#define SERVO2_PIN PinE3 // // Limit Switches // -#define X_MIN_PIN 14 -#define X_MAX_PIN 15 -#define Y_MIN_PIN 16 -#define Y_MAX_PIN 17 -#define Z_MIN_PIN 23 -#define Z_MAX_PIN 22 +#define X_MIN_PIN PinJ1 +#define X_MAX_PIN PinJ0 +#define Y_MIN_PIN PinH1 +#define Y_MAX_PIN PinH0 +#define Z_MIN_PIN PinA1 +#define Z_MAX_PIN PinA0 // // Steppers // -#define X_STEP_PIN 55 -#define X_DIR_PIN 54 -#define X_ENABLE_PIN 60 +#define X_STEP_PIN PinF1 +#define X_DIR_PIN PinF0 +#define X_ENABLE_PIN PinF6 -#define Y_STEP_PIN 57 -#define Y_DIR_PIN 56 -#define Y_ENABLE_PIN 61 +#define Y_STEP_PIN PinF3 +#define Y_DIR_PIN PinF2 +#define Y_ENABLE_PIN PinF7 -#define Z_STEP_PIN 59 -#define Z_DIR_PIN 58 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinF5 +#define Z_DIR_PIN PinF4 +#define Z_ENABLE_PIN PinK0 -#define E0_STEP_PIN 67 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN PinK5 +#define E0_DIR_PIN PinA2 +#define E0_ENABLE_PIN PinA4 -#define E1_STEP_PIN 68 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 27 +#define E1_STEP_PIN PinK6 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA5 // // Temperature Sensors // -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN 10 -#define TEMP_BED_PIN 10 -#define TEMP_2_PIN 11 -#define TEMP_3_PIN 12 +#define TEMP_0_PIN PinH6 // Analog Input +#define TEMP_1_PIN PinB4 +#define TEMP_BED_PIN PinB4 +#define TEMP_2_PIN PinB5 +#define TEMP_3_PIN PinB6 // // Heaters / Fans // #ifndef HEATER_0_PIN - #define HEATER_0_PIN 10 // E0 + #define HEATER_0_PIN PinB4 // E0 #endif #ifndef HEATER_1_PIN - #define HEATER_1_PIN 2 // E1 + #define HEATER_1_PIN PinE4 // E1 #endif -#define HEATER_BED_PIN 8 // HEAT-BED +#define HEATER_BED_PIN PinH5 // HEAT-BED #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN PinH6 #endif #ifndef FAN_2_PIN - #define FAN_2_PIN 7 + #define FAN_2_PIN PinH4 #endif #define SDPOWER_PIN -1 @@ -117,37 +118,37 @@ #define PS_ON_PIN -1 #define KILL_PIN -1 -#define SSR_PIN 6 +#define SSR_PIN PinH3 // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // SD Support // -#define SD_DETECT_PIN 49 -#define SDSS 53 +#define SD_DETECT_PIN PinL0 +#define SDSS PinB0 // // LCD / Controller // -#define BEEPER_PIN 29 +#define BEEPER_PIN PinA7 #if HAS_WIRED_LCD - #define LCD_PINS_RS 33 - #define LCD_PINS_ENABLE 30 - #define LCD_PINS_D4 35 - #define LCD_PINS_D5 32 - #define LCD_PINS_D6 37 - #define LCD_PINS_D7 36 - - #define BTN_EN1 47 - #define BTN_EN2 48 - #define BTN_ENC 31 - - #define LCD_SDSS 53 + #define LCD_PINS_RS PinC4 + #define LCD_PINS_ENABLE PinC7 + #define LCD_PINS_D4 PinC2 + #define LCD_PINS_D5 PinC5 + #define LCD_PINS_D6 PinC0 + #define LCD_PINS_D7 PinC1 + + #define BTN_EN1 PinL2 + #define BTN_EN2 PinL1 + #define BTN_ENC PinC6 + + #define LCD_SDSS PinB0 #endif diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index e19ea744e5eb..7782c8e8b343 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -21,9 +21,11 @@ */ #pragma once -#define HEATER_0_PIN 9 // E0 -#define HEATER_1_PIN 10 // E1 -#define FAN_PIN 11 -#define FAN2_PIN 12 +// ATmega2560 + +#define HEATER_0_PIN PinH6 // E0 +#define HEATER_1_PIN PinB4 // E1 +#define FAN_PIN PinB5 +#define FAN2_PIN PinB6 #include "pins_PICA.h" diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h index f2e4d3da0266..ed2a06ca47a1 100644 --- a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -23,6 +23,7 @@ /** * Protoneer v3.00 pin assignments + * ATmega2560 * * This CNC shield has an UNO pinout and fits all Arduino-compatibles. * @@ -38,40 +39,40 @@ // // Limit Switches // -#define X_STOP_PIN 9 -#define Y_STOP_PIN 10 -#define Z_STOP_PIN 11 +#define X_STOP_PIN PinH6 +#define Y_STOP_PIN PinB4 +#define Z_STOP_PIN PinB5 // // Steppers // -#define X_STEP_PIN 2 -#define X_DIR_PIN 5 -#define X_ENABLE_PIN 8 // Shared enable pin +#define X_STEP_PIN PinE4 +#define X_DIR_PIN PinE3 +#define X_ENABLE_PIN PinH5 // Shared enable pin -#define Y_STEP_PIN 3 -#define Y_DIR_PIN 6 +#define Y_STEP_PIN PinE5 +#define Y_DIR_PIN PinH3 #define Y_ENABLE_PIN X_ENABLE_PIN -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 7 +#define Z_STEP_PIN PinG5 +#define Z_DIR_PIN PinH4 #define Z_ENABLE_PIN X_ENABLE_PIN // Designated with letter "A" on BOARD -#define E0_STEP_PIN 12 -#define E0_DIR_PIN 13 +#define E0_STEP_PIN PinB6 +#define E0_DIR_PIN PinB7 #define E0_ENABLE_PIN X_ENABLE_PIN // // Temperature sensors - These could be any analog output not hidden by board // -#define TEMP_0_PIN 8 // Analog Input -//#define TEMP_1_PIN 9 // Analog Input -//#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +//#define TEMP_1_PIN PinH6 // Analog Input +//#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans - These could be any digital input not hidden by board // -//#define HEATER_0_PIN 22 // EXTRUDER 1 -//#define HEATER_1_PIN 23 // EXTRUDER 2 -//#define HEATER_BED_PIN 24 +//#define HEATER_0_PIN PinA0 // EXTRUDER 1 +//#define HEATER_1_PIN PinA1 // EXTRUDER 2 +//#define HEATER_BED_PIN PinA2 diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index c2ca5b31038a..5f96f89431d2 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -21,70 +21,72 @@ */ #pragma once +// ATmega2561 + #if NOT_TARGET(__AVR_ATmega1281__, __AVR_ATmega2561__) #error "Oops! Select 'Silvergate' in 'Tools > Board.'" #endif #define BOARD_INFO_NAME "Silver Gate" -#define X_STEP_PIN 43 -#define X_DIR_PIN 44 -#define X_ENABLE_PIN 42 -#define X_MIN_PIN 31 -#define X_MAX_PIN 34 +#define X_STEP_PIN PinA5 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinA4 +#define X_MIN_PIN PinC1 +#define X_MAX_PIN PinC4 -#define Y_STEP_PIN 40 -#define Y_DIR_PIN 41 -#define Y_ENABLE_PIN 39 -#define Y_MIN_PIN 32 -#define Y_MAX_PIN 35 +#define Y_STEP_PIN PinA2 +#define Y_DIR_PIN PinA3 +#define Y_ENABLE_PIN PinA1 +#define Y_MIN_PIN PinC2 +#define Y_MAX_PIN PinC5 -#define Z_STEP_PIN 13 -#define Z_DIR_PIN 38 -#define Z_ENABLE_PIN 14 -#define Z_MIN_PIN 33 -#define Z_MAX_PIN 36 +#define Z_STEP_PIN PinE2 +#define Z_DIR_PIN PinA0 +#define Z_ENABLE_PIN PinE6 +#define Z_MIN_PIN PinC3 +#define Z_MAX_PIN PinC6 -#define E0_STEP_PIN 27 -#define E0_DIR_PIN 37 -#define E0_ENABLE_PIN 45 +#define E0_STEP_PIN PinG2 +#define E0_DIR_PIN PinC7 +#define E0_ENABLE_PIN PinA7 -#define SDSS 16 +#define SDSS PinB0 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 34 // X_MAX unless overridden + #define FIL_RUNOUT_PIN PinC4 // X_MAX unless overridden #endif #ifndef FAN_PIN - #define FAN_PIN 5 + #define FAN_PIN PinE3 #endif -#define HEATER_0_PIN 7 +#define HEATER_0_PIN PinB5 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 3 + #define E0_AUTO_FAN_PIN PinE5 #endif -#define CONTROLLER_FAN_PIN 2 +#define CONTROLLER_FAN_PIN PinE4 -#define TEMP_0_PIN 7 // Analog Input +#define TEMP_0_PIN PinB5 // Analog Input -#define HEATER_BED_PIN 8 -#define TEMP_BED_PIN 6 +#define HEATER_BED_PIN PinB6 +#define TEMP_BED_PIN PinB4 #if HAS_WIRED_LCD #if IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 - #define LCD_PINS_RS 30 - #define LCD_PINS_ENABLE 20 - #define LCD_PINS_D4 25 - #define BEEPER_PIN 29 - #define BTN_EN1 19 - #define BTN_EN2 22 - #define BTN_ENC 24 - #define LCD_BACKLIGHT_PIN 6 + #define LCD_PINS_RS PinC0 + #define LCD_PINS_ENABLE PinD3 + #define LCD_PINS_D4 PinG0 + #define BEEPER_PIN PinG4 + #define BTN_EN1 PinD2 + #define BTN_EN2 PinD5 + #define BTN_ENC PinD7 + #define LCD_BACKLIGHT_PIN PinB4 #if ENABLED(SILVER_GATE_GLCD_CONTROLLER) - #define KILL_PIN 21 - #define HOME_PIN 28 + #define KILL_PIN PinD4 + #define HOME_PIN PinG3 #endif #define BOARD_ST7920_DELAY_1 0 #define BOARD_ST7920_DELAY_2 250 @@ -92,11 +94,11 @@ #endif #endif -#define SD_DETECT_PIN 15 +#define SD_DETECT_PIN PinE7 -#define STAT_LED_RED_PIN 23 -#define STAT_LED_BLUE_PIN 26 +#define STAT_LED_RED_PIN PinD6 +#define STAT_LED_BLUE_PIN PinG1 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 51 + #define CASE_LIGHT_PIN PinF5 #endif diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index 503dd9ec8148..3089ed796c02 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -23,6 +23,7 @@ /** * Wanhao 0ne+ pin assignments + * ATmega2560 */ #include "env_validate.h" @@ -34,73 +35,73 @@ // // Limit Switches // -#define X_STOP_PIN 19 -#define Y_STOP_PIN 18 -#define Z_STOP_PIN 38 +#define X_STOP_PIN PinD2 +#define Y_STOP_PIN PinD3 +#define Z_STOP_PIN PinD7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 38 + #define Z_MIN_PROBE_PIN PinD7 #endif // // Steppers // -#define X_STEP_PIN 22 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 57 +#define X_STEP_PIN PinA0 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinF3 -#define Y_STEP_PIN 25 -#define Y_DIR_PIN 26 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinA3 +#define Y_DIR_PIN PinA4 +#define Y_ENABLE_PIN PinA2 -#define Z_STEP_PIN 29 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 28 +#define Z_STEP_PIN PinA7 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinA6 -#define E0_STEP_PIN 55 -#define E0_DIR_PIN 56 -#define E0_ENABLE_PIN 54 +#define E0_STEP_PIN PinF1 +#define E0_DIR_PIN PinF2 +#define E0_ENABLE_PIN PinF0 // // Temperature Sensors // -#define TEMP_0_PIN 13 -#define TEMP_BED_PIN 14 +#define TEMP_0_PIN PinB7 +#define TEMP_BED_PIN PinJ1 // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 44 -#define FAN_PIN 12 // IO pin. Buffer needed +#define HEATER_0_PIN PinG5 +#define HEATER_BED_PIN PinL5 +#define FAN_PIN PinB6 // IO pin. Buffer needed // // SD Card // -#define SD_DETECT_PIN 83 -#define SDSS 53 +#define SD_DETECT_PIN PinD6 +#define SDSS PinB0 // // Misc. Functions // -#define BEEPER_PIN 37 -#define KILL_PIN 64 +#define BEEPER_PIN PinC0 +#define KILL_PIN PinK2 // // LCD / Controller (Integrated MINIPANEL) // #if ENABLED(MINIPANEL) - #define DOGLCD_A0 40 - #define DOGLCD_CS 41 - #define LCD_BACKLIGHT_PIN 65 // Backlight LED on A11/D65 - #define LCD_RESET_PIN 27 - - #define BTN_EN1 2 - #define BTN_EN2 3 - #define BTN_ENC 5 + #define DOGLCD_A0 PinG1 + #define DOGLCD_CS PinG0 + #define LCD_BACKLIGHT_PIN PinK3 // Backlight LED on A11/D65 + #define LCD_RESET_PIN PinA5 + + #define BTN_EN1 PinE4 + #define BTN_EN2 PinE5 + #define BTN_ENC PinE3 // This display has adjustable contrast #define LCD_CONTRAST_MIN 0 diff --git a/Marlin/src/pins/mega/pins_WEEDO_62A.h b/Marlin/src/pins/mega/pins_WEEDO_62A.h index 4b3bf6a43bee..7b87edf2e436 100644 --- a/Marlin/src/pins/mega/pins_WEEDO_62A.h +++ b/Marlin/src/pins/mega/pins_WEEDO_62A.h @@ -23,6 +23,7 @@ /** * Based on WEEDO 62A pin configuration * Copyright (c) 2019 WEEDO3D Perron + * ATmega2560 */ #pragma once @@ -36,71 +37,71 @@ // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 40 -#define Y_MAX_PIN 41 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinG1 +#define Y_MAX_PIN PinG0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinA4 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinA2 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 -#define E0_STEP_PIN 54 -#define E0_DIR_PIN 55 -#define E0_ENABLE_PIN 38 +#define E0_STEP_PIN PinF0 +#define E0_DIR_PIN PinF1 +#define E0_ENABLE_PIN PinD7 // // Temperature Sensors // -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_BED_PIN 14 // ANALOG NUMBERING +#define TEMP_0_PIN PinB7 // ANALOG NUMBERING +#define TEMP_BED_PIN PinJ1 // ANALOG NUMBERING // // Heaters / Fans // -#define HEATER_0_PIN 10 // EXTRUDER 1 -#define HEATER_BED_PIN 8 // BED -#define FAN_PIN 4 // IO pin. Buffer needed +#define HEATER_0_PIN PinB4 // EXTRUDER 1 +#define HEATER_BED_PIN PinH5 // BED +#define FAN_PIN PinG5 // IO pin. Buffer needed // // Misc. Functions // -#define PS_ON_PIN 12 -#define LED_PIN 13 +#define PS_ON_PIN PinB6 +#define LED_PIN PinB7 // // SD Support // #if ENABLED(SDSUPPORT) - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS PinB0 + #define SD_DETECT_PIN PinL0 #endif // // LCD / Controller // #if HAS_WIRED_LCD - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 - #define DOGLCD_A0 27 - #define DOGLCD_CS 29 - #define LCD_RESET_PIN 25 + #define DOGLCD_A0 PinA5 + #define DOGLCD_CS PinA7 + #define LCD_RESET_PIN PinA3 #define LCD_CONTRAST_INIT 255 - #define BTN_EN1 33 - #define BTN_EN2 31 - #define BTN_ENC 35 + #define BTN_EN1 PinC4 + #define BTN_EN2 PinC6 + #define BTN_ENC PinC2 #endif diff --git a/Marlin/src/pins/ramps/env_validate.h b/Marlin/src/pins/ramps/env_validate.h index 6006a78f013c..1e1c82bd5ea8 100644 --- a/Marlin/src/pins/ramps/env_validate.h +++ b/Marlin/src/pins/ramps/env_validate.h @@ -21,15 +21,14 @@ */ #pragma once -#if ENABLED(ALLOW_SAM3X8E) - #if NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino Due' or 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" - #endif -#elif ENABLED(REQUIRE_MEGA2560) && NOT_TARGET(__AVR_ATmega2560__) +// We do not allow __SAM3X8E__ because it is an entirely different MCU type (ARM Cortex M3). +// It would complicate the pin header files too much if they needed to include sets of multiple +// board layouts. + +#if ENABLED(REQUIRE_MEGA2560) && NOT_TARGET(__AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" #elif DISABLED(REQUIRE_MEGA2560) && NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" #endif -#undef ALLOW_SAM3X8E #undef REQUIRE_MEGA2560 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 6f5b775af9ce..f45083774126 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -23,6 +23,7 @@ /** * 3DRAG (and K8200 / K8400) Arduino Mega with RAMPS v1.4 pin assignments + * ATmega2560, ATmega1280 */ #ifndef BOARD_INFO_NAME @@ -40,17 +41,17 @@ // // Limit Switches // -#define Z_STOP_PIN 18 +#define Z_STOP_PIN PinD3 // // Steppers // #if HAS_CUTTER - #define Z_DIR_PIN 28 - #define Z_ENABLE_PIN 24 - #define Z_STEP_PIN 26 + #define Z_DIR_PIN PinA6 + #define Z_ENABLE_PIN PinA2 + #define Z_STEP_PIN PinA4 #else - #define Z_ENABLE_PIN 63 + #define Z_ENABLE_PIN PinK1 #endif #if HAS_CUTTER && !HAS_EXTRUDERS @@ -62,14 +63,14 @@ // // Heaters / Fans // -#define MOSFET_B_PIN 8 -#define MOSFET_C_PIN 9 -#define MOSFET_D_PIN 12 +#define MOSFET_B_PIN PinH5 +#define MOSFET_C_PIN PinH6 +#define MOSFET_D_PIN PinB6 // // Misc. Functions // -#define SDSS 25 +#define SDSS PinA3 #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header @@ -108,16 +109,16 @@ */ #if HAS_CUTTER #if !HAS_EXTRUDERS - #define SPINDLE_LASER_PWM_PIN 46 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 62 // Pullup! - #define SPINDLE_DIR_PIN 48 + #define SPINDLE_LASER_PWM_PIN PinL3 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinK0 // Pullup! + #define SPINDLE_DIR_PIN PinL1 #elif !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use - #define SPINDLE_LASER_ENA_PIN 16 // Pullup or pulldown! - #define SPINDLE_DIR_PIN 17 + #define SPINDLE_LASER_ENA_PIN PinH1 // Pullup or pulldown! + #define SPINDLE_DIR_PIN PinH0 #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM #endif #endif #endif @@ -127,10 +128,10 @@ // // Heaters / Fans // -#define HEATER_2_PIN 6 +#define HEATER_2_PIN PinH3 #undef SD_DETECT_PIN -#define SD_DETECT_PIN 53 +#define SD_DETECT_PIN PinB0 // // LCD / Controller @@ -145,24 +146,24 @@ #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 35 - #define LCD_PINS_D6 33 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinC0 + #define LCD_PINS_D5 PinC2 + #define LCD_PINS_D6 PinC4 + #define LCD_PINS_D7 PinC6 // Buttons #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 23 + #define BTN_EN1 PinH1 + #define BTN_EN2 PinH0 + #define BTN_ENC PinA1 #else - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 #endif // HAS_WIRED_LCD && IS_NEWPANEL diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 24266bb9d289..78486793dab0 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -23,6 +23,7 @@ /** * AZTEEG_X3_PRO (Arduino Mega) pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -44,21 +45,21 @@ // Tested this pin with bed leveling on a Delta with 1 servo. // Physical wire attachment on EXT1: GND, 5V, D47. // -#define SERVO0_PIN 47 +#define SERVO0_PIN PinL2 // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 -#define Z_STOP_PIN 18 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinJ1 +#define Z_STOP_PIN PinD3 #ifndef FAN_PIN - #define FAN_PIN 6 + #define FAN_PIN PinH3 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) - #define CASE_LIGHT_PIN 44 + #define CASE_LIGHT_PIN PinL5 #endif // @@ -78,51 +79,51 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 18 + #define Z_MIN_PROBE_PIN PinD3 #endif // // Steppers // -#define E2_STEP_PIN 23 -#define E2_DIR_PIN 25 -#define E2_ENABLE_PIN 40 +#define E2_STEP_PIN PinA1 +#define E2_DIR_PIN PinA3 +#define E2_ENABLE_PIN PinG1 -#define E3_STEP_PIN 27 -#define E3_DIR_PIN 29 -#define E3_ENABLE_PIN 41 +#define E3_STEP_PIN PinA5 +#define E3_DIR_PIN PinA7 +#define E3_ENABLE_PIN PinG0 -#define E4_STEP_PIN 43 -#define E4_DIR_PIN 37 -#define E4_ENABLE_PIN 42 +#define E4_STEP_PIN PinL6 +#define E4_DIR_PIN PinC0 +#define E4_ENABLE_PIN PinL7 // // Temperature Sensors // -#define TEMP_2_PIN 12 // Analog Input -#define TEMP_3_PIN 11 // Analog Input -#define TEMP_4_PIN 10 // Analog Input -#define TC1 4 // Analog Input (Thermo couple on Azteeg X3Pro) -#define TC2 5 // Analog Input (Thermo couple on Azteeg X3Pro) +#define TEMP_2_PIN PinB6 // Analog Input +#define TEMP_3_PIN PinB5 // Analog Input +#define TEMP_4_PIN PinB4 // Analog Input +#define TC1 PinG5 // Analog Input (Thermo couple on Azteeg X3Pro) +#define TC2 PinE3 // Analog Input (Thermo couple on Azteeg X3Pro) // // Heaters / Fans // -#define HEATER_2_PIN 16 -#define HEATER_3_PIN 17 -#define HEATER_4_PIN 4 -#define HEATER_5_PIN 5 -#define HEATER_6_PIN 6 -#define HEATER_7_PIN 11 +#define HEATER_2_PIN PinH1 +#define HEATER_3_PIN PinH0 +#define HEATER_4_PIN PinG5 +#define HEATER_5_PIN PinE3 +#define HEATER_6_PIN PinH3 +#define HEATER_7_PIN PinB5 #ifndef CONTROLLER_FAN_PIN - #define CONTROLLER_FAN_PIN 4 // Pin used for the fan to cool motherboard (-1 to disable) + #define CONTROLLER_FAN_PIN PinG5 // Pin used for the fan to cool motherboard (-1 to disable) #endif // // Auto fans // -#define AUTO_FAN_PIN 5 +#define AUTO_FAN_PIN PinE3 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN AUTO_FAN_PIN #endif @@ -140,16 +141,16 @@ // LCD / Controller // #undef BEEPER_PIN -#define BEEPER_PIN 33 +#define BEEPER_PIN PinC4 #if EITHER(VIKI2, miniVIKI) #undef SD_DETECT_PIN - #define SD_DETECT_PIN 49 // For easy adapter board + #define SD_DETECT_PIN PinL0 // For easy adapter board #undef BEEPER_PIN - #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display + #define BEEPER_PIN PinB6 // 33 isn't physically available to the LCD display #else - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define STAT_LED_RED_PIN PinC5 + #define STAT_LED_BLUE_PIN PinC2 #endif // @@ -157,7 +158,7 @@ // #if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN #undef DOGLCD_A0 // Steal pin 44 for the case light; if you have a Viki2 and have connected it - #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments + #define DOGLCD_A0 PinF3 // following the Panucatt wiring diagram, you may need to tweak these pin assignments // as the wiring diagram uses pin 44 for DOGLCD_A0. #endif @@ -170,9 +171,9 @@ #if HAS_CUTTER // EXP2 header #if EITHER(VIKI2, miniVIKI) - #define BTN_EN2 31 // Pin 7 needed for Spindle PWM + #define BTN_EN2 PinC6 // Pin 7 needed for Spindle PWM #endif - #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 20 // Pullup! - #define SPINDLE_DIR_PIN 21 + #define SPINDLE_LASER_PWM_PIN PinH4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinD1 // Pullup! + #define SPINDLE_DIR_PIN PinD0 #endif From d7bb6f5a97b6b1389d25782598131648380391a6 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Wed, 7 Dec 2022 00:24:18 +0100 Subject: [PATCH 28/83] - added temperature feedback in Celsius to the Serial output error message --- Marlin/src/core/language.h | 2 + Marlin/src/module/temperature.cpp | 122 ++++++++++++------- Marlin/src/module/temperature.h | 6 +- Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 4 - 4 files changed, 85 insertions(+), 49 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index 545f9df6410b..22fb9cccd4ce 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -247,6 +247,8 @@ #define STR_LASER_TEMP "laser temperature" #define STR_STOPPED_HEATER ", system stopped! Heater_ID: " +#define STR_DETECTED_TEMP_B " (temp: " +#define STR_DETECTED_TEMP_E ")" #define STR_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !" #define STR_T_HEATING_FAILED "Heating failed" #define STR_T_THERMAL_RUNAWAY "Thermal Runaway" diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1802c2106517..2fc8dae90f23 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -784,10 +784,10 @@ volatile bool Temperature::raw_temps_ready = false; if (current_temp > watch_temp_target) heated = true; // - Flag if target temperature reached } else if (ELAPSED(ms, temp_change_ms)) // Watch timer expired - _temp_error(heater_id, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); + _temp_error(heater_id, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD), current_temp); } else if (current_temp < target - (MAX_OVERSHOOT_PID_AUTOTUNE)) // Heated, then temperature fell too far? - _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY), current_temp); } #endif } // every 2 seconds @@ -1261,7 +1261,7 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { kill(lcd_msg, HEATER_FSTR(heater_id)); } -void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_msg, FSTR_P const lcd_msg) { +void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_msg, FSTR_P const lcd_msg, const celsius_float_t deg) { static uint8_t killed = 0; @@ -1287,8 +1287,11 @@ void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_m OPTCODE(HAS_TEMP_BED, case H_BED: SERIAL_ECHOPGM(STR_HEATER_BED); break) default: if (real_heater_id >= 0) - SERIAL_ECHOLNPGM("E", real_heater_id); + SERIAL_ECHOPGM("E", real_heater_id); } + SERIAL_ECHOPGM(STR_DETECTED_TEMP_B); + SERIAL_ECHO(deg); + SERIAL_ECHOLNPGM(STR_DETECTED_TEMP_E); SERIAL_EOL(); } @@ -1318,18 +1321,18 @@ void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_m #endif } -void Temperature::max_temp_error(const heater_id_t heater_id) { +void Temperature::max_temp_error(const heater_id_t heater_id, const celsius_float_t deg) { #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(1); #endif - _temp_error(heater_id, F(STR_T_MAXTEMP), GET_TEXT_F(MSG_ERR_MAXTEMP)); + _temp_error(heater_id, F(STR_T_MAXTEMP), GET_TEXT_F(MSG_ERR_MAXTEMP), deg); } -void Temperature::min_temp_error(const heater_id_t heater_id) { +void Temperature::min_temp_error(const heater_id_t heater_id, const celsius_float_t deg) { #if HAS_DWIN_E3V2_BASIC && (HAS_HOTEND || HAS_HEATED_BED) DWIN_Popup_Temperature(0); #endif - _temp_error(heater_id, F(STR_T_MINTEMP), GET_TEXT_F(MSG_ERR_MINTEMP)); + _temp_error(heater_id, F(STR_T_MINTEMP), GET_TEXT_F(MSG_ERR_MINTEMP), deg); } #if HAS_PID_DEBUG @@ -1545,7 +1548,10 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { void Temperature::manage_hotends(const millis_t &ms) { HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) - if (degHotend(e) > temp_range[e].maxtemp) max_temp_error((heater_id_t)e); + { + auto deg = degHotend(e); + if (deg > temp_range[e].maxtemp) max_temp_error((heater_id_t)e, deg); + } #endif TERN_(HEATER_IDLE_HANDLER, heater_idle[e].update(ms)); @@ -1560,11 +1566,12 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #if WATCH_HOTENDS // Make sure temperature is increasing if (watch_hotend[e].elapsed(ms)) { // Enabled and time to check? - if (watch_hotend[e].check(degHotend(e))) // Increased enough? + auto temp = degHotend(e); + if (watch_hotend[e].check(temp)) // Increased enough? start_watching_hotend(e); // If temp reached, turn off elapsed check else { TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error((heater_id_t)e, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); + _temp_error((heater_id_t)e, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD), temp); } } #endif @@ -1579,19 +1586,25 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { void Temperature::manage_heated_bed(const millis_t &ms) { #if ENABLED(THERMAL_PROTECTION_BED) - if (degBed() > BED_MAXTEMP) max_temp_error(H_BED); + { + auto deg = degBed(); + if (deg > BED_MAXTEMP) max_temp_error(H_BED, deg); + } #endif #if WATCH_BED + { // Make sure temperature is increasing if (watch_bed.elapsed(ms)) { // Time to check the bed? - if (watch_bed.check(degBed())) // Increased enough? + auto deg = degBed(); + if (watch_bed.check(deg)) // Increased enough? start_watching_bed(); // If temp reached, turn off elapsed check else { TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error(H_BED, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); + _temp_error(H_BED, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD), deg); } } + } #endif // WATCH_BED #if BOTH(PROBING_HEATERS_OFF, BED_LIMIT_SWITCHING) @@ -1661,17 +1674,23 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #endif #if ENABLED(THERMAL_PROTECTION_CHAMBER) - if (degChamber() > CHAMBER_MAXTEMP) max_temp_error(H_CHAMBER); + { + auto deg = degChamber(); + if (deg > CHAMBER_MAXTEMP) max_temp_error(H_CHAMBER, deg); + } #endif #if WATCH_CHAMBER + { // Make sure temperature is increasing if (watch_chamber.elapsed(ms)) { // Time to check the chamber? - if (watch_chamber.check(degChamber())) // Increased enough? Error below. + auto deg = degChamber(); + if (watch_chamber.check(deg)) // Increased enough? Error below. start_watching_chamber(); // If temp reached, turn off elapsed check. else - _temp_error(H_CHAMBER, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD)); + _temp_error(H_CHAMBER, FPSTR(str_t_heating_failed), GET_TEXT_F(MSG_HEATING_FAILED_LCD), deg); } + } #endif #if EITHER(CHAMBER_FAN, CHAMBER_VENT) || DISABLED(PIDTEMPCHAMBER) @@ -1788,14 +1807,18 @@ void Temperature::min_temp_error(const heater_id_t heater_id) { #endif #if ENABLED(THERMAL_PROTECTION_COOLER) - if (degCooler() > COOLER_MAXTEMP) max_temp_error(H_COOLER); + { + auto deg = degCooler(); + if (deg > COOLER_MAXTEMP) max_temp_error(H_COOLER, deg); + } #endif #if WATCH_COOLER // Make sure temperature is decreasing if (watch_cooler.elapsed(ms)) { // Time to check the cooler? - if (degCooler() > watch_cooler.target) // Failed to decrease enough? - _temp_error(H_COOLER, GET_TEXT_F(MSG_COOLING_FAILED), GET_TEXT_F(MSG_COOLING_FAILED)); + auto deg = degCooler(); + if (deg > watch_cooler.target) // Failed to decrease enough? + _temp_error(H_COOLER, GET_TEXT_F(MSG_COOLING_FAILED), GET_TEXT_F(MSG_COOLING_FAILED), deg); else start_watching_cooler(); // Start again if the target is still far off } @@ -1880,20 +1903,32 @@ void Temperature::task() { #if DISABLED(IGNORE_THERMOCOUPLE_ERRORS) #if TEMP_SENSOR_IS_MAX_TC(0) - if (degHotend(0) > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) max_temp_error(H_E0); - if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0); + { + auto deg = degHotend(0); + if (deg > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) max_temp_error(H_E0, deg); + if (deg < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0, deg); + } #endif #if TEMP_SENSOR_IS_MAX_TC(1) - if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); - if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + { + auto deg = degHotend(1); + if (deg > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1, deg); + if (deg < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1, deg); + } #endif #if TEMP_SENSOR_IS_MAX_TC(2) - if (degHotend(2) > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.0)) max_temp_error(H_E2); - if (degHotend(2) < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + .01)) min_temp_error(H_E2); + { + auto deg = degHotend(2); + if (deg > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.0)) max_temp_error(H_E2, deg); + if (deg < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + .01)) min_temp_error(H_E2, deg); + } #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) - if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); - if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); + { + auto deg = degRedundant(); + if (deg > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT, deg); + if (deg < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT, deg); + } #endif #else #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" @@ -1905,9 +1940,12 @@ void Temperature::task() { TERN_(HAS_HOTEND, manage_hotends(ms)); #if HAS_TEMP_REDUNDANT + { + auto deg = degRedundant(); // Make sure measured temperatures are close together - if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) - _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP)); + if (ABS(degRedundantTarget() - deg) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) + _temp_error((heater_id_t)HEATER_ID(TEMP_SENSOR_REDUNDANT_TARGET), F(STR_REDUNDANCY), GET_TEXT_F(MSG_ERR_REDUNDANT_TEMP), deg); + } #endif // Manage extruder auto fans and/or read fan tachometers @@ -2404,7 +2442,7 @@ void Temperature::updateTemperaturesFromRawValues() { const raw_adc_t r = temp_hotend[e].getraw(); const bool neg = temp_dir[e] < 0, pos = temp_dir[e] > 0; if ((neg && r < temp_range[e].raw_max) || (pos && r > temp_range[e].raw_max)) - max_temp_error((heater_id_t)e); + max_temp_error((heater_id_t)e, temp_hotend[e].celsius); /** // DEBUG PREHEATING TIME @@ -2416,7 +2454,7 @@ void Temperature::updateTemperaturesFromRawValues() { const bool heater_on = temp_hotend[e].target > 0; if (heater_on && !is_preheating(e) && ((neg && r > temp_range[e].raw_min) || (pos && r < temp_range[e].raw_min))) { if (TERN1(MULTI_MAX_CONSECUTIVE_LOW_TEMP_ERR, ++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED)) - min_temp_error((heater_id_t)e); + min_temp_error((heater_id_t)e, temp_hotend[e].celsius); } else { TERN_(MULTI_MAX_CONSECUTIVE_LOW_TEMP_ERR, consecutive_low_temperature_error[e] = 0); @@ -2427,23 +2465,23 @@ void Temperature::updateTemperaturesFromRawValues() { #define TP_CMP(S,A,B) (TEMPDIR(S) < 0 ? ((A)<(B)) : ((A)>(B))) #if ENABLED(THERMAL_PROTECTION_BED) - if (TP_CMP(BED, temp_bed.getraw(), maxtemp_raw_BED)) max_temp_error(H_BED); - if (temp_bed.target > 0 && TP_CMP(BED, mintemp_raw_BED, temp_bed.getraw())) min_temp_error(H_BED); + if (TP_CMP(BED, temp_bed.getraw(), maxtemp_raw_BED)) max_temp_error(H_BED, temp_bed.celsius); + if (temp_bed.target > 0 && TP_CMP(BED, mintemp_raw_BED, temp_bed.getraw())) min_temp_error(H_BED, temp_bed.celsius); #endif #if BOTH(HAS_HEATED_CHAMBER, THERMAL_PROTECTION_CHAMBER) - if (TP_CMP(CHAMBER, temp_chamber.getraw(), maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER); - if (temp_chamber.target > 0 && TP_CMP(CHAMBER, mintemp_raw_CHAMBER, temp_chamber.getraw())) min_temp_error(H_CHAMBER); + if (TP_CMP(CHAMBER, temp_chamber.getraw(), maxtemp_raw_CHAMBER)) max_temp_error(H_CHAMBER, temp_chamber.celsius); + if (temp_chamber.target > 0 && TP_CMP(CHAMBER, mintemp_raw_CHAMBER, temp_chamber.getraw())) min_temp_error(H_CHAMBER, temp_chamber.celsius); #endif #if BOTH(HAS_COOLER, THERMAL_PROTECTION_COOLER) - if (cutter.unitPower > 0 && TP_CMP(COOLER, temp_cooler.getraw(), maxtemp_raw_COOLER)) max_temp_error(H_COOLER); - if (TP_CMP(COOLER, mintemp_raw_COOLER, temp_cooler.getraw())) min_temp_error(H_COOLER); + if (cutter.unitPower > 0 && TP_CMP(COOLER, temp_cooler.getraw(), maxtemp_raw_COOLER)) max_temp_error(H_COOLER, temp_cooler.celsius); + if (TP_CMP(COOLER, mintemp_raw_COOLER, temp_cooler.getraw())) min_temp_error(H_COOLER, temp_cooler.celsius); #endif #if BOTH(HAS_TEMP_BOARD, THERMAL_PROTECTION_BOARD) - if (TP_CMP(BOARD, temp_board.getraw(), maxtemp_raw_BOARD)) max_temp_error(H_BOARD); - if (TP_CMP(BOARD, mintemp_raw_BOARD, temp_board.getraw())) min_temp_error(H_BOARD); + if (TP_CMP(BOARD, temp_board.getraw(), maxtemp_raw_BOARD)) max_temp_error(H_BOARD, temp_board.celsius); + if (TP_CMP(BOARD, mintemp_raw_BOARD, temp_board.getraw())) min_temp_error(H_BOARD, temp_board.celsius); #endif #undef TP_CMP @@ -2936,12 +2974,12 @@ void Temperature::init() { case TRRunaway: TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY)); + _temp_error(heater_id, FPSTR(str_t_thermal_runaway), GET_TEXT_F(MSG_THERMAL_RUNAWAY), current); #if ENABLED(THERMAL_PROTECTION_VARIANCE_MONITOR) case TRMalfunction: TERN_(HAS_DWIN_E3V2_BASIC, DWIN_Popup_Temperature(0)); - _temp_error(heater_id, FPSTR(str_t_temp_malfunction), GET_TEXT_F(MSG_TEMP_MALFUNCTION)); + _temp_error(heater_id, FPSTR(str_t_temp_malfunction), GET_TEXT_F(MSG_TEMP_MALFUNCTION), current); #endif } } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index d0f7d2dda774..b326b1e87126 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1134,9 +1134,9 @@ class Temperature { static float get_pid_output_chamber(); #endif - static void _temp_error(const heater_id_t e, FSTR_P const serial_msg, FSTR_P const lcd_msg); - static void min_temp_error(const heater_id_t e); - static void max_temp_error(const heater_id_t e); + static void _temp_error(const heater_id_t e, FSTR_P const serial_msg, FSTR_P const lcd_msg, const celsius_float_t deg); + static void min_temp_error(const heater_id_t e, const celsius_float_t deg); + static void max_temp_error(const heater_id_t e, const celsius_float_t deg); #define HAS_THERMAL_PROTECTION ANY(THERMAL_PROTECTION_HOTENDS, THERMAL_PROTECTION_CHAMBER, THERMAL_PROTECTION_BED, THERMAL_PROTECTION_COOLER) diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 8b8d171d8c10..840e02776456 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -216,10 +216,6 @@ #define STAT_LED_RED_PIN SERVO0_PIN // C1 (1280-EX1, DEBUG2) #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) - #elif ENABLED(MKS_TS35_V2_0) - - - #else // Replicator uses a 3-wire SR controller with HD44780 #define SR_DATA_PIN PinC3 // C3 From e22249aee44b2b22b1489958ecf2dfd65c2ac70c Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Wed, 7 Dec 2022 15:08:51 +0100 Subject: [PATCH 29/83] - fixed a crash in the LCD menu progress indication rotation where a presence of no status updates was unchecked, causing a jump to corrupt memory locations - various adjustments --- Marlin/src/lcd/marlinui.cpp | 33 +++++++++++++++++++++------------ Marlin/src/lcd/marlinui.h | 6 +++++- Marlin/src/libs/numtostr.cpp | 2 +- 3 files changed, 27 insertions(+), 14 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index cdda7ca85abf..057de368501f 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -644,14 +644,20 @@ void MarlinUI::init() { #endif // BASIC_PROGRESS_BAR - bool did_expire = status_reset_callback && (*status_reset_callback)(); + bool did_expire = false; + + if (status_reset_callback) { + did_expire = (*status_reset_callback)(); + } #if HAS_STATUS_MESSAGE_TIMEOUT - #ifndef GOT_MS - #define GOT_MS - const millis_t ms = millis(); - #endif - did_expire |= status_message_expire_ms && ELAPSED(ms, status_message_expire_ms); + if (did_expire == false) { + #ifndef GOT_MS + #define GOT_MS + const millis_t ms = millis(); + #endif + did_expire |= status_message_expire_ms && ELAPSED(ms, status_message_expire_ms); + } #endif if (did_expire) reset_status(); @@ -1743,12 +1749,15 @@ void MarlinUI::init() { OPTITEM(SHOW_REMAINING_TIME, drawRemain) OPTITEM(SHOW_INTERACTION_TIME, drawInter) }; - static bool prev_blink; - static uint8_t i; - if (prev_blink != get_blink()) { - prev_blink = get_blink(); - if (++i >= COUNT(progFunc)) i = 0; - (*progFunc[i])(); + if constexpr (COUNT(progFunc) > 0) { + static bool prev_blink; + static uint8_t i; + if (prev_blink != get_blink()) { + prev_blink = get_blink(); + i++; + if (i >= COUNT(progFunc)) i = 0; + (*progFunc[i])(); + } } } #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ec19f8bd34ba..901b2831bc19 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -589,7 +589,11 @@ class MarlinUI { static void return_to_status(); static bool on_status_screen() { return currentScreen == status_screen; } - FORCE_INLINE static void run_current_screen() { (*currentScreen)(); } + FORCE_INLINE static void run_current_screen() { + if (currentScreen) { + (*currentScreen)(); + } + } #if ENABLED(LIGHTWEIGHT_UI) static void lcd_in_status(const bool inStatus); diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 594255aea81e..50527ce5301f 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -28,7 +28,7 @@ char conv[8] = { 0 }; #define DIGIT(n) ('0' + (n)) -#define DIGIMOD(n, f) DIGIT((n)/(f) % 10) +#define DIGIMOD(n, f) DIGIT(((n)/(f)) % 10) #define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) #define INTFLOAT(V,N) (((V) * 10 * pow(10, N) + ((V) < 0 ? -5: 5)) / 10) // pow10? From 7446980bdb82d80a95bdf49773b788406c926909 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 8 Dec 2022 01:18:18 +0100 Subject: [PATCH 30/83] - added optimized HAL SPI implementation for 8bit AVR MCUs - added generic HW implementation for 8bit AVR MCUs based on the ArduinoCore new preprocessor macro AVR_CHIPOSCILLATOR_FREQ: please look into your board manufacturer schematics to find the XTAL1/XTAL2 pins, then create a pin header board preprocessor definition with the Hz number (typically in MHz) to enable the optimized AVR HAL SPI implementation. - removed an unnecessary comment that I added in Sd2Card --- Marlin/src/HAL/AVR/HAL_SPI_HW.cpp | 235 +++++++-- Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp | 236 +++++++++ Marlin/src/HAL/AVR/HAL_SPI_SW.cpp | 13 +- Marlin/src/HAL/AVR/registers.h | 744 ++++++++++++++------------- Marlin/src/lcd/marlinui.cpp | 4 +- Marlin/src/sd/Sd2Card.cpp | 1 - 6 files changed, 824 insertions(+), 409 deletions(-) create mode 100644 Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp index 7b326018ae9b..774cc77f3152 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp @@ -21,8 +21,12 @@ */ /** - * Adapted from Arduino Sd2Card Library - * Copyright (c) 2009 by William Greiman + * AVR HAL SPI implementation made by Martin Turski, company owner of EirDev + * This implementation was specifically made for the Marlin FW. + * For inquiries please contact turningtides@outlook.de + * If there is any issue with this implementation, please open an inquiry on GitHub + * and include the link in the mail. Otherwise your mail may get ignored. + * Made to improve the reliability and future-proof Marlin. */ /** @@ -33,9 +37,11 @@ #include "../../inc/MarlinConfig.h" +#if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI, HALSPI_HW_GENERIC) + #include "registers.h" -#if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) +#include #ifndef AVR_CHIPOSCILLATOR_FREQ #error Missing AVR crystal oscillator frequency! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) @@ -76,11 +82,61 @@ } } + #ifndef HALSPI_LOOPBEEP_TIMEOUT + #define HALSPI_LOOPBEEP_TIMEOUT 3000 + #endif + + struct spi_monitored_loop + { + private: + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; + #endif + public: + inline spi_monitored_loop() { + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); + #endif + } + inline void update(unsigned int beep_code) { + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); + delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); + #endif + } + }; + static bool _spi_is_running = false; static int _spi_cs_pin; static bool _spi_transaction_is_active; static bool _spi_dirty_tx; +#if defined(GET_LOW_FUSE_BITS) + static uint8_t _spi_lfuse; +#endif + void spiBegin() { #if PIN_EXISTS(SD_SS) // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. @@ -93,17 +149,32 @@ #endif #endif // This could still be required because the specification says that the DDR of those pins is "User Defined". + // (we only support master SPI) SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); SET_OUTPUT(SD_MOSI_PIN); + #if defined(GET_LOW_FUSE_BITS) + cli(); + _spi_lfuse = boot_lock_fuse_bits_get(GET_LOW_FUSE_BITS); + sei(); + #endif + // By default we disable the SPI peripheral. + _PRR0._PRSPI = false; + _SPCR._SPE = false; _PRR0._PRSPI = true; } // Returns the clock frequency as output by the System Clock Prescaler. inline uint32_t _GetSystemClockFrequency() { // See which clock is selected. - const ATmega_lfuse lfuse = AVR_LFUSE_VALUE; + const ATmega_lfuse lfuse = +#ifndef GET_LOW_FUSE_BITS + AVR_DEFAULT_LFUSE_VALUE; +#else + _spi_lfuse; +#endif uint32_t baseclk; @@ -132,7 +203,9 @@ return ( baseclk >> clkps_po2 ); } - inline void _spiConfigBitOrder(SPCR_reg_t& __SPCR, int mode) { + // We could improve these definitions if we had C++20. + template // SPCR_reg_t + inline void _spiConfigBitOrder(regType& __SPCR, int mode) { if (mode == SPI_BITORDER_LSB) { __SPCR._DORD = 1; } @@ -141,7 +214,8 @@ } } - inline void _spiConfigClockMode(SPCR_reg_t& __SPCR, int mode) { + template // SPCR_reg_t + inline void _spiConfigClockMode(regType& __SPCR, int mode) { if (mode == SPI_CLKMODE_0) { __SPCR._CPOL = 0; __SPCR._CPHA = 0; @@ -160,6 +234,71 @@ } } +#ifndef HALSPI_AVR_NO_SLEEP + + static volatile bool _spi_txcomplete = true; + + inline void _spi_enter_wait() { + cli(); + + SMCR_reg_t __SMCR; + __SMCR._SE = true; + __SMCR._SM = 0; // IDLE + __SMCR.reserved1 = 0; + AVRHelpers::dwrite(_SMCR) = __SMCR; + + // Enable the SPI interrupt. + _SPCR._SPIE = true; + _spi_txcomplete = false; + + sei(); + } + + inline void _spi_leave_wait() { + SMCR_reg_t __SMCR; + __SMCR._SE = false; + __SMCR._SM = 0; + __SMCR.reserved1 = 0; + AVRHelpers::dwrite(_SMCR) = __SMCR; + + // Disable the SPI interrupt. + _SPCR._SPIE = false; + _spi_txcomplete = true; + } + +#include + + ISR(SPI_STC_vect) { + // Make sure that a SLEEP instruction right after this interrupt call does not halt the processor. + // This is sort of like an event variable in Win32 or a futex in Linux. + _spi_leave_wait(); + } +#endif + + inline void _spi_waitForInterrupt() { +#ifndef HALSPI_AVR_NO_SLEEP + // This function is meant to sleep until the AVR SPI peripheral triggers the SPIF interrupt. + __asm__ __volatile__( + A("SLEEP") + ); +#endif + } + + inline bool _spi_hasTransferCompleted() { +#ifdef HALSPI_AVR_NO_SLEEP + return _SPSR._SPIF; +#else + return _spi_txcomplete; +#endif + } + + inline void _spi_push(uint8_t b) { +#ifndef HALSPI_AVR_NO_SLEEP + _spi_enter_wait(); +#endif + _SPDR = b; + } + /** * Initialize hardware SPI transaction */ @@ -168,15 +307,10 @@ _spi_on_error(1); // In hardware SPI mode we can only use the pre-determined SPI pins for MISO, MOSI and SCK, thus ignore the first three pin hints. - // But for the chip-select pin, we either have to go HW mode if it is the peripheral SPI pin or we can go SW if it is a GPIO. - if ( _ATmega_getPinFunctions(hint_cs).hasFunc(eATmegaPinFunc::SPI_CS) ) { - // HW SPI_CS - _spi_cs_pin = -1; - } - else { - // SW SPI_CS - _spi_cs_pin = hint_cs; - } + // We only support master SPI for now. + // For this we have to configure the chip-select (~SS) pin as output. + // This way it cannot be driven low by external peripherals., thus keeping our master state. + _spi_cs_pin = hint_cs; // Clear the power-reduction. _PRR0._PRSPI = false; @@ -186,7 +320,7 @@ SPCR_reg_t __SPCR; __SPCR._SPIE = false; - __SPCR._SPE = true; + __SPCR._SPE = false; _spiConfigBitOrder(__SPCR, SPI_BITORDER_DEFAULT); __SPCR._MSTR = true; _spiConfigClockMode(__SPCR, SPI_CLKMODE_DEFAULT); @@ -222,7 +356,7 @@ } // Write initial configuration. - _SPCR = __SPCR; + AVRHelpers::dwrite(_SPCR) = __SPCR; _spi_is_running = true; _spi_transaction_is_active = false; @@ -232,8 +366,12 @@ static void _maybe_start_transaction() { if (_spi_transaction_is_active) return; - if (_spi_cs_pin >= 0) + _SPCR._SPE = true; + + if (_spi_cs_pin >= 0) { + _ATmega_pinMode(_spi_cs_pin, OUTPUT); _ATmega_digitalWrite(_spi_cs_pin, LOW); + } _spi_transaction_is_active = true; } @@ -254,10 +392,16 @@ spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); } + inline void _spi_safety_delay() { + //asm("nop"); // enable this if you encounter any delay troubles. + } + inline void _spi_finish_tx() { if (_spi_dirty_tx == false) return; - while (_SPSR._SPIF == false) { /* do nothing */ } + _spi_safety_delay(); + spi_monitored_loop txew; + while (_spi_hasTransferCompleted() == false) { txew.update(1); _spi_waitForInterrupt(); } _spi_dirty_tx = false; } @@ -266,12 +410,14 @@ if (_spi_is_running == false) _spi_on_error(2); - _spi_finish_tx(); - if (_spi_transaction_is_active) { + _spi_finish_tx(); + if (_spi_cs_pin >= 0) _ATmega_digitalWrite(_spi_cs_pin, HIGH); - + + _SPCR._SPE = false; + _spi_transaction_is_active = false; } @@ -282,23 +428,29 @@ } void spiSetBitOrder(int bitOrder) { + if (_spi_is_running == false) _spi_on_error(4); _spiConfigBitOrder(_SPCR, bitOrder); } void spiSetClockMode(int clockMode) { + if (_spi_is_running == false) _spi_on_error(4); _spiConfigClockMode(_SPCR, clockMode); } void spiEstablish() { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); } /** SPI receive a byte */ uint8_t spiRec(uint8_t txval) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); _spi_finish_tx(); - _SPDR = txval; - while (_SPSR._SPIF == false) { /* wait until data has been received */ } + _spi_push(txval); + _spi_safety_delay(); + spi_monitored_loop rxew; + while (_spi_hasTransferCompleted() == false) { rxew.update(2); _spi_waitForInterrupt(); } return _SPDR; } @@ -323,49 +475,55 @@ } uint16_t spiRec16(uint16_t txval) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); bool msb = ( _SPCR._DORD == 0 ); uint8_t tx_first, tx_second; _split_txbytes(txval, tx_first, tx_second, msb); _spi_finish_tx(); - _SPDR = tx_first; - while (_SPSR._SPIF == false) { /* Intentionally left empty */ } + _spi_push(tx_first); + _spi_safety_delay(); + spi_monitored_loop rxe1w; + while (_spi_hasTransferCompleted() == false) { rxe1w.update(3); _spi_waitForInterrupt(); } uint8_t rx_first = _SPDR; - _SPDR = tx_second; - while (_SPSR._SPIF == false) { /* Intentionally left empty */ } + _spi_push(tx_second); + _spi_safety_delay(); + spi_monitored_loop rxe2w; + while (_spi_hasTransferCompleted() == false) { rxe2w.update(4); _spi_waitForInterrupt(); } uint8_t rx_second = _SPDR; return _fuse_txbytes(rx_first, rx_second, msb); } /** SPI read data */ void spiRead(uint8_t *buf, uint16_t nbyte, uint8_t txval) { + if (_spi_is_running == false) _spi_on_error(4); if (nbyte == 0) return; _maybe_start_transaction(); - nbyte--; _spi_finish_tx(); - _SPDR = txval; for (uint16_t i = 0; i < nbyte; i++) { - while (_SPSR._SPIF == false) { /* do nothing */ } + _spi_push(txval); + _spi_safety_delay(); + spi_monitored_loop rxew; + while (_spi_hasTransferCompleted() == false) { rxew.update(5); _spi_waitForInterrupt(); } buf[i] = _SPDR; - _SPDR = txval; } - while (_SPSR._SPIF == false) { /* do nothing */ } - buf[nbyte] = _SPDR; } inline void _spiSendByte(uint8_t byte) { _spi_finish_tx(); - _SPDR = byte; + _spi_push(byte); _spi_dirty_tx = true; } /** SPI send a byte */ void spiSend(uint8_t b) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); _spiSendByte(b); } void spiSend16(uint16_t v) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); bool msb = ( _SPCR._DORD == 0 ); uint8_t tx_first, tx_second; @@ -376,6 +534,7 @@ /** SPI send block */ void spiSendBlock(uint8_t token, const uint8_t *buf) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); _spiSendByte(token); for (uint16_t i = 0; i < 512; i++) { @@ -385,12 +544,14 @@ /** Begin SPI transaction */ void spiWrite(const uint8_t *buf, uint16_t cnt) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); for (uint16_t n = 0; n < cnt; n++) - _spiSendByte(n); + _spiSendByte(buf[n]); } void spiWrite16(const uint16_t *buf, uint16_t cnt) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); bool msb = ( _SPCR._DORD == 0 ); for (uint16_t n = 0; n < cnt; n++) { @@ -402,12 +563,14 @@ } void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); for (uint16_t n = 0; n < repcnt; n++) _spiSendByte(val); } void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + if (_spi_is_running == false) _spi_on_error(4); _maybe_start_transaction(); bool msb = ( _SPCR._DORD == 0 ); uint8_t tx_first, tx_second; diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp new file mode 100644 index 000000000000..d521f88c8b0d --- /dev/null +++ b/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp @@ -0,0 +1,236 @@ +/** + * 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 . + * + */ + +/** + * HAL for AVR - SPI functions + */ + +#ifdef __AVR__ + +#include "../../inc/MarlinConfig.h" + +#if NONE(SOFTWARE_SPI, FORCE_SOFT_SPI) && ENABLED(HALSPI_HW_GENERIC) + +#include + +#include "registers.h" + + void spiBegin() { + #if PIN_EXISTS(SD_SS) + // Do not init HIGH for boards with pin 4 used as Fans or Heaters or otherwise, not likely to have multiple SPI devices anyway. + #if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + // SS must be in output mode even if it is not chip select + SET_OUTPUT(SD_SS_PIN); + #else + // set SS high - may be chip select for another SPI device + OUT_WRITE(SD_SS_PIN, HIGH); + #endif + #endif + // This could still be required because the specification says that the DDR of those pins is "User Defined". + // (we only support master SPI) + SET_OUTPUT(SD_SCK_PIN); + SET_INPUT(SD_MISO_PIN); + SET_OUTPUT(SD_MOSI_PIN); + } + + static SPISettings _spi_config; + static uint32_t _spi_maxClockFreq; + static int _spi_clockMode; + static int _spi_bitOrder; + static bool _spi_transaction_is_running; + static int _spi_cs_pin; + + void spiInitEx(uint32_t maxClockFreq, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { + SPI.begin(); + + _spi_maxClockFreq = maxClockFreq; + _spi_clockMode = SPI_MODE0; + _spi_bitOrder = MSBFIRST; + _spi_config = SPISettings(_spi_maxClockFreq, _spi_bitOrder, _spi_clockMode); + + _spi_cs_pin = hint_cs; + + _spi_transaction_is_running = false; + } + + void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // Use datarates Marlin uses + uint32_t clock; + switch (spiRate) { + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_HALF_SPEED: clock = 5000000; break; + case SPI_QUARTER_SPEED: clock = 2500000; break; + case SPI_EIGHTH_SPEED: clock = 1250000; break; + case SPI_SPEED_5: clock = 625000; break; + case SPI_SPEED_6: clock = 300000; break; + default: + clock = 4000000; // Default from the SPI library + } + spiInitEx(clock, hint_sck, hint_miso, hint_mosi, hint_cs); + } + + void spiClose() { + if (_spi_transaction_is_running) { + if (_spi_cs_pin >= 0) + _ATmega_digitalWrite(_spi_cs_pin, HIGH); + + SPI.endTransaction(); + + _spi_transaction_is_running = false; + } + + SPI.end(); + } + + void spiSetBitOrder(int bitOrder) { + int new_bitOrder; + + if (bitOrder == SPI_BITORDER_MSB) { + new_bitOrder = MSBFIRST; + } + else if (bitOrder == SPI_BITORDER_LSB) { + new_bitOrder = LSBFIRST; + } + else return; + + if (_spi_bitOrder == new_bitOrder) return; + + _spi_bitOrder = new_bitOrder; + _spi_config = SPISettings(_spi_maxClockFreq, _spi_bitOrder, _spi_clockMode); + + if (_spi_transaction_is_running) { + SPI.endTransaction(); + SPI.beginTransaction(_spi_config); + } + } + + void spiSetClockMode(int clockMode) { + int new_clockMode; + + if (clockMode == SPI_CLKMODE_0) { + new_clockMode = SPI_MODE0; + } + else if (clockMode == SPI_CLKMODE_1) { + new_clockMode = SPI_MODE1; + } + else if (clockMode == SPI_CLKMODE_2) { + new_clockMode = SPI_MODE2; + } + else if (clockMode == SPI_CLKMODE_3) { + new_clockMode = SPI_MODE3; + } + else return; + + if (new_clockMode == _spi_clockMode) return; + + _spi_clockMode = new_clockMode; + _spi_config = SPISettings(_spi_maxClockFreq, _spi_bitOrder, _spi_clockMode); + + if (_spi_transaction_is_running) { + SPI.endTransaction(); + SPI.beginTransaction(_spi_config); + } + } + + static void _maybe_start_transaction() { + if (_spi_transaction_is_running) return; + + SPI.beginTransaction(_spi_config); + + if (_spi_cs_pin >= 0) { + _ATmega_pinMode(_spi_cs_pin, OUTPUT); + _ATmega_digitalWrite(_spi_cs_pin, LOW); + } + + _spi_transaction_is_running = true; + } + + void spiEstablish() { + _maybe_start_transaction(); + } + + void spiSend(uint8_t txval) { + _maybe_start_transaction(); + (void)SPI.transfer(txval); + } + + void spiSend16(uint8_t txval) { + _maybe_start_transaction(); + (void)SPI.transfer16(txval); + } + + uint8_t spiRec(uint8_t txval) { + _maybe_start_transaction(); + return SPI.transfer(txval); + } + + uint16_t spiRec16(uint16_t txval) { + _maybe_start_transaction(); + return SPI.transfer16(txval); + } + + void spiRead(uint8_t *buf, uint16_t rdcnt, uint8_t txval) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < rdcnt; n++) { + buf[n] = SPI.transfer(txval); + } + } + + void spiSendBlock(uint8_t token, const uint8_t *block) { + _maybe_start_transaction(); + (void)SPI.transfer(token); + for (uint16_t n = 0; n < 512; n++) { + (void)SPI.transfer(block[n]); + } + } + + void spiWrite(const uint8_t *buf, uint16_t cnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < cnt; n++) { + (void)SPI.transfer(buf[n]); + } + } + + void spiWrite16(const uint16_t *buf, uint16_t cnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < cnt; n++) { + (void)SPI.transfer16(buf[n]); + } + } + + void spiWriteRepeat(uint8_t val, uint16_t repcnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < repcnt; n++) { + (void)SPI.transfer(val); + } + } + + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { + _maybe_start_transaction(); + for (uint16_t n = 0; n < repcnt; n++) { + (void)SPI.transfer16(val); + } + } + +#endif + +#endif //__AVR__ \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp index ece1756dc97e..ee1e86a137db 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp @@ -91,9 +91,6 @@ OUT_WRITE(SD_SS_PIN, HIGH); #endif #endif - // This could still be required because the specification says that the DDR of those pins is "User Defined". - SET_OUTPUT(SD_SCK_PIN); - SET_OUTPUT(SD_MOSI_PIN); } void spiInit(uint8_t spiRate, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { @@ -160,9 +157,7 @@ void spiSetClockMode(int clockMode) { // TODO. - if (clockMode != SPI_CLKMODE_0) { - for (;;) {} - } + _spi_on_error(3); } void spiEstablish() { /* do nothing */ } @@ -170,8 +165,7 @@ // Soft SPI receive byte uint8_t spiRec(uint8_t txval) { if (txval != 0xFF) { - // TODO. - for (;;) {} + _spi_on_error(4); } uint8_t data = 0; // no interrupts during byte receive - about 8µs @@ -202,8 +196,7 @@ uint16_t spiRec16(uint16_t txval) { if (txval != 0xFFFF) { - // TODO. - for (;;) {} + _spi_on_error(4); } uint16_t data = 0; bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 5aae44ba72f2..c41f8a0fb658 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -24,6 +24,10 @@ #include +// This volatile-nonsense has to be done due to the C++ platform language specialization that specifies, for it's own compiler ideology, +// that memory writes and reads can be optimized across easily-reachable code spaces. This is in contrast to MSVC which specifies that +// memory writes and reads are holy. + // OVERVIEW OF PREPROCESSOR DEFINITIONS: // __AVR_ATmega2560__ // __AVR_ATmega1284P__ @@ -79,10 +83,10 @@ struct _bit_reg_t { uint8_t val; - bool getValue(uint8_t idx) { + bool getValue(uint8_t idx) const volatile { return ( val & (1< +struct no_volatile { + typedef T type; +}; + +template +struct no_volatile : public no_volatile {}; + +template +inline typename no_volatile ::type& dwrite( memRegType& V ) { return (typename no_volatile ::type&)V; } + +} // namespace AVRHelpers inline void _ATmega_resetperipherals() { + using namespace AVRHelpers; + // Due to BOOTLOADER or other board inconsistencies we could get launched into Marlin FW // with configuration that does not match the reset state in the documentation. That is why // we should clean-reset the entire device. @@ -1874,7 +1894,7 @@ inline void _ATmega_resetperipherals() { __SREG._H = false; __SREG._T = false; __SREG._I = false; - _SREG = __SREG; + dwrite(_SREG) = __SREG; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) @@ -1886,7 +1906,7 @@ inline void _ATmega_resetperipherals() { #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) _EEAR._EEAR = 0; - _EEDR = 0; + dwrite(_EEDR) = 0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1898,7 +1918,7 @@ inline void _ATmega_resetperipherals() { __EECR._EEPM0 = 0; __EECR._EEPM1 = 0; __EECR.reserved1 = 0; - _EECR = __EECR; + dwrite(_EECR) = __EECR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1913,13 +1933,13 @@ inline void _ATmega_resetperipherals() { __XMCRA._SRW1 = 0; __XMCRA._SRL = 0; __XMCRA._SRE = 0; - _XMCRA = __XMCRA; + dwrite(_XMCRA) = __XMCRA; XMCRB_reg_t __XMCRB; __XMCRB._XMM = 0; __XMCRB.reserved1 = 0; __XMCRB._XMBK = false; - _XMCRB = __XMCRB; + dwrite(_XMCRB) = __XMCRB; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1927,7 +1947,7 @@ inline void _ATmega_resetperipherals() { __SMCR._SE = false; __SMCR._SM = 0; __SMCR.reserved1 = 0; - _SMCR = __SMCR; + dwrite(_SMCR) = __SMCR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1960,7 +1980,7 @@ inline void _ATmega_resetperipherals() { __PRR0._PRTIM2 = false; __PRR0._PRTWI = false; #endif - _PRR0 = __PRR0; + dwrite(_PRR0) = __PRR0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -1980,7 +2000,7 @@ inline void _ATmega_resetperipherals() { __PRR1._PRUSART1 = false; __PRR1.reserved1 = 0; #endif - _PRR1 = __PRR1; + dwrite(_PRR1) = __PRR1; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1993,7 +2013,7 @@ inline void _ATmega_resetperipherals() { __WDTCSR._WDP3 = 0; __WDTCSR._WDIE = false; __WDTCSR._WDIF = false; - _WDTCSR = __WDTCSR; + dwrite(_WDTCSR) = __WDTCSR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2008,16 +2028,16 @@ inline void _ATmega_resetperipherals() { #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - _PORTA = __PORT; - _PORTC = __PORT; + dwrite(_PORTA) = __PORT; + dwrite(_PORTC) = __PORT; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _PORTB = __PORT; - _PORTD = __PORT; + dwrite(_PORTB) = __PORT; + dwrite(_PORTD) = __PORT; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - _PORTE = __PORT; - _PORTF = __PORT; + dwrite(_PORTE) = __PORT; + dwrite(_PORTF) = __PORT; #endif #if defined(__AVR_TRM01__) @@ -2028,7 +2048,7 @@ inline void _ATmega_resetperipherals() { __PORTG._DDR.reserved1 = 0; __PORTG._PORT.val = 0; __PORTG._PORT.reserved1 = 0; - _PORTG = __PORTG; + dwrite(_PORTG) = __PORTG; #endif #if defined(__AVR_TRM03__) @@ -2039,14 +2059,14 @@ inline void _ATmega_resetperipherals() { __PORTC._DDR.reserved1 = 0; __PORTC._PORT.val = 0; __PORTC._PORT.reserved1 = 0; - _PORTC = __PORTC; + dwrite(_PORTC) = __PORTC; #endif #if defined(__AVR_TRM01__) - _PORTH = __PORT; - _PORTJ = __PORT; - _PORTK = __PORT; - _PORTL = __PORT; + dwrite(_PORTH) = __PORT; + dwrite(_PORTJ) = __PORT; + dwrite(_PORTK) = __PORT; + dwrite(_PORTL) = __PORT; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2066,7 +2086,7 @@ inline void _ATmega_resetperipherals() { __EICRA._ISC1 = 0; __EICRA.reserved1 = 0; #endif - _EICRA = __EICRA; + dwrite(_EICRA) = __EICRA; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) @@ -2075,7 +2095,7 @@ inline void _ATmega_resetperipherals() { __EICRB._ISC5 = 0; __EICRB._ISC6 = 0; __EICRB._ISC7 = 0; - _EICRB = __EICRB; + dwrite(_EICRB) = __EICRB; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2099,7 +2119,7 @@ inline void _ATmega_resetperipherals() { __EIMSK._INT1 = false; __EIMSK.reserved1 = 0; #endif - _EIMSK = __EIMSK; + dwrite(_EIMSK) = __EIMSK; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2123,7 +2143,7 @@ inline void _ATmega_resetperipherals() { __EIFR._INTF1 = false; __EIFR.reserved1 = 0; #endif - _EIFR = __EIFR; + dwrite(_EIFR) = __EIFR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2143,7 +2163,7 @@ inline void _ATmega_resetperipherals() { __PCICR._PCIE0 = false; __PCICR.reserved1 = 0; #endif - _PCICR = __PCICR; + dwrite(_PCICR) = __PCICR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2163,7 +2183,7 @@ inline void _ATmega_resetperipherals() { __PCIFR._PCIF0 = false; __PCIFR.reserved1 = 0; #endif - _PCIFR = __PCIFR; + dwrite(_PCIFR) = __PCIFR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2195,7 +2215,7 @@ inline void _ATmega_resetperipherals() { __TIMER_8bit._TCNTn = 0; __TIMER_8bit._OCRnA = 0; __TIMER_8bit._OCRnB = 0; - TIMER0 = __TIMER_8bit; + dwrite(TIMER0) = __TIMER_8bit; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2204,14 +2224,14 @@ inline void _ATmega_resetperipherals() { __TIMSK0._OCIE0A = false; __TIMSK0._OCIE0B = false; __TIMSK0.reserved1 = 0; - _TIMSK0 = __TIMSK0; + dwrite(_TIMSK0) = __TIMSK0; TIFR0_reg_t __TIFR0; __TIFR0._TOV0 = false; __TIFR0._OCF0A = false; __TIFR0._OCF0B = false; __TIFR0.reserved1 = 0; - _TIFR0 = __TIFR0; + dwrite(_TIFR0) = __TIFR0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2241,14 +2261,14 @@ inline void _ATmega_resetperipherals() { TIMER._OCRnC = 0; #endif TIMER._ICRn = 0; - TIMER1 = TIMER; + dwrite(TIMER1) = TIMER; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - TIMER3 = TIMER; + dwrite(TIMER3) = TIMER; #endif #if defined(__AVR_TRM01__) - TIMER4 = TIMER; - TIMER5 = TIMER; + dwrite(TIMER4) = TIMER; + dwrite(TIMER5) = TIMER; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2262,7 +2282,7 @@ inline void _ATmega_resetperipherals() { __TIMSK1.reserved1 = 0; __TIMSK1._ICIE1 = false; __TIMSK1.reserved2 = 0; - _TIMSK1 = __TIMSK1; + dwrite(_TIMSK1) = __TIMSK1; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -2276,7 +2296,7 @@ inline void _ATmega_resetperipherals() { __TIMSK3.reserved1 = 0; __TIMSK3._ICIE3 = false; __TIMSK3.reserved2 = 0; - _TIMSK3 = __TIMSK3; + dwrite(_TIMSK3) = __TIMSK3; #endif #if defined(__AVR_TRM01__) @@ -2288,7 +2308,7 @@ inline void _ATmega_resetperipherals() { __TIMSK4.reserved1 = false; __TIMSK4._ICIE4 = false; __TIMSK4.reserved2 = false; - _TIMSK4 = __TIMSK4; + dwrite(_TIMSK4) = __TIMSK4; TIMSK5_reg_t __TIMSK5; __TIMSK5._TOIE5 = false; @@ -2298,7 +2318,7 @@ inline void _ATmega_resetperipherals() { __TIMSK5.reserved1 = 0; __TIMSK5._ICIE5 = false; __TIMSK5.reserved2 = 0; - _TIMSK5 = __TIMSK5; + dwrite(_TIMSK5) = __TIMSK5; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2312,7 +2332,7 @@ inline void _ATmega_resetperipherals() { __TIFR1.reserved1 = 0; __TIFR1._ICF1 = false; __TIFR1.reserved2 = 0; - _TIFR1 = __TIFR1; + dwrite(_TIFR1) = __TIFR1; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -2326,7 +2346,7 @@ inline void _ATmega_resetperipherals() { __TIFR3.reserved1 = 0; __TIFR3._ICF3 = false; __TIFR3.reserved2 = 0; - _TIFR3 = __TIFR3; + dwrite(_TIFR3) = __TIFR3; #endif #if defined(__AVR_TRM01__) @@ -2338,7 +2358,7 @@ inline void _ATmega_resetperipherals() { __TIFR4.reserved1 = 0; __TIFR4._ICF4 = false; __TIFR4.reserved2 = 0; - _TIFR4 = __TIFR4; + dwrite(_TIFR4) = __TIFR4; TIFR5_reg_t __TIFR5; __TIFR5._TOV5 = false; @@ -2348,11 +2368,11 @@ inline void _ATmega_resetperipherals() { __TIFR5.reserved1 = 0; __TIFR5._ICF5 = false; __TIFR5.reserved2 = 0; - _TIFR5 = __TIFR5; + dwrite(_TIFR5) = __TIFR5; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _TIMER2 = __TIMER_8bit; + dwrite(_TIMER2) = __TIMER_8bit; #endif #if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2365,7 +2385,7 @@ inline void _ATmega_resetperipherals() { __ASSR._AS2 = false; __ASSR._EXCLK = false; __ASSR.reserved1 = 0; - _ASSR = __ASSR; + dwrite(_ASSR) = __ASSR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2374,14 +2394,14 @@ inline void _ATmega_resetperipherals() { __TIMSK2._OCIE2A = false; __TIMSK2._OCIE2B = false; __TIMSK2.reserved1 = 0; - _TIMSK2 = __TIMSK2; + dwrite(_TIMSK2) = __TIMSK2; TIFR2_reg_t __TIFR2; __TIFR2._TOV2 = false; __TIFR2._OCF2A = false; __TIFR2._OCF2B = false; __TIFR2.reserved1 = 0; - _TIFR2 = __TIFR2; + dwrite(_TIFR2) = __TIFR2; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2393,14 +2413,14 @@ inline void _ATmega_resetperipherals() { __SPCR._DORD = 0; __SPCR._SPE = false; __SPCR._SPIE = false; - _SPCR = __SPCR; + dwrite(_SPCR) = __SPCR; SPSR_reg_t __SPSR; __SPSR._SPI2X = false; __SPSR.reserved1 = 0; __SPSR._WCOL = false; __SPSR._SPIF = false; - _SPSR = __SPSR; + dwrite(_SPSR) = __SPSR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2433,18 +2453,18 @@ inline void _ATmega_resetperipherals() { USART._UBRRn.reserved1 = 0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - USART0 = USART; + dwrite(USART0) = USART; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - USART1 = USART; + dwrite(USART1) = USART; #endif #if defined(__AVR_TRM01__) - USART2 = USART; - USART3 = USART; + dwrite(USART2) = USART; + dwrite(USART3) = USART; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _TWBR = 0; + dwrite(_TWBR) = 0; TWCR_reg_t __TWCR; __TWCR._TWIE = false; @@ -2455,7 +2475,7 @@ inline void _ATmega_resetperipherals() { __TWCR._TWSTA = false; __TWCR._TWEA = false; __TWCR._TWINT = false; - _TWCR = __TWCR; + dwrite(_TWCR) = __TWCR; TWSR_reg_t __TWSR; __TWSR._TWPS0 = false; @@ -2466,19 +2486,19 @@ inline void _ATmega_resetperipherals() { __TWSR._TWS5 = 1; __TWSR._TWS6 = 1; __TWSR._TWS7 = 1; - _TWSR = __TWSR; + dwrite(_TWSR) = __TWSR; - _TWDR = 0xFF; + dwrite(_TWDR) = 0xFF; TWAR_reg_t __TWAR; __TWAR._TWGCE = false; __TWAR._TWA = 0x7F; - _TWAR = __TWAR; + dwrite(_TWAR) = __TWAR; TWAMR_reg_t __TWAMR; __TWAMR.reserved1 = false; __TWAMR._TWAM = 0; - _TWAMR = __TWAMR; + dwrite(_TWAMR) = __TWAMR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2490,7 +2510,7 @@ inline void _ATmega_resetperipherals() { __ADCSRB.reserved1 = 0; __ADCSRB._ACME = false; __ADCSRB.reserved2 = 0; - _ADCSRB = __ADCSRB; + dwrite(_ADCSRB) = __ADCSRB; ACSR_reg_t __ACSR; __ACSR._ACIS = 0; @@ -2500,7 +2520,7 @@ inline void _ATmega_resetperipherals() { __ACSR._ACO = false; __ACSR._ACBG = false; __ACSR._ACD = false; - _ACSR = __ACSR; + dwrite(_ACSR) = __ACSR; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2508,7 +2528,7 @@ inline void _ATmega_resetperipherals() { __DIDR1._AIN0D = false; __DIDR1._AIN1D = false; __DIDR1.reserved1 = false; - _DIDR1 = __DIDR1; + dwrite(_DIDR1) = __DIDR1; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2525,7 +2545,7 @@ inline void _ATmega_resetperipherals() { __ADMUX._ADLAR = 0; __ADMUX._REFS0 = 0; __ADMUX._REFS1 = 0; - _ADMUX = __ADMUX; + dwrite(_ADMUX) = __ADMUX; ADCSRA_reg_t __ADCSRA; __ADCSRA._ADPS = 0; @@ -2534,9 +2554,9 @@ inline void _ATmega_resetperipherals() { __ADCSRA._ADATE = false; __ADCSRA._ADSC = false; __ADCSRA._ADEN = false; - _ADCSRA = __ADCSRA; + dwrite(_ADCSRA) = __ADCSRA; - _ADC = 0; + dwrite(_ADC) = 0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2571,7 +2591,7 @@ inline void _ATmega_resetperipherals() { __SPMCSR._SPMIE = false; #endif #endif - _SPMCSR = __SPMCSR; + dwrite(_SPMCSR) = __SPMCSR; #endif // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) @@ -3070,6 +3090,10 @@ inline ATmegaPinInfo _ATmega_getPinInfo(uint8_t pin) { inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { ATmegaPinInfo info = _ATmega_getPinInfo(pin); + // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that + // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should + // add power-reduction awareness to this logic! + pin_dev_state_t state; #if defined(__AVR_TRM01__) @@ -4373,14 +4397,14 @@ struct _ATmega_lfuse { uint8_t _CKDIV8 : 1; }; -#ifndef AVR_LFUSE_VALUE -#define AVR_LFUSE_VALUE 0xFF +#ifndef AVR_DEFAULT_LFUSE_VALUE +#define AVR_DEFAULT_LFUSE_VALUE 0xFF #endif -#ifndef AVR_HFUSE_VALUE -#define AVR_HFUSE_VALUE 0x99 +#ifndef AVR_DEFAULT_HFUSE_VALUE +#define AVR_DEFAULT_HFUSE_VALUE 0x99 #endif -#ifndef AVR_LFUSE_VALUE -#define AVR_LFUSE_VALUE 0x62 +#ifndef AVR_DEFAULT_LFUSE_VALUE +#define AVR_DEFAULT_LFUSE_VALUE 0x62 #endif #elif defined(__AVR_TRM03__) @@ -4390,8 +4414,8 @@ struct _ATmega_efuse { uint8_t reserved1 : 7; }; -#ifndef AVR_EFUSE_VALUE -#define AVR_EFUSE_VALUE 0xFF +#ifndef AVR_DEFAULT_EFUSE_VALUE +#define AVR_DEFAULT_EFUSE_VALUE 0xFF #endif #elif defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) @@ -4401,8 +4425,8 @@ struct _ATmega_efuse { uint8_t reserved1 : 5; }; -#ifndef AVR_EFUSE_VALUE -#define AVR_EFUSE_VALUE 0xF9 +#ifndef AVR_DEFAULT_EFUSE_VALUE +#define AVR_DEFAULT_EFUSE_VALUE 0xF9 #endif #elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) @@ -4411,8 +4435,8 @@ struct _ATmega_efuse { uint8_t reserved1 : 5; }; -#ifndef AVR_EFUSE_VALUE -#define AVR_EFUSE_VALUE 0xFF +#ifndef AVR_DEFAULT_EFUSE_VALUE +#define AVR_DEFAULT_EFUSE_VALUE 0xFF #endif #endif @@ -4427,8 +4451,8 @@ struct _ATmega_hfuse { uint8_t _RSTDISBL : 1; }; -#ifndef AVR_HFUSE_VALUE -#define AVR_HFUSE_VALUE 0xCF +#ifndef AVR_DEFAULT_HFUSE_VALUE +#define AVR_DEFAULT_HFUSE_VALUE 0xCF #endif #elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) @@ -4442,8 +4466,8 @@ struct _ATmega_hfuse { uint8_t _RSTDISBL : 1; }; -#ifndef AVR_HFUSE_VALUE -#define AVR_HFUSE_VALUE 0xC9 +#ifndef AVR_DEFAULT_HFUSE_VALUE +#define AVR_DEFAULT_HFUSE_VALUE 0xC9 #endif #endif @@ -4456,8 +4480,8 @@ struct _ATmega_lfuse { uint8_t _CKDIV8 : 1; }; -#ifndef AVR_LFUSE_VALUE -#define AVR_LFUSE_VALUE 0xC9 +#ifndef AVR_DEFAULT_LFUSE_VALUE +#define AVR_DEFAULT_LFUSE_VALUE 0xC9 #endif #elif defined(__AVR_TRM04__) @@ -4486,14 +4510,14 @@ struct _ATmega_lfuse { }; // Default values if not already defined. -#ifndef AVR_EFUSE_VALUE -#define AVR_EFUSE_VALUE 0xF3 +#ifndef AVR_DEFAULT_EFUSE_VALUE +#define AVR_DEFAULT_EFUSE_VALUE 0xF3 #endif -#ifndef AVR_HFUSE_VALUE -#define AVR_HFUSE_VALUE 0x99 +#ifndef AVR_DEFAULT_HFUSE_VALUE +#define AVR_DEFAULT_HFUSE_VALUE 0x99 #endif -#ifndef AVR_LFUSE_VALUE -#define AVR_LFUSE_VALUE 0x62 +#ifndef AVR_DEFAULT_LFUSE_VALUE +#define AVR_DEFAULT_LFUSE_VALUE 0x62 #endif #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 057de368501f..56a78d5f1709 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1743,13 +1743,13 @@ void MarlinUI::init() { #if LCD_WITH_BLINK && DISABLED(HAS_GRAPHICAL_TFT) typedef void (*PrintProgress_t)(); void MarlinUI::rotate_progress() { // Renew and redraw all enabled progress strings - const PrintProgress_t progFunc[] = { + static const PrintProgress_t progFunc[] = { OPTITEM(SHOW_PROGRESS_PERCENT, drawPercent) OPTITEM(SHOW_ELAPSED_TIME, drawElapsed) OPTITEM(SHOW_REMAINING_TIME, drawRemain) OPTITEM(SHOW_INTERACTION_TIME, drawInter) }; - if constexpr (COUNT(progFunc) > 0) { + if /* constexpr */ (COUNT(progFunc) > 0) { static bool prev_blink; static uint8_t i; if (prev_blink != get_blink()) { diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index cd4d527500da..796138a26b4a 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -285,7 +285,6 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi spiInit(spiRate_, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN, -1); // Must supply min of 74 clock cycles with CS high. - // TODO: can we just use spiWriteRepeat??? spiWriteRepeat(0xFF, 10); hal.watchdog_refresh(); // In case init takes too long From 0787327a9e3e3749eeb6db7016a6f49c1a8fdd1b Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 8 Dec 2022 21:55:45 +0100 Subject: [PATCH 31/83] - converted the RAMPS AVR pin header files to pin names instead of internal numbers --- Marlin/src/pins/ramps/pins_AZTEEG_X3.h | 31 +- Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h | 11 +- Marlin/src/pins/ramps/pins_BIQU_KFB_2.h | 3 +- Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 45 ++- Marlin/src/pins/ramps/pins_COPYMASTER_3D.h | 10 +- Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 12 +- .../src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h | 71 ++-- Marlin/src/pins/ramps/pins_FELIX2.h | 9 +- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 125 +++--- Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h | 21 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 119 +++--- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 127 +++--- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 185 ++++----- Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 27 +- Marlin/src/pins/ramps/pins_K8200.h | 1 + Marlin/src/pins/ramps/pins_K8400.h | 11 +- Marlin/src/pins/ramps/pins_K8600.h | 35 +- Marlin/src/pins/ramps/pins_K8800.h | 77 ++-- Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h | 25 +- Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h | 8 +- Marlin/src/pins/ramps/pins_MKS_BASE_10.h | 1 + Marlin/src/pins/ramps/pins_MKS_BASE_14.h | 19 +- Marlin/src/pins/ramps/pins_MKS_BASE_15.h | 1 + Marlin/src/pins/ramps/pins_MKS_BASE_16.h | 3 +- Marlin/src/pins/ramps/pins_MKS_BASE_HEROIC.h | 1 + Marlin/src/pins/ramps/pins_MKS_BASE_common.h | 35 +- Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 5 +- Marlin/src/pins/ramps/pins_MKS_GEN_L.h | 11 +- Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h | 33 +- Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h | 33 +- Marlin/src/pins/ramps/pins_ORTUR_4.h | 65 +-- Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h | 19 +- Marlin/src/pins/ramps/pins_RAMPS.h | 207 +++++----- Marlin/src/pins/ramps/pins_RAMPS_13.h | 1 + Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h | 28 +- Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h | 2 + Marlin/src/pins/ramps/pins_RAMPS_OLD.h | 71 ++-- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 49 +-- Marlin/src/pins/ramps/pins_RAMPS_S_12.h | 133 +++--- Marlin/src/pins/ramps/pins_RIGIDBOARD.h | 53 +-- Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h | 3 +- Marlin/src/pins/ramps/pins_RL200.h | 19 +- Marlin/src/pins/ramps/pins_RUMBA.h | 156 ++++--- Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h | 6 +- Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h | 9 +- Marlin/src/pins/ramps/pins_TANGO.h | 13 +- Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h | 125 +++--- Marlin/src/pins/ramps/pins_TRIGORILLA_13.h | 7 +- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 69 ++-- Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h | 3 +- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 382 +++++++++--------- Marlin/src/pins/ramps/pins_ULTIMAIN_2.h | 97 ++--- Marlin/src/pins/ramps/pins_ULTIMAKER.h | 121 +++--- Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h | 165 ++++---- Marlin/src/pins/ramps/pins_VORON.h | 11 +- Marlin/src/pins/ramps/pins_ZRIB_V20.h | 27 +- Marlin/src/pins/ramps/pins_ZRIB_V52.h | 17 +- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 195 ++++----- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 131 +++--- 59 files changed, 1671 insertions(+), 1608 deletions(-) diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index 31adea42709d..7a111f41ef6a 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -23,6 +23,7 @@ /** * AZTEEG_X3 Arduino Mega with RAMPS v1.4 pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -33,15 +34,15 @@ #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) - #define CASE_LIGHT_PIN 6 // Define before RAMPS pins include + #define CASE_LIGHT_PIN PinH3 // Define before RAMPS pins include #endif #define BOARD_INFO_NAME "Azteeg X3" // // Servos // -#define SERVO0_PIN 44 // SERVO1 port -#define SERVO1_PIN 55 // SERVO2 port +#define SERVO0_PIN PinL5 // SERVO1 port +#define SERVO1_PIN PinF1 // SERVO2 port #include "pins_RAMPS_13.h" // ... RAMPS @@ -56,17 +57,17 @@ #undef DOGLCD_A0 #undef DOGLCD_CS #undef BTN_ENC - #define DOGLCD_A0 31 - #define DOGLCD_CS 32 - #define BTN_ENC 12 + #define DOGLCD_A0 PinC6 + #define DOGLCD_CS PinC5 + #define BTN_ENC PinB6 - #define STAT_LED_RED_PIN 64 - #define STAT_LED_BLUE_PIN 63 + #define STAT_LED_RED_PIN PinK2 + #define STAT_LED_BLUE_PIN PinK1 #else - #define STAT_LED_RED_PIN 6 - #define STAT_LED_BLUE_PIN 11 + #define STAT_LED_RED_PIN PinH3 + #define STAT_LED_BLUE_PIN PinB5 #endif @@ -87,11 +88,11 @@ #if HAS_CUTTER #undef SDA // use EXP3 header #undef SCL - #if SERVO0_PIN == 7 + #if SERVO0_PIN == PinH4 #undef SERVO0_PIN - #define SERVO0_PIN 11 + #define SERVO0_PIN PinB5 #endif - #define SPINDLE_LASER_PWM_PIN 7 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 20 // Pullup! - #define SPINDLE_DIR_PIN 21 + #define SPINDLE_LASER_PWM_PIN PinH4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinD1 // Pullup! + #define SPINDLE_DIR_PIN PinD0 #endif diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index fa622ffb15dc..8593fe5a82cc 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -23,6 +23,7 @@ /** * BAM&DICE Due (Arduino Mega) pin assignments + * ATmega2560, ATmega1280 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -34,14 +35,14 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 66 // Pullup or pulldown! -#define SPINDLE_DIR_PIN 67 -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinK4 // Pullup or pulldown! +#define SPINDLE_DIR_PIN PinK5 +#define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM // // Temperature Sensors // -#define TEMP_0_PIN 9 // Analog Input -#define TEMP_1_PIN 11 // Analog Input +#define TEMP_0_PIN PinH6 // Analog Input +#define TEMP_1_PIN PinB5 // Analog Input #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h index 58a62fb8bc74..8fc4158f1cf7 100644 --- a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h +++ b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h @@ -23,6 +23,7 @@ /** * KFB 2.0 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,6 +36,6 @@ // Heaters / Fans // // Power outputs BEEF or BEFF -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 4a54b85ae0bd..9dcf3a760552 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -23,6 +23,7 @@ /** * bq ZUM Mega 3D board definition + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -33,76 +34,76 @@ // // Limit Switches // -#define X_MAX_PIN 79 +#define X_MAX_PIN PinE6 // This board has headers for Z-min, Z-max and IND_S_5V *but* as the bq team // decided to ship the printer only with the probe and no additional Z-min // endstop and the instruction manual advises the user to connect the probe to // IND_S_5V the option Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN will not work. #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define Z_MIN_PIN 19 // IND_S_5V - #define Z_MAX_PIN 18 // Z-MIN Label + #define Z_MIN_PIN PinD2 // IND_S_5V + #define Z_MAX_PIN PinD3 // Z-MIN Label #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 // IND_S_5V + #define Z_MIN_PROBE_PIN PinD2 // IND_S_5V #endif // // Steppers // -#define Z_ENABLE_PIN 77 +#define Z_ENABLE_PIN PinJ6 -#define DIGIPOTSS_PIN 22 +#define DIGIPOTSS_PIN PinA0 #define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // // Temperature Sensors // -#define TEMP_1_PIN 14 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_1_PIN PinJ1 // Analog Input +#define TEMP_BED_PIN PinJ0 // Analog Input // // Heaters / Fans // -#define MOSFET_A_PIN 9 -#define MOSFET_B_PIN 12 -#define MOSFET_C_PIN 10 -#define MOSFET_D_PIN 7 +#define MOSFET_A_PIN PinH6 +#define MOSFET_B_PIN PinB6 +#define MOSFET_C_PIN PinB4 +#define MOSFET_D_PIN PinH4 // // Auto fans // #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 11 + #define E0_AUTO_FAN_PIN PinB5 #endif #ifndef E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN 6 + #define E1_AUTO_FAN_PIN PinH3 #endif #ifndef E2_AUTO_FAN_PIN - #define E2_AUTO_FAN_PIN 6 + #define E2_AUTO_FAN_PIN PinH3 #endif #ifndef E3_AUTO_FAN_PIN - #define E3_AUTO_FAN_PIN 6 + #define E3_AUTO_FAN_PIN PinH3 #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM -#define SPINDLE_DIR_PIN 42 +#define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM +#define SPINDLE_DIR_PIN PinL7 // // Misc. Functions // -#define PS_ON_PIN 81 // External Power Supply +#define PS_ON_PIN PinD4 // External Power Supply #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif // Alter timing for graphical display @@ -122,5 +123,5 @@ // #if ENABLED(HEPHESTOS2_HEATED_BED_KIT) #undef HEATER_BED_PIN - #define HEATER_BED_PIN 8 + #define HEATER_BED_PIN PinH5 #endif diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h index 020941027aaf..e09a5c6c6b88 100644 --- a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -21,12 +21,14 @@ */ #pragma once +// ATmega2560 + #define BOARD_INFO_NAME "Copymaster 3D RAMPS" -#define Z_STEP_PIN 47 -#define Y_MAX_PIN 14 -#define FIL_RUNOUT_PIN 15 -#define SD_DETECT_PIN 66 +#define Z_STEP_PIN PinL2 +#define Y_MAX_PIN PinJ1 +#define FIL_RUNOUT_PIN PinJ0 +#define SD_DETECT_PIN PinK4 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index e1bd2ec4ed54..2dc7f77fa2ee 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -21,6 +21,8 @@ */ #pragma once +// ATmega2560 + #if HOTENDS > 2 || E_STEPPERS > 2 #error "Dagoma3D F5 supports up to 2 hotends / E steppers." #endif @@ -30,13 +32,13 @@ // // Endstops // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 3 -#define Z_STOP_PIN 15 +#define X_STOP_PIN PinE4 +#define Y_STOP_PIN PinE5 +#define Z_STOP_PIN PinJ0 -#define FIL_RUNOUT_PIN 39 +#define FIL_RUNOUT_PIN PinG2 #if EXTRUDERS > 1 - #define FIL_RUNOUT2_PIN 14 + #define FIL_RUNOUT2_PIN PinJ1 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index 1a4b83f02dce..ad5b9d9dc5c4 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -23,6 +23,7 @@ /** * Wanhao Duplicator i3 Plus pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -33,68 +34,68 @@ // // Limit Switches // -#define X_STOP_PIN 54 // PF0 / A0 -#define Y_STOP_PIN 24 // PA2 / AD2 -#define Z_MIN_PIN 23 // PA1 / AD1 -#define Z_MAX_PIN 25 // PA3 / AD3 -#define SERVO0_PIN 40 // PG1 / !RD +#define X_STOP_PIN PinF0 // PF0 / A0 +#define Y_STOP_PIN PinA2 // PA2 / AD2 +#define Z_MIN_PIN PinA1 // PA1 / AD1 +#define Z_MAX_PIN PinA3 // PA3 / AD3 +#define SERVO0_PIN PinG1 // PG1 / !RD // // Steppers // -#define X_STEP_PIN 61 // PF7 / A7 -#define X_DIR_PIN 62 // PK0 / A8 -#define X_ENABLE_PIN 60 // PF6 / A6 +#define X_STEP_PIN PinF7 // PF7 / A7 +#define X_DIR_PIN PinK0 // PK0 / A8 +#define X_ENABLE_PIN PinF6 // PF6 / A6 -#define Y_STEP_PIN 64 // PK2 / A10 -#define Y_DIR_PIN 65 // PK3 / A11 -#define Y_ENABLE_PIN 63 // PK1 / A9 +#define Y_STEP_PIN PinK2 // PK2 / A10 +#define Y_DIR_PIN PinK3 // PK3 / A11 +#define Y_ENABLE_PIN PinK1 // PK1 / A9 -#define Z_STEP_PIN 67 // PK5 / A13 -#define Z_DIR_PIN 69 // PK7 / A15 -#define Z_ENABLE_PIN 66 // PK4 / A12 -#define Z_MIN_PROBE_PIN 25 // PA3 / AD3 +#define Z_STEP_PIN PinK5 // PK5 / A13 +#define Z_DIR_PIN PinK7 // PK7 / A15 +#define Z_ENABLE_PIN PinK4 // PK4 / A12 +#define Z_MIN_PROBE_PIN PinA3 // PA3 / AD3 -#define E0_STEP_PIN 58 // PF4 / A4 -#define E0_DIR_PIN 59 // PF5 / A5 -#define E0_ENABLE_PIN 57 // PF3 / A3 +#define E0_STEP_PIN PinF4 // PF4 / A4 +#define E0_DIR_PIN PinF5 // PF5 / A5 +#define E0_ENABLE_PIN PinF3 // PF3 / A3 // // Temperature Sensors // -#define TEMP_0_PIN 1 // PF1 / A1 Analog -#define TEMP_BED_PIN 14 // PK6 / A14 Analog +#define TEMP_0_PIN PinE1 // PF1 / A1 Analog (verify this pin) +#define TEMP_BED_PIN PinJ1 // PK6 / A14 Analog // // Heaters / Fans // -#define HEATER_0_PIN 4 // PG5 / PWM4 -#define HEATER_BED_PIN 3 // PE5 / PWM3 +#define HEATER_0_PIN PinG5 // PG5 / PWM4 +#define HEATER_BED_PIN PinE5 // PE5 / PWM3 -#define FAN_PIN 5 // PE3 / PWM5 +#define FAN_PIN PinE3 // PE3 / PWM5 // // Misc. Functions // -#define SDSS 53 // PB0 / SS -#define LED_PIN 13 // PB7 / PWM13 +#define SDSS PinB0 // PB0 / SS +#define LED_PIN PinB7 // PB7 / PWM13 -#define SD_MISO_PIN 50 // PB3 -#define SD_MOSI_PIN 51 // PB2 -#define SD_SCK_PIN 52 // PB1 +#define SD_MISO_PIN PinB3 // PB3 +#define SD_MOSI_PIN PinB2 // PB2 +#define SD_SCK_PIN PinB1 // PB1 // // LCDs and Controllers // #if HAS_WIRED_LCD #if ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 2 - #define LCD_PINS_ENABLE 36 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 34 - #define LCD_PINS_D6 35 - #define LCD_PINS_D7 32 - #define ADC_KEYPAD_PIN 12 // Analog + #define LCD_PINS_RS PinE4 + #define LCD_PINS_ENABLE PinC1 + #define LCD_PINS_D4 PinC0 + #define LCD_PINS_D5 PinC3 + #define LCD_PINS_D6 PinC2 + #define LCD_PINS_D7 PinC5 + #define ADC_KEYPAD_PIN PinB6 // Analog #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FELIX2.h b/Marlin/src/pins/ramps/pins_FELIX2.h index 3e7849d71f23..a265955eb0fc 100644 --- a/Marlin/src/pins/ramps/pins_FELIX2.h +++ b/Marlin/src/pins/ramps/pins_FELIX2.h @@ -23,6 +23,7 @@ /** * FELIXprinters v2.0/3.0 (RAMPS v1.4) pin assignments + * ATmega2560, ATmega1280 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,23 +36,23 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 #include "pins_RAMPS.h" // // Misc. Functions // -#define SDPOWER_PIN 1 +#define SDPOWER_PIN PinE1 -#define PS_ON_PIN 12 +#define PS_ON_PIN PinB6 // // LCD / Controller // #if HAS_WIRED_LCD && IS_NEWPANEL - #define SD_DETECT_PIN 6 + #define SD_DETECT_PIN PinH3 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index a6791ff7c8b5..a6670f4c8182 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -23,6 +23,7 @@ /** * Formbot Raptor pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -42,122 +43,122 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 6 -#define SERVO2_PIN 5 +#define SERVO0_PIN PinB5 +#define SERVO1_PIN PinH3 +#define SERVO2_PIN PinE3 // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PiNF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN PinL0 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN PinG1 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN PinL7 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN PinL5 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 43 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN PinL7 +#define E2_DIR_PIN PinL6 +#define E2_ENABLE_PIN PinL5 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinH5 #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN PinH6 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 57 + #define FIL_RUNOUT_PIN PinF3 #endif #if !HAS_FILAMENT_SENSOR - #define FAN1_PIN 4 + #define FAN1_PIN PinG5 #endif // // Misc. Functions // #ifndef SDSS - #define SDSS 53 + #define SDSS PinB0 #endif -#define LED_PIN 13 -#define LED4_PIN 5 +#define LED_PIN PinB7 +#define LED4_PIN PinE3 // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN PinE3 // Analog Input #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN PinB6 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 5 + #define CASE_LIGHT_PIN PinE3 #endif // @@ -166,16 +167,16 @@ // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // #if IS_RRD_SC - #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define BEEPER_PIN PinC0 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 + #define KILL_PIN PinG0 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h index 4fb10bfd356b..1c5b8e2d9d4e 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR2.h @@ -23,15 +23,16 @@ /** * Formbot Raptor 2 pin assignments + * ATmega2560 */ #define BOARD_INFO_NAME "Formbot Raptor2" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME -#define FAN_PIN 6 +#define FAN_PIN PinH3 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 22 + #define FIL_RUNOUT_PIN PinA0 #endif #include "pins_FORMBOT_RAPTOR.h" @@ -43,21 +44,21 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Try to use servo connector first - #define SPINDLE_LASER_ENA_PIN 6 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_LASER_ENA_PIN PinH3 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinG5 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #elif !GREEDY_PANEL // Try to use AUX2 - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #endif #endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) #if NUM_SERVOS <= 1 // Try to use servo connector first - #define CASE_LIGHT_PIN 6 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif !GREEDY_PANEL // Try to use AUX2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 17d3abc71f37..2a3f04195967 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -23,6 +23,7 @@ /** * Formbot pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -38,7 +39,7 @@ // // Servos // -#define SERVO0_PIN 11 +#define SERVO0_PIN PinB5 #define SERVO1_PIN -1 // was 6 #define SERVO2_PIN -1 // was 5 #define SERVO3_PIN -1 @@ -46,112 +47,112 @@ // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN PinL0 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN PinG1 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN PinL7 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN PinL5 #endif -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 43 -#define E2_ENABLE_PIN 44 +#define E2_STEP_PIN PinL7 +#define E2_DIR_PIN PinL6 +#define E2_ENABLE_PIN PinL5 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 3 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinE5 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 58 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinF4 -#define FAN_PIN 9 +#define FAN_PIN PinH6 #if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN PinG5 //#define FIL_RUNOUT2_PIN -1 #else // Though defined as a fan pin, it is utilized as a dedicated laser pin by Formbot. - #define FAN1_PIN 4 + #define FAN1_PIN PinG5 #endif // // Misc. Functions // -#define SDSS 53 +#define SDSS PinB0 #ifndef LED_PIN - #define LED_PIN 13 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED + #define LED_PIN PinB7 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED #endif // is a good place to get a signal to control the Max7219 LED Matrix. // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN PinE3 // Analog Input #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN PinB6 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 8 + #define CASE_LIGHT_PIN PinH5 #endif // @@ -161,24 +162,24 @@ // #if IS_RRD_SC #ifndef BEEPER_PIN - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 #endif - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 // Allow MAX7219 to steal the KILL pin #if !defined(KILL_PIN) && MAX7219_CLK_PIN != 41 && MAX7219_DIN_PIN != 41 && MAX7219_LOAD_PIN != 41 - #define KILL_PIN 41 + #define KILL_PIN PinG0 #endif - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index e23a63994faa..5936b50d6f24 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -23,6 +23,7 @@ /** * Formbot pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -38,7 +39,7 @@ // // Servos // -#define SERVO0_PIN 11 +#define SERVO0_PIN PinB5 #define SERVO1_PIN -1 // was 6 #define SERVO2_PIN -1 #define SERVO3_PIN -1 @@ -46,115 +47,115 @@ // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN PinL0 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN PinG1 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN PinL7 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN PinL5 #endif #if HAS_X2_STEPPER - #define X2_STEP_PIN 42 - #define X2_DIR_PIN 43 - #define X2_ENABLE_PIN 44 + #define X2_STEP_PIN PinL7 + #define X2_DIR_PIN PinL6 + #define X2_ENABLE_PIN PinL5 #else - #define E2_STEP_PIN 42 - #define E2_DIR_PIN 43 - #define E2_ENABLE_PIN 44 + #define E2_STEP_PIN PinL7 + #define E2_DIR_PIN PinL6 + #define E2_ENABLE_PIN PinL5 #endif // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 9 -#define FAN1_PIN 12 +#define FAN_PIN PinH6 +#define FAN1_PIN PinB6 -#define FIL_RUNOUT_PIN 22 -#define FIL_RUNOUT2_PIN 21 +#define FIL_RUNOUT_PIN PinA0 +#define FIL_RUNOUT2_PIN PinD0 // // Misc. Functions // -#define SDSS 53 +#define SDSS PinB0 #ifndef LED_PIN - #define LED_PIN 13 + #define LED_PIN PinB7 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 5 + #define CASE_LIGHT_PIN PinE3 #endif #define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 4 // Pullup! +#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // Analog Input +#define FILWIDTH_PIN PinE3 // Analog Input // // LCD / Controller @@ -162,21 +163,21 @@ // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // #if IS_RRD_SC - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 #ifndef KILL_PIN - #define KILL_PIN 41 + #define KILL_PIN PinG0 #endif #ifndef BEEPER_PIN - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index b8de260909b6..0f8bb4fa7cdc 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -23,6 +23,7 @@ // // FYSETC F6 1.3 (and 1.4) pin assignments +// ATmega2560 // #if NOT_TARGET(__AVR_ATmega2560__) @@ -33,27 +34,27 @@ #define BOARD_INFO_NAME "FYSETC F6 1.3" #endif -#define RESET_PIN 30 -#define SPI_FLASH_CS_PIN 83 +#define RESET_PIN PinC7 +#define SPI_FLASH_CS_PIN PinD6 // // Servos // -#define SERVO0_PIN 13 -#define SERVO1_PIN 11 // (PS_ON_PIN) -#define SERVO2_PIN 10 // (FIL_RUNOUT_PIN) -#define SERVO3_PIN 4 // (RGB_LED_G_PIN) +#define SERVO0_PIN PinB7 +#define SERVO1_PIN PinB5 // (PS_ON_PIN) +#define SERVO2_PIN PinB4 // (FIL_RUNOUT_PIN) +#define SERVO3_PIN PinG5 // (RGB_LED_G_PIN) // // Limit Switches // -#define X_MIN_PIN 63 -#define X_MAX_PIN 64 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 12 +#define X_MIN_PIN PinK1 +#define X_MAX_PIN PinK2 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinB6 #ifndef Z_MAX_PIN - #define Z_MAX_PIN 9 + #define Z_MAX_PIN PinH6 #endif #ifndef FIL_RUNOUT_PIN @@ -64,52 +65,52 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 9 // Servos pin + #define Z_MIN_PROBE_PIN PinH6 // Servos pin #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN 70 + #define X_CS_PIN PinG4 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN 39 + #define Y_CS_PIN PinG2 #endif -#define Z_STEP_PIN 43 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 58 +#define Z_STEP_PIN PinL6 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinF4 #ifndef Z_CS_PIN - #define Z_CS_PIN 74 + #define Z_CS_PIN PinJ7 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN 47 + #define E0_CS_PIN PinL2 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN 32 + #define E1_CS_PIN PinC5 #endif -#define E2_STEP_PIN 59 -#define E2_DIR_PIN 57 -#define E2_ENABLE_PIN 40 +#define E2_STEP_PIN PinF5 +#define E2_DIR_PIN PinF3 +#define E2_ENABLE_PIN PinG1 #ifndef E2_CS_PIN - #define E2_CS_PIN 42 + #define E2_CS_PIN PinL7 #endif // @@ -125,37 +126,37 @@ * At the moment, F6 rx pins are not pc interrupt pins */ #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 72 + #define X_SERIAL_TX_PIN PinJ2 #endif #ifndef X_SERIAL_RX_PIN #define X_SERIAL_RX_PIN -1 // 71 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 75 + #define Y_SERIAL_TX_PIN PinJ4 #endif #ifndef Y_SERIAL_RX_PIN #define Y_SERIAL_RX_PIN -1 // 73 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 79 + #define Z_SERIAL_TX_PIN PinE6 #endif #ifndef Z_SERIAL_RX_PIN #define Z_SERIAL_RX_PIN -1 // 78 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 77 + #define E0_SERIAL_TX_PIN PinJ6 #endif #ifndef E0_SERIAL_RX_PIN #define E0_SERIAL_RX_PIN -1 // 76 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN 81 + #define E1_SERIAL_TX_PIN PinD4 #endif #ifndef E1_SERIAL_RX_PIN #define E1_SERIAL_RX_PIN -1 // 80 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN 82 + #define E2_SERIAL_TX_PIN PinD5 #endif #ifndef E2_SERIAL_RX_PIN #define E2_SERIAL_RX_PIN -1 // 22 @@ -165,33 +166,33 @@ // // Temperature Sensors // -#define TEMP_0_PIN 12 // Analog Input -#define TEMP_1_PIN 13 // Analog Input -#define TEMP_2_PIN 14 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_0_PIN PinB6 // Analog Input +#define TEMP_1_PIN PinB7 // Analog Input +#define TEMP_2_PIN PinJ1 // Analog Input +#define TEMP_BED_PIN PinJ0 // Analog Input #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 9 // Analog Input on X+ endstop + #define FILWIDTH_PIN PinH6 // Analog Input on X+ endstop #endif // // Heaters / Fans // -#define HEATER_0_PIN 5 -#define HEATER_1_PIN 6 -#define HEATER_2_PIN 7 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinE3 +#define HEATER_1_PIN PinH3 +#define HEATER_2_PIN PinH4 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 44 -#define FAN1_PIN 45 -#define FAN2_PIN 46 +#define FAN_PIN PinL5 +#define FAN1_PIN PinL4 +#define FAN2_PIN PinL3 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define KILL_PIN 41 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define KILL_PIN PinG0 #ifndef PS_ON_PIN #define PS_ON_PIN SERVO1_PIN @@ -211,36 +212,36 @@ // // LCDs and Controllers // -#define SD_DETECT_PIN 49 +#define SD_DETECT_PIN PinL0 #if ENABLED(FYSETC_242_OLED_12864) - #define BTN_EN1 37 - #define BTN_EN2 29 - #define BTN_ENC 35 - #define BEEPER_PIN 31 - - #define LCD_PINS_DC 25 - #define LCD_PINS_RS 33 - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 23 - #define DOGLCD_SCK 17 + #define BTN_EN1 PinC0 + #define BTN_EN2 PinA7 + #define BTN_ENC PinC2 + #define BEEPER_PIN PinC6 + + #define LCD_PINS_DC PinA3 + #define LCD_PINS_RS PinC4 + #define DOGLCD_CS PinH1 + #define DOGLCD_MOSI PinA1 + #define DOGLCD_SCK PinH0 #define DOGLCD_A0 LCD_PINS_DC #undef KILL_PIN - #define NEOPIXEL_PIN 27 + #define NEOPIXEL_PIN PinA5 #else - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 #if ENABLED(FYSETC_MINI_12864) // // See https://wiki.fysetc.com/Mini12864_Panel/ // - #define DOGLCD_A0 16 - #define DOGLCD_CS 17 + #define DOGLCD_A0 PinH1 + #define DOGLCD_CS PinH0 #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN 27 + #define LCD_BACKLIGHT_PIN PinA5 #endif #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. @@ -248,30 +249,30 @@ #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 25 + #define RGB_LED_R_PIN PinA3 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 27 + #define RGB_LED_G_PIN PinA5 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 29 + #define RGB_LED_B_PIN PinA7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 25 + #define NEOPIXEL_PIN PinA3 #endif #elif HAS_MARLINUI_U8GLIB || HAS_MARLINUI_HD44780 - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS 25 - #define DOGLCD_A0 27 + #define DOGLCD_CS PinA3 + #define DOGLCD_A0 PinA5 #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -281,20 +282,20 @@ #endif #if IS_NEWPANEL - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 #endif #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 3 + #define RGB_LED_R_PIN PinE5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 4 + #define RGB_LED_G_PIN PinG5 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 9 + #define RGB_LED_B_PIN PinH6 #endif #ifndef RGB_LED_W_PIN #define RGB_LED_W_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index 1fc24154b733..fb20bc9e402b 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -23,33 +23,34 @@ // // FYSETC F6 v1.4 pin assignments +// ATmega2560 // #define BOARD_INFO_NAME "FYSETC F6 1.4" -#define Z_MAX_PIN 2 +#define Z_MAX_PIN PinE4 #if HAS_TMC_UART /** * TMC2208/TMC2209 stepper drivers */ - #define X_SERIAL_TX_PIN 71 - #define X_SERIAL_RX_PIN 72 + #define X_SERIAL_TX_PIN PinG3 + #define X_SERIAL_RX_PIN PinJ2 - #define Y_SERIAL_TX_PIN 78 - #define Y_SERIAL_RX_PIN 73 + #define Y_SERIAL_TX_PIN PinE2 + #define Y_SERIAL_RX_PIN PinJ3 - #define Z_SERIAL_TX_PIN 79 - #define Z_SERIAL_RX_PIN 75 + #define Z_SERIAL_TX_PIN PinE6 + #define Z_SERIAL_RX_PIN PinJ4 - #define E0_SERIAL_TX_PIN 81 - #define E0_SERIAL_RX_PIN 77 + #define E0_SERIAL_TX_PIN PinD4 + #define E0_SERIAL_RX_PIN PinJ6 - #define E1_SERIAL_TX_PIN 80 - #define E1_SERIAL_RX_PIN 76 + #define E1_SERIAL_TX_PIN PinE7 + #define E1_SERIAL_RX_PIN PinJ5 - #define E2_SERIAL_TX_PIN 82 - #define E2_SERIAL_RX_PIN 62 + #define E2_SERIAL_TX_PIN PinD5 + #define E2_SERIAL_RX_PIN PinK0 #endif #include "pins_FYSETC_F6_13.h" diff --git a/Marlin/src/pins/ramps/pins_K8200.h b/Marlin/src/pins/ramps/pins_K8200.h index 395e1ccca50e..b15551982dbf 100644 --- a/Marlin/src/pins/ramps/pins_K8200.h +++ b/Marlin/src/pins/ramps/pins_K8200.h @@ -24,6 +24,7 @@ /** * K8200 Arduino Mega with RAMPS v1.3 pin assignments * Identical to 3DRAG + * ATmega2560 */ #define BOARD_INFO_NAME "Velleman K8200" diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index 36c438aca2de..f59e25330198 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -24,6 +24,7 @@ /** * Velleman K8400 (Vertex) * 3DRAG clone + * ATmega2560, ATmega1280 * * K8400 has some minor differences over a normal 3Drag: * - No X/Y max endstops @@ -39,16 +40,16 @@ // Steppers // #if HAS_CUTTER - #define Z_STEP_PIN 32 + #define Z_STEP_PIN PinC5 #endif -#define E1_STEP_PIN 32 +#define E1_STEP_PIN PinC5 // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinJ1 #include "pins_3DRAG.h" // ... RAMPS @@ -56,7 +57,7 @@ // Heaters / Fans // #undef HEATER_1_PIN -#define HEATER_1_PIN 11 +#define HEATER_1_PIN PinB5 // // Misc. Functions diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index a9613e8eb27f..a93602ddd4c0 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -23,6 +23,7 @@ /** * VERTEX NANO Arduino Mega with RAMPS EFB v1.4 pin assignments. + * ATmega2560, ATmega1280 */ #if HAS_MULTI_HOTEND @@ -35,26 +36,26 @@ // // Limit Switches // -#define X_MIN_PIN 3 -#define Y_MAX_PIN 14 -#define Z_MAX_PIN 18 +#define X_MIN_PIN PinE5 +#define Y_MAX_PIN PinJ1 +#define Z_MAX_PIN PinD3 #define Z_MIN_PIN -1 // // Steppers // -#define Z_ENABLE_PIN 63 +#define Z_ENABLE_PIN PinK1 // // Heaters / Fans // -#define FAN_PIN 8 +#define FAN_PIN PinH5 // // Misc. Functions // -#define SDSS 25 -#define CASE_LIGHT_PIN 7 +#define SDSS PinA3 +#define CASE_LIGHT_PIN PinH4 // // Other RAMPS pins @@ -78,23 +79,23 @@ #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 35 - #define LCD_PINS_D6 33 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinC0 + #define LCD_PINS_D5 PinC2 + #define LCD_PINS_D6 PinC4 + #define LCD_PINS_D7 PinC6 // Buttons #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC - #define BTN_EN1 17 - #define BTN_EN2 16 - #define BTN_ENC 23 + #define BTN_EN1 PinH0 + #define BTN_EN2 PinH1 + #define BTN_ENC PinA1 #else - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 #endif diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index 17bb59fdc9d0..809d9fb5bb31 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -23,6 +23,7 @@ /** * Velleman K8800 (Vertex) + * ATmega2560, ATmega1280 */ #include "env_validate.h" @@ -33,84 +34,84 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 14 -#define Z_STOP_PIN 66 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinJ1 +#define Z_STOP_PIN PinK4 #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 68 + #define Z_MIN_PROBE_PIN PinK6 #endif -#define FIL_RUNOUT_PIN 69 // PK7 +#define FIL_RUNOUT_PIN PinK7 // PK7 // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 63 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK1 -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 // // Temperature Sensors // -#define TEMP_0_PIN 13 +#define TEMP_0_PIN PinB7 // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define FAN_PIN 8 -#define CONTROLLER_FAN_PIN 9 +#define HEATER_0_PIN PinB4 +#define FAN_PIN PinH5 +#define CONTROLLER_FAN_PIN PinH6 // // Misc. Functions // -#define KILL_PIN 20 // PD1 -#define CASE_LIGHT_PIN 7 +#define KILL_PIN PinD1 // PD1 +#define CASE_LIGHT_PIN PinH4 // // SD Card // -#define SDSS 25 -#define SD_DETECT_PIN 21 // PD0 +#define SDSS PinA3 +#define SD_DETECT_PIN PinD0 // PD0 // // LCD / Controller // -#define BEEPER_PIN 6 +#define BEEPER_PIN PinH3 #if HAS_WIRED_LCD - #define LCD_SDSS 53 + #define LCD_SDSS PinB0 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS PinA7 + #define DOGLCD_A0 PinA5 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 35 - #define LCD_PINS_D6 33 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinC0 + #define LCD_PINS_D5 PinC2 + #define LCD_PINS_D6 PinC4 + #define LCD_PINS_D7 PinC6 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #if IS_NEWPANEL - #define BTN_EN1 17 - #define BTN_EN2 16 - #define BTN_ENC 23 + #define BTN_EN1 PinH0 + #define BTN_EN2 PinH1 + #define BTN_ENC PinA1 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index af1d33c83c60..3d91201a8cc1 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -23,6 +23,7 @@ /** * Longer3D LK1/LK4/LK5 Pro board pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -52,7 +53,7 @@ // Servos // #if !MB(LONGER3D_LK1_PRO) - #define SERVO0_PIN 7 + #define SERVO0_PIN PinH4 #endif #define SERVO1_PIN -1 #define SERVO2_PIN -1 @@ -61,25 +62,25 @@ // // Limit Switches // -#define X_STOP_PIN 3 +#define X_STOP_PIN PinE5 #ifdef CHANGE_Y_LIMIT_PINS - #define Y_STOP_PIN 37 + #define Y_STOP_PIN PinC0 #else - #define Y_MIN_PIN 14 - #define Y_MAX_PIN 15 + #define Y_MIN_PIN PinJ1 + #define Y_MAX_PIN PinJ0 #endif #if !MB(LONGER3D_LK1_PRO) #ifdef CHANGE_Y_LIMIT_PINS - #define Z_STOP_PIN 35 + #define Z_STOP_PIN PinC2 #else - #define Z_MIN_PIN 35 - #define Z_MAX_PIN 37 + #define Z_MIN_PIN PinC2 + #define Z_MAX_PIN PinC0 #endif #else - #define Z_MIN_PIN 11 - #define Z_MAX_PIN 37 + #define Z_MIN_PIN PinB5 + #define Z_MAX_PIN PinC0 #endif #undef CHANGE_Y_LIMIT_PINS @@ -112,8 +113,8 @@ // // Misc. Functions // -#define SD_DETECT_PIN 49 -#define FIL_RUNOUT_PIN 2 +#define SD_DETECT_PIN PinL0 +#define FIL_RUNOUT_PIN PinE4 // // Other RAMPS 1.3 pins diff --git a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h index a42dba874f41..0242eebfae02 100644 --- a/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h +++ b/Marlin/src/pins/ramps/pins_MAKEBOARD_MINI.h @@ -21,13 +21,15 @@ */ #pragma once +// ATmega2560 + #define BOARD_INFO_NAME "MAKEboard Mini" // // Only 3 Limit Switch plugs on Micromake C1 // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 15 -#define Z_STOP_PIN 19 +#define X_STOP_PIN PinE4 +#define Y_STOP_PIN PinJ0 +#define Z_STOP_PIN PinD2 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h index 64efa46c0550..390c30d0cb7d 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h @@ -23,6 +23,7 @@ /** * MKS BASE 1.0 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * ATmega2560 * * Rev B - Override pin definitions for CASE_LIGHT and M3/M4/M5 spindle control */ diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h index 7e2a722cf222..3823ba142af8 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_14.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_14.h @@ -23,6 +23,7 @@ /** * MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,27 +36,27 @@ // // Heaters / Fans // -#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 +#define FAN_PIN PinH6 // PH6 ** Pin18 ** PWM9 // Other Mods -#define SERVO3_PIN 12 // PB6 ** Pin25 ** D12 -#define PS_ON_PIN 2 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM -#define FILWIDTH_PIN 15 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup! -#define FIL_RUNOUT_PIN 19 // Z+ // PD2 ** Pin45 ** USART1_RX +#define SERVO3_PIN PinB6 // PB6 ** Pin25 ** D12 +#define PS_ON_PIN PinE4 // X+ // PE4 ** Pin6 ** PWM2 **MUST BE HARDWARE PWM +#define FILWIDTH_PIN PinJ0 // Y+ // PJ0 ** Pin63 ** USART3_RX **Pin should have a pullup! +#define FIL_RUNOUT_PIN PinD2 // Z+ // PD2 ** Pin45 ** USART1_RX #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 50 + #define RGB_LED_R_PIN PinB3 #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_G_PIN 51 + #define RGB_LED_G_PIN PinB2 #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_B_PIN 52 + #define RGB_LED_B_PIN PinB1 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 11 // PB5 ** Pin24 ** PWM11 + #define CASE_LIGHT_PIN PinB5 // PB5 ** Pin24 ** PWM11 #endif #include "pins_MKS_BASE_common.h" // ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_15.h b/Marlin/src/pins/ramps/pins_MKS_BASE_15.h index 5fedd3f97c8a..1d93ec5cf9bf 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_15.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_15.h @@ -23,6 +23,7 @@ /** * MKS BASE v1.5 with A4982 stepper drivers and digital micro-stepping + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 63e0b51d3cc5..5f81c564d3d8 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -23,6 +23,7 @@ /** * MKS BASE v1.6 with A4982 stepper drivers and digital micro-stepping + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,7 +36,7 @@ // // Servos // -#define SERVO1_PIN 12 // Digital 12 / Pin 25 +#define SERVO1_PIN PinB6 // Digital 12 / Pin 25 // // Omitted RAMPS pins diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_HEROIC.h b/Marlin/src/pins/ramps/pins_MKS_BASE_HEROIC.h index 973f924e7c16..c50f28a40734 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_HEROIC.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_HEROIC.h @@ -23,6 +23,7 @@ /** * MKS BASE with Heroic HR4982 stepper drivers + * ATmega2560 */ #include "pins_MKS_BASE_15.h" // ... MKS_BASE_common ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h index 9047a4bcf0e6..771627c181f5 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_common.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_common.h @@ -23,6 +23,7 @@ /** * MKS BASE – Arduino Mega2560 with RAMPS pin assignments + * ATmega2560 */ #ifndef BOARD_INFO_NAME @@ -34,19 +35,19 @@ // Heaters / Fans // // Power outputs EFBF or EFBE - #define MOSFET_D_PIN 7 + #define MOSFET_D_PIN PinH4 // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #define SPINDLE_LASER_PWM_PIN 2 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 15 // Pullup! - #define SPINDLE_DIR_PIN 19 + #define SPINDLE_LASER_PWM_PIN PinE4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinJ0 // Pullup! + #define SPINDLE_DIR_PIN PinD2 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 2 + #define CASE_LIGHT_PIN PinE4 #endif #endif @@ -55,21 +56,21 @@ // Microstepping pins // #if MKS_BASE_VERSION >= 14 // |===== 1.4 =====|===== 1.5+ =====| - #define X_MS1_PIN 5 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN - #define X_MS2_PIN 6 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN - #define Y_MS1_PIN 59 // PF5 | Pin 92 | A5 | | | - #define Y_MS2_PIN 58 // PF4 | Pin 93 | A4 | | | - #define Z_MS1_PIN 22 // PA0 | Pin 78 | D22 | | | - #define Z_MS2_PIN 39 // PG2 | Pin 70 | D39 | | | + #define X_MS1_PIN PinE3 // PE3 | Pin 5 | PWM5 | | D3 | SERVO2_PIN + #define X_MS2_PIN PinH3 // PH3 | Pin 15 | PWM6 | Pin 14 | D6 | SERVO1_PIN + #define Y_MS1_PIN PinF5 // PF5 | Pin 92 | A5 | | | + #define Y_MS2_PIN PinF4 // PF4 | Pin 93 | A4 | | | + #define Z_MS1_PIN PinA0 // PA0 | Pin 78 | D22 | | | + #define Z_MS2_PIN PinG2 // PG2 | Pin 70 | D39 | | | #if MKS_BASE_VERSION == 14 - #define E0_MS1_PIN 64 // PK2 | Pin 87 | A10 | | | - #define E0_MS2_PIN 63 // PK1 | Pin 88 | A9 | | | + #define E0_MS1_PIN PinK2 // PK2 | Pin 87 | A10 | | | + #define E0_MS2_PIN PinK1 // PK1 | Pin 88 | A9 | | | #else - #define E0_MS1_PIN 63 // PK1 | | | Pin 86 | A9 | - #define E0_MS2_PIN 64 // PK2 | | | Pin 87 | A10 | + #define E0_MS1_PIN PinK1 // PK1 | | | Pin 86 | A9 | + #define E0_MS2_PIN PinK2 // PK2 | | | Pin 87 | A10 | #endif - #define E1_MS1_PIN 57 // PF3 | Pin 94 | A3 | Pin 93 | A3 | - #define E1_MS2_PIN 4 // PG5 | Pin 1 | PWM4 | | D4 | SERVO3_PIN + #define E1_MS1_PIN PinF3 // PF3 | Pin 94 | A3 | Pin 93 | A3 | + #define E1_MS2_PIN PinG5 // PG5 | Pin 1 | PWM4 | | D4 | SERVO3_PIN #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index 7a8c99e3af1c..a3624db8e4d5 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.4 adjusted pin assignments + * ATmega2560, ATmega1280 * * MKS GEN v1.3 (Extruder, Fan, Bed) * MKS GEN v1.3 (Extruder, Extruder, Fan, Bed) @@ -40,7 +41,7 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 // // PSU / SERVO @@ -49,7 +50,7 @@ // #if ENABLED(PSU_CONTROL) #define SERVO3_PIN -1 - #define PS_ON_PIN 4 + #define PS_ON_PIN PinG5 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index ca1f1338164e..28af5d6e7c43 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -23,6 +23,7 @@ /** * MKS GEN L – Arduino Mega2560 with RAMPS v1.4 pin assignments + * ATmega2560, ATmega1280 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,12 +36,12 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 // Hotend, Hotend, Bed + Fan on D9 #if FET_ORDER_EEB - #define MOSFET_B_PIN 7 - #define FAN_PIN 9 + #define MOSFET_B_PIN PinH4 + #define FAN_PIN PinH6 #endif // @@ -49,11 +50,11 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 59 + #define X_CS_PIN PinF5 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 63 + #define Y_CS_PIN PinK1 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h index 0378b166a2d4..57019fb84aec 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h @@ -23,6 +23,7 @@ /** * MKS GEN L V2 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,7 +36,7 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 // // CS Pins wired to avoid conflict with the LCD @@ -43,47 +44,47 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 63 + #define X_CS_PIN PinK1 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 64 + #define Y_CS_PIN PinK2 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN 65 + #define Z_CS_PIN PinK3 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN 66 + #define E0_CS_PIN PinK4 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN 21 + #define E1_CS_PIN PinD0 #endif // TMC2130 Diag Pins (currently just for reference) -#define X_DIAG_PIN 3 -#define Y_DIAG_PIN 14 -#define Z_DIAG_PIN 18 -#define E0_DIAG_PIN 2 -#define E1_DIAG_PIN 15 +#define X_DIAG_PIN PinE5 +#define Y_DIAG_PIN PinJ1 +#define Z_DIAG_PIN PinD3 +#define E0_DIAG_PIN PinE4 +#define E1_DIAG_PIN PinJ0 #ifndef SERVO1_PIN - #define SERVO1_PIN 12 + #define SERVO1_PIN PinB6 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 39 + #define SERVO2_PIN PinG2 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 32 + #define SERVO3_PIN PinC5 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN 20 + #define E1_SERIAL_TX_PIN PinD1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN 21 + #define E1_SERIAL_RX_PIN PinD0 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h index d508cb453f4d..66d10e4d1598 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h @@ -23,6 +23,7 @@ /** * MKS GEN L V2 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * ATmega2560 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -35,7 +36,7 @@ // Heaters / Fans // // Power outputs EFBF or EFBE -#define MOSFET_D_PIN 7 +#define MOSFET_D_PIN PinH4 // // CS Pins wired to avoid conflict with the LCD @@ -43,43 +44,43 @@ // #ifndef X_CS_PIN - #define X_CS_PIN 63 + #define X_CS_PIN PinK1 #endif #ifndef Y_CS_PIN - #define Y_CS_PIN 64 + #define Y_CS_PIN PinK2 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN 65 + #define Z_CS_PIN PinK3 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN 66 + #define E0_CS_PIN PinK4 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN 12 + #define E1_CS_PIN PinB6 #endif // TMC2130 Diag Pins (currently just for reference) -#define X_DIAG_PIN 3 -#define Y_DIAG_PIN 14 -#define Z_DIAG_PIN 18 -#define E0_DIAG_PIN 2 -#define E1_DIAG_PIN 15 +#define X_DIAG_PIN PinE5 +#define Y_DIAG_PIN PinJ1 +#define Z_DIAG_PIN PinD3 +#define E0_DIAG_PIN PinE4 +#define E1_DIAG_PIN PinJ0 #ifndef SERVO1_PIN - #define SERVO1_PIN 21 + #define SERVO1_PIN PinD0 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 39 + #define SERVO2_PIN PinG2 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 32 + #define SERVO3_PIN PinC5 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN 20 + #define E1_SERIAL_TX_PIN PinD1 #endif #ifndef E1_SERIAL_RX_PIN - #define E1_SERIAL_RX_PIN 12 + #define E1_SERIAL_RX_PIN PinB6 #endif #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_ORTUR_4.h b/Marlin/src/pins/ramps/pins_ORTUR_4.h index bc86c1a8c66a..4f4bf92b46ee 100644 --- a/Marlin/src/pins/ramps/pins_ORTUR_4.h +++ b/Marlin/src/pins/ramps/pins_ORTUR_4.h @@ -23,6 +23,7 @@ /** * Ortur 4 Arduino Mega based on RAMPS v1.4 pin assignments + * ATmega2560 */ #define BOARD_INFO_NAME "Ortur 4.3" @@ -31,48 +32,48 @@ // // Servos // -#define SERVO0_PIN 29 +#define SERVO0_PIN PinA7 // // Limit Switches // -#define X_MAX_PIN 18 -#define Z_MIN_PIN 63 +#define X_MAX_PIN PinD3 +#define Z_MIN_PIN PinK1 -#define Z_MIN_PROBE_PIN 2 -#define FIL_RUNOUT_PIN 59 +#define Z_MIN_PROBE_PIN PinE4 +#define FIL_RUNOUT_PIN PinF5 // // Steppers // -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 -#define E0_CS_PIN 44 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC3 +#define E0_ENABLE_PIN PinC7 +#define E0_CS_PIN PinL5 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 -#define E1_CS_PIN 42 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA2 +#define E1_CS_PIN PinL7 // // Temperature Sensors // -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 13 // Analog Input +#define TEMP_0_PIN PinJ0 // Analog Input +#define TEMP_1_PIN PinB7 // Analog Input #if HAS_TMC_UART - #define X_SERIAL_TX_PIN 59 - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_TX_PIN PinF5 + #define X_SERIAL_RX_PIN PinK1 - #define Y_SERIAL_TX_PIN 64 - #define Y_SERIAL_RX_PIN 40 + #define Y_SERIAL_TX_PIN PinK2 + #define Y_SERIAL_RX_PIN PinG1 - #define Z_SERIAL_TX_PIN 44 - #define Z_SERIAL_RX_PIN 42 + #define Z_SERIAL_TX_PIN PinL5 + #define Z_SERIAL_RX_PIN PinL7 - #define E0_SERIAL_TX_PIN 66 - #define E0_SERIAL_RX_PIN 65 + #define E0_SERIAL_TX_PIN PinK4 + #define E0_SERIAL_RX_PIN PinK3 #endif #include "pins_RAMPS.h" @@ -82,24 +83,24 @@ // #if IS_RRD_FG_SC #undef BEEPER_PIN - #define BEEPER_PIN 35 + #define BEEPER_PIN PinC2 #undef LCD_PINS_RS #undef LCD_PINS_ENABLE #undef LCD_PINS_D4 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 23 - #define LCD_PINS_D4 37 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA1 + #define LCD_PINS_D4 PinC0 #undef LCD_SDSS #undef SD_DETECT_PIN - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS PinB0 + #define SD_DETECT_PIN PinL0 #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC - #define BTN_EN1 29 - #define BTN_EN2 25 - #define BTN_ENC 16 + #define BTN_EN1 PinA7 + #define BTN_EN2 PinA3 + #define BTN_ENC PinH1 #endif diff --git a/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h index 12c40c7dca03..86ecf5196caf 100644 --- a/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h +++ b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h @@ -22,6 +22,7 @@ /** * Pxmalion Core i3 - https://github.com/Pxmalion + * ATmega2560 */ #include "env_validate.h" @@ -33,7 +34,7 @@ // // Servos // -#define SERVO0_PIN 51 +#define SERVO0_PIN PinB2 #define SERVO1_PIN -1 #define SERVO2_PIN -1 #define SERVO3_PIN -1 @@ -41,10 +42,10 @@ // // Limit Switches // -#define X_STOP_PIN 3 -#define Y_STOP_PIN 2 -#define Z_MIN_PIN 19 -#define Z_MAX_PIN 18 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinE4 +#define Z_MIN_PIN PinD2 +#define Z_MAX_PIN PinD3 // TODO: Filament Runout Sensor #ifndef FIL_RUNOUT_PIN @@ -65,13 +66,13 @@ // #define FET_ORDER_EFB #ifndef MOSFET_A_PIN - #define MOSFET_A_PIN 8 + #define MOSFET_A_PIN PinH5 #endif #ifndef MOSFET_B_PIN - #define MOSFET_B_PIN 7 + #define MOSFET_B_PIN PinH4 #endif #ifndef MOSFET_C_PIN - #define MOSFET_C_PIN 9 + #define MOSFET_C_PIN PinH6 #endif // @@ -81,6 +82,6 @@ #define FILWIDTH_PIN -1 // Analog Input #endif -#define PS_ON_PIN 11 +#define PS_ON_PIN PinB5 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 525c231c8266..658fa0a8d415 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.4 (or v1.3) pin assignments + * ATmega2560, ATmega1280 * * Applies to the following boards: * @@ -45,7 +46,7 @@ * 7 | 11 */ -#if ENABLED(AZSMZ_12864) && DISABLED(ALLOW_SAM3X8E) +#if ENABLED(AZSMZ_12864) #error "No pins defined for RAMPS with AZSMZ_12864." #endif @@ -63,19 +64,19 @@ // #ifndef SERVO0_PIN #ifdef IS_RAMPS_13 - #define SERVO0_PIN 7 + #define SERVO0_PIN PinH4 #else - #define SERVO0_PIN 11 + #define SERVO0_PIN PinB5 #endif #endif #ifndef SERVO1_PIN - #define SERVO1_PIN 6 + #define SERVO1_PIN PinH3 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 5 + #define SERVO2_PIN PinE3 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 4 + #define SERVO3_PIN PinG5 #endif // @@ -87,7 +88,7 @@ #define MOSFET_C_PIN -1 #endif #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) && NUM_SERVOS < 2 - #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH5 // Hardware PWM #endif #ifndef Z_MIN_PIN #define Z_MIN_PIN -1 @@ -96,10 +97,10 @@ #define Z_MAX_PIN -1 #endif #ifndef I_STOP_PIN - #define I_STOP_PIN 18 + #define I_STOP_PIN PinD3 #endif #ifndef J_STOP_PIN - #define J_STOP_PIN 19 + #define J_STOP_PIN PinD2 #endif #endif @@ -108,26 +109,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 3 + #define X_MIN_PIN PinE5 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 14 + #define Y_MIN_PIN PinJ1 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 15 + #define Y_MAX_PIN PinJ0 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 18 + #define Z_MIN_PIN PinD3 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 19 + #define Z_MAX_PIN PinD2 #endif #endif @@ -135,96 +136,96 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN 53 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN 49 + #define Y_CS_PIN PinL0 #endif #ifndef Z_STEP_PIN - #define Z_STEP_PIN 46 + #define Z_STEP_PIN PinL3 #endif #ifndef Z_DIR_PIN - #define Z_DIR_PIN 48 + #define Z_DIR_PIN PinL1 #endif #ifndef Z_ENABLE_PIN - #define Z_ENABLE_PIN 62 + #define Z_ENABLE_PIN PinK0 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN 40 + #define Z_CS_PIN PinG1 #endif #ifndef E0_STEP_PIN - #define E0_STEP_PIN 26 + #define E0_STEP_PIN PinA4 #endif #ifndef E0_DIR_PIN - #define E0_DIR_PIN 28 + #define E0_DIR_PIN PinA6 #endif #ifndef E0_ENABLE_PIN - #define E0_ENABLE_PIN 24 + #define E0_ENABLE_PIN PinA2 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN 42 + #define E0_CS_PIN PinL7 #endif #ifndef E1_STEP_PIN - #define E1_STEP_PIN 36 + #define E1_STEP_PIN PinC1 #endif #ifndef E1_DIR_PIN - #define E1_DIR_PIN 34 + #define E1_DIR_PIN PinC3 #endif #ifndef E1_ENABLE_PIN - #define E1_ENABLE_PIN 30 + #define E1_ENABLE_PIN PinC7 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN 44 + #define E1_CS_PIN PinL5 #endif // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN 15 // Analog Input + #define TEMP_1_PIN PinJ0 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // SPI for MAX Thermocouple // #ifndef TEMP_0_CS_PIN - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // #ifndef MOSFET_A_PIN - #define MOSFET_A_PIN 10 + #define MOSFET_A_PIN PinB4 #endif #ifndef MOSFET_B_PIN - #define MOSFET_B_PIN 9 + #define MOSFET_B_PIN PinH6 #endif #ifndef MOSFET_C_PIN - #define MOSFET_C_PIN 8 + #define MOSFET_C_PIN PinH5 #endif #ifndef MOSFET_D_PIN #define MOSFET_D_PIN -1 @@ -262,7 +263,7 @@ #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan #define FAN_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed - #define FAN_PIN 4 // IO pin. Buffer needed + #define FAN_PIN PinG5 // IO pin. Buffer needed #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") #define FAN_PIN MOSFET_B_PIN #endif @@ -274,26 +275,26 @@ #ifndef SDSS #define SDSS AUX3_06_PIN #endif -#define LED_PIN 13 +#define LED_PIN PinB7 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 #endif // RAMPS 1.4 DIO 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN PinG5 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN PinB6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -302,15 +303,15 @@ // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS < 2 // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! #ifndef SPINDLE_LASER_PWM_PIN - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM #endif - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #else #error "No auto-assignable Spindle/Laser pins available." #endif @@ -320,13 +321,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 66 + #define TMC_SPI_MOSI PinK4 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO PinL5 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 64 + #define TMC_SPI_SCK PinK2 #endif #if HAS_TMC_UART @@ -352,10 +353,10 @@ //#define E4_HARDWARE_SERIAL Serial1 #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN PinG1 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN PinK1 #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 @@ -365,10 +366,10 @@ #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN PinF5 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN PinK2 #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 @@ -378,10 +379,10 @@ #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN PinL7 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN PinK3 #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN -1 @@ -391,10 +392,10 @@ #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN PinL5 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN PinK4 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 @@ -445,13 +446,13 @@ // #if HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN 40 // Z_CS_PIN + #define E_MUX0_PIN PinG1 // Z_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 42 // E0_CS_PIN + #define E_MUX1_PIN PinL7 // E0_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 44 // E1_CS_PIN + #define E_MUX2_PIN PinL5 // E1_CS_PIN #endif #endif @@ -461,10 +462,10 @@ // 1 3 5 7 // 5V GND A3 A4 // -#define AUX1_05_PIN 57 // (A3) -#define AUX1_06_PIN 2 -#define AUX1_07_PIN 58 // (A4) -#define AUX1_08_PIN 1 +#define AUX1_05_PIN PinF3 // (A3) +#define AUX1_06_PIN PinE4 +#define AUX1_07_PIN PinF4 // (A4) +#define AUX1_08_PIN PinE1 // // AUX2 GND A9 D40 D42 A11 @@ -472,14 +473,14 @@ // 1 3 5 7 9 // VCC A5 A10 D44 A12 // -#define AUX2_03_PIN 59 // (A5) -#define AUX2_04_PIN 63 // (A9) -#define AUX2_05_PIN 64 // (A10) -#define AUX2_06_PIN 40 -#define AUX2_07_PIN 44 -#define AUX2_08_PIN 42 -#define AUX2_09_PIN 66 // (A12) -#define AUX2_10_PIN 65 // (A11) +#define AUX2_03_PIN PinF5 // (A5) +#define AUX2_04_PIN PinK1 // (A9) +#define AUX2_05_PIN PinK2 // (A10) +#define AUX2_06_PIN PinG1 +#define AUX2_07_PIN PinL5 +#define AUX2_08_PIN PinL7 +#define AUX2_09_PIN PinK4 // (A12) +#define AUX2_10_PIN PinK3 // (A11) // // AUX3 GND D52 D50 5V @@ -487,31 +488,31 @@ // 8 6 4 2 // NC D53 D51 D49 // -#define AUX3_02_PIN 49 -#define AUX3_03_PIN 50 -#define AUX3_04_PIN 51 -#define AUX3_05_PIN 52 -#define AUX3_06_PIN 53 +#define AUX3_02_PIN PinL0 +#define AUX3_03_PIN PinB3 +#define AUX3_04_PIN PinB2 +#define AUX3_05_PIN PinB1 +#define AUX3_06_PIN PinB0 // // AUX4 5V GND D32 D47 D45 D43 D41 D39 D37 D35 D33 D31 D29 D27 D25 D23 D17 D16 // -#define AUX4_03_PIN 32 -#define AUX4_04_PIN 47 -#define AUX4_05_PIN 45 -#define AUX4_06_PIN 43 -#define AUX4_07_PIN 41 -#define AUX4_08_PIN 39 -#define AUX4_09_PIN 37 -#define AUX4_10_PIN 35 -#define AUX4_11_PIN 33 -#define AUX4_12_PIN 31 -#define AUX4_13_PIN 29 -#define AUX4_14_PIN 27 -#define AUX4_15_PIN 25 -#define AUX4_16_PIN 23 -#define AUX4_17_PIN 17 -#define AUX4_18_PIN 16 +#define AUX4_03_PIN PinC5 +#define AUX4_04_PIN PinL2 +#define AUX4_05_PIN PinL4 +#define AUX4_06_PIN PinL6 +#define AUX4_07_PIN PinG0 +#define AUX4_08_PIN PinG2 +#define AUX4_09_PIN PinC0 +#define AUX4_10_PIN PinC2 +#define AUX4_11_PIN PinC4 +#define AUX4_12_PIN PinC6 +#define AUX4_13_PIN PinA7 +#define AUX4_14_PIN PinA5 +#define AUX4_15_PIN PinA3 +#define AUX4_16_PIN PinA1 +#define AUX4_17_PIN PinH0 +#define AUX4_18_PIN PinH1 /** * LCD adapters come in different variants. The socket keys can be diff --git a/Marlin/src/pins/ramps/pins_RAMPS_13.h b/Marlin/src/pins/ramps/pins_RAMPS_13.h index 6e7c8cbab592..026492e4a871 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_13.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_13.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.3 pin assignments + * ATmega2560, ATmega1280 * * Applies to the following boards: * diff --git a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h index 3d5f5d6f9107..8bc9b9c8a329 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_CREALITY.h @@ -21,6 +21,8 @@ */ #pragma once +// ATmega2560 + #if HOTENDS > 2 || E_STEPPERS > 2 #error "Creality RAMPS supports up to 2 hotends / E steppers." #endif @@ -30,12 +32,12 @@ // // Heaters / Fans // -#define MOSFET_B_PIN 7 // For HEATER_1_PIN ("EEF" or "EEB") -#define FAN_PIN 9 +#define MOSFET_B_PIN PinH4 // For HEATER_1_PIN ("EEF" or "EEB") +#define FAN_PIN PinH6 -#define FIL_RUNOUT_PIN 2 +#define FIL_RUNOUT_PIN PinE4 #if NUM_RUNOUT_SENSORS >= 2 - #define FIL_RUNOUT2_PIN 15 // Creality CR-X can use dual runout sensors + #define FIL_RUNOUT2_PIN PinJ0 // Creality CR-X can use dual runout sensors #endif #ifndef SD_DETECT_PIN @@ -43,30 +45,30 @@ //#define HAS_ONBOARD_SD_DETECT // If the SD_DETECT_PIN is wired up #endif #if ENABLED(HAS_ONBOARD_SD_DETECT) || !SD_CONNECTION_IS(ONBOARD) - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN PinL0 #endif #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 40 // Used by CR2020 Industrial series + #define PS_ON_PIN PinG1 // Used by CR2020 Industrial series #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) - #define CASE_LIGHT_PIN 65 + #define CASE_LIGHT_PIN PinK3 #endif #include "pins_RAMPS.h" #ifndef BEEPER_PIN - #define BEEPER_PIN 37 // Always define beeper pin so Play Tone works with ExtUI + #define BEEPER_PIN PinC0 // Always define beeper pin so Play Tone works with ExtUI #endif -#define EXP1_PIN 65 // A11 - Used by CR2020 Industrial series for case -#define EXP2_PIN 66 // A12 -#define EXP3_PIN 11 // SERVO0_PIN -#define EXP4_PIN 12 // PS_ON_PIN +#define EXP1_PIN PinK3 // A11 - Used by CR2020 Industrial series for case +#define EXP2_PIN PinK4 // A12 +#define EXP3_PIN PinB5 // SERVO0_PIN +#define EXP4_PIN PinB6 // PS_ON_PIN -#define SUICIDE_PIN 12 // Used by CR2020 Industrial series +#define SUICIDE_PIN PinB6 // Used by CR2020 Industrial series #ifndef SUICIDE_PIN_STATE #define SUICIDE_PIN_STATE HIGH #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h index 8f9148b732ee..3ffa940c482d 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_ENDER_4.h @@ -21,6 +21,8 @@ */ #pragma once +// ATmega2560 + #if HAS_MULTI_HOTEND || E_STEPPERS > 1 #error "Ender-4 only supports 1 hotend / E stepper." #endif diff --git a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h index 974766623594..7cee1a628630 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_OLD.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_OLD.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.0, v1.1, v1.2 pin assignments + * ATmega2560, ATmega1280 */ #include "env_validate.h" @@ -35,83 +36,83 @@ // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 16 -#define Y_MAX_PIN 17 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinH1 +#define Y_MAX_PIN PinH0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinA4 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinA2 -#define Y_STEP_PIN 38 -#define Y_DIR_PIN 40 -#define Y_ENABLE_PIN 36 +#define Y_STEP_PIN PinD7 +#define Y_DIR_PIN PinG1 +#define Y_ENABLE_PIN PinC1 -#define Z_STEP_PIN 44 -#define Z_DIR_PIN 46 -#define Z_ENABLE_PIN 42 +#define Z_STEP_PIN PinL5 +#define Z_DIR_PIN PinL3 +#define Z_ENABLE_PIN PinL7 -#define E0_STEP_PIN 32 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN PinC5 +#define E0_DIR_PIN PinC3 +#define E0_ENABLE_PIN PinC7 // // Temperature Sensors // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input +#define TEMP_0_PIN PinE4 // Analog Input +#define TEMP_BED_PIN PinE1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // #if ENABLED(RAMPS_V_1_0) - #define HEATER_0_PIN 12 + #define HEATER_0_PIN PinB6 #define HEATER_BED_PIN -1 #ifndef FAN_PIN - #define FAN_PIN 11 + #define FAN_PIN PinB5 #endif #else // RAMPS_V_1_1 or RAMPS_V_1_2 - #define HEATER_0_PIN 10 - #define HEATER_BED_PIN 8 + #define HEATER_0_PIN PinB4 + #define HEATER_BED_PIN PinH5 #ifndef FAN_PIN - #define FAN_PIN 9 + #define FAN_PIN PinH6 #endif #endif // // Misc. Functions // -#define SDPOWER_PIN 48 -#define SDSS 53 -#define LED_PIN 13 +#define SDPOWER_PIN PinL1 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 45 // Hardware PWM + #define CASE_LIGHT_PIN PinL4 // Hardware PWM #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 41 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_DIR_PIN 43 +#define SPINDLE_LASER_ENA_PIN PinG0 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN PinL4 // Hardware PWM +#define SPINDLE_DIR_PIN PinL6 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 8ccb14c866db..43f04bb218a1 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.4Plus, also known as 3DYMY version, pin assignments + * ATmega2560, ATmega1280 * * Applies to the following boards: * @@ -42,8 +43,8 @@ #define BOARD_INFO_NAME "RAMPS 1.4 Plus" -#define MOSFET_A_PIN 8 -#define MOSFET_C_PIN 10 +#define MOSFET_A_PIN PinH5 +#define MOSFET_C_PIN PinB4 // // Steppers @@ -53,14 +54,14 @@ #define Z_CS_PIN -1 // Swap E0 / E1 on 3DYMY -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC3 +#define E0_ENABLE_PIN PinC7 #define E0_CS_PIN -1 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA2 #define E1_CS_PIN -1 /** 3DYMY Expansion Headers @@ -73,22 +74,22 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN 37 -#define EXP1_02_PIN 35 -#define EXP1_03_PIN 31 -#define EXP1_04_PIN 41 -#define EXP1_05_PIN 33 -#define EXP1_06_PIN 23 -#define EXP1_07_PIN 42 -#define EXP1_08_PIN 44 +#define EXP1_01_PIN PinC0 +#define EXP1_02_PIN PinC2 +#define EXP1_03_PIN PinC6 +#define EXP1_04_PIN PinG0 +#define EXP1_05_PIN PinC4 +#define EXP1_06_PIN PinA1 +#define EXP1_07_PIN PinL7 +#define EXP1_08_PIN PinL5 -#define EXP2_01_PIN 50 -#define EXP2_02_PIN 52 -#define EXP2_03_PIN 29 -#define EXP2_04_PIN 53 -#define EXP2_05_PIN 25 -#define EXP2_06_PIN 51 -#define EXP2_07_PIN 49 -#define EXP2_08_PIN 27 +#define EXP2_01_PIN PinB3 +#define EXP2_02_PIN PinB1 +#define EXP2_03_PIN PinA7 +#define EXP2_04_PIN PinB0 +#define EXP2_05_PIN PinA3 +#define EXP2_06_PIN PinB2 +#define EXP2_07_PIN PinL0 +#define EXP2_08_PIN PinA5 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index 93916db3e988..343e5a598310 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -24,6 +24,7 @@ /** * Arduino Mega with RAMPS-S v1.2 by Sakul.cz pin assignments * Written by Michal Rábek + * ATmega2560 * * Applies to the following boards: * @@ -47,16 +48,16 @@ // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN 10 + #define SERVO0_PIN PinB4 #endif #ifndef SERVO1_PIN - #define SERVO1_PIN 11 + #define SERVO1_PIN PinB5 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN 12 + #define SERVO2_PIN PinB6 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 44 + #define SERVO3_PIN PinL5 #endif // @@ -64,26 +65,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 37 + #define X_MIN_PIN PinC0 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 36 + #define X_MAX_PIN PinC1 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 35 + #define Y_MIN_PIN PinC2 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 34 + #define Y_MAX_PIN PinC3 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 33 + #define Z_MIN_PIN PinC4 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 32 + #define Z_MAX_PIN PinC5 #endif #endif @@ -91,62 +92,62 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 5 + #define Z_MIN_PROBE_PIN PinE3 #endif // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 44 // RAMPS_S S3 on the servos connector + #define FIL_RUNOUT_PIN PinL5 // RAMPS_S S3 on the servos connector #endif // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN PinH0 +#define X_DIR_PIN PinH1 +#define X_ENABLE_PIN PinL1 -#define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 -#define Y_ENABLE_PIN 55 +#define Y_STEP_PIN PinF0 +#define Y_DIR_PIN PinL2 +#define Y_ENABLE_PIN PinF1 #ifndef Z_STEP_PIN - #define Z_STEP_PIN 57 + #define Z_STEP_PIN PinF3 #endif -#define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_DIR_PIN PinF2 +#define Z_ENABLE_PIN PinK0 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 22 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA1 +#define E0_DIR_PIN PinA0 +#define E0_ENABLE_PIN PinA2 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 25 -#define E1_ENABLE_PIN 27 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA3 +#define E1_ENABLE_PIN PinA5 -#define E2_STEP_PIN 29 -#define E2_DIR_PIN 28 -#define E2_ENABLE_PIN 39 +#define E2_STEP_PIN PinA7 +#define E2_DIR_PIN PinA6 +#define E2_ENABLE_PIN PinG2 // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN 15 // Analog Input + #define TEMP_0_PIN PinJ0 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN 14 // Analog Input + #define TEMP_1_PIN PinJ1 // Analog Input #endif #ifndef TEMP_2_PIN - #define TEMP_2_PIN 13 // Analog Input + #define TEMP_2_PIN PinB7 // Analog Input #endif #ifndef TEMP_3_PIN - #define TEMP_3_PIN 12 // Analog Input + #define TEMP_3_PIN PinB6 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN 11 // Analog Input + #define TEMP_BED_PIN PinB5 // Analog Input #endif // @@ -156,16 +157,16 @@ #define MOSFET_D_PIN -1 #endif #ifndef RAMPS_S_HE_0 - #define RAMPS_S_HE_0 2 + #define RAMPS_S_HE_0 PinE4 #endif #ifndef RAMPS_S_HE_1 - #define RAMPS_S_HE_1 3 + #define RAMPS_S_HE_1 PinE5 #endif #ifndef RAMPS_S_HE_2 - #define RAMPS_S_HE_2 6 + #define RAMPS_S_HE_2 PinH3 #endif -#define HEATER_BED_PIN 9 +#define HEATER_BED_PIN PinH6 #define HEATER_0_PIN RAMPS_S_HE_0 @@ -183,26 +184,26 @@ // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef KILL_PIN - #define KILL_PIN 46 + #define KILL_PIN PinL3 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 60 // Analog Input on EXTEND + #define FILWIDTH_PIN PinF6 // Analog Input on EXTEND #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 // RAMPS_S S2 on the servos connector + #define PS_ON_PIN PinB6 // RAMPS_S S2 on the servos connector #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 12 // Hardware PWM (RAMPS_S S1 on the servos connector) + #define CASE_LIGHT_PIN PinB6 // Hardware PWM (RAMPS_S S1 on the servos connector) #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -210,22 +211,22 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #endif // // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 51 + #define TMC_SPI_MOSI PinB2 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 50 + #define TMC_SPI_MISO PinB3 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 53 + #define TMC_SPI_SCK PinB0 #endif // @@ -233,13 +234,13 @@ // #if HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN 29 // E2_STEP_PIN + #define E_MUX0_PIN PinA7 // E2_STEP_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 28 // E2_DIR_PIN + #define E_MUX1_PIN PinA6 // E2_DIR_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 39 // E2_ENABLE_PIN + #define E_MUX2_PIN PinG2 // E2_ENABLE_PIN #endif #endif @@ -251,15 +252,15 @@ // LCD Display output pins // #if HAS_WIRED_LCD - #define BEEPER_PIN 45 - #define LCD_PINS_RS 19 - #define LCD_PINS_ENABLE 49 - #define LCD_PINS_D4 18 - #define LCD_PINS_D5 30 - #define LCD_PINS_D6 41 - #define LCD_PINS_D7 31 + #define BEEPER_PIN PinL4 + #define LCD_PINS_RS PinD2 + #define LCD_PINS_ENABLE PinL0 + #define LCD_PINS_D4 PinD3 + #define LCD_PINS_D5 PinC7 + #define LCD_PINS_D6 PinG0 + #define LCD_PINS_D7 PinC6 #ifndef SD_DETECT_PIN - #define SD_DETECT_PIN 38 + #define SD_DETECT_PIN PinD7 #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -272,7 +273,7 @@ // LCD Display input pins // #if IS_NEWPANEL - #define BTN_EN1 40 - #define BTN_EN2 42 - #define BTN_ENC 43 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinL7 + #define BTN_ENC PinL6 #endif diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h index 273e0274a8e7..543026cd6671 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD.h @@ -23,6 +23,7 @@ /** * RIGIDBOARD Arduino Mega with RAMPS v1.4 pin assignments + * ATmega2560, ATmega1280 */ #ifndef BOARD_INFO_NAME @@ -33,31 +34,31 @@ // Steppers // RigidBot swaps E0 / E1 plugs vs RAMPS 1.3 // -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC3 +#define E0_ENABLE_PIN PinC7 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 // Z-MAX pin J14 End Stops + #define Z_MIN_PROBE_PIN PinD2 // Z-MAX pin J14 End Stops #endif // // MOSFET changes // -#define MOSFET_A_PIN 9 // EXTRUDER 1 -#define MOSFET_B_PIN 8 // FAN (by default) -#define MOSFET_D_PIN 12 // EXTRUDER 2 or FAN +#define MOSFET_A_PIN PinH6 // EXTRUDER 1 +#define MOSFET_B_PIN PinH5 // FAN (by default) +#define MOSFET_D_PIN PinB6 // EXTRUDER 2 or FAN #include "pins_RAMPS.h" -#define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot +#define STEPPER_RESET_PIN PinG0 // Stepper drivers have a reset on RigidBot // // Temperature Sensors @@ -65,26 +66,26 @@ #undef TEMP_0_PIN #undef TEMP_1_PIN #undef TEMP_BED_PIN -#define TEMP_0_PIN 14 // Analog Input -#define TEMP_1_PIN 13 // Analog Input -#define TEMP_BED_PIN 15 // Analog Input +#define TEMP_0_PIN PinJ1 // Analog Input +#define TEMP_1_PIN PinB7 // Analog Input +#define TEMP_BED_PIN PinJ0 // Analog Input // SPI for MAX Thermocouple #undef TEMP_0_CS_PIN #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card + #define TEMP_0_CS_PIN PinB0 // Don't use pin 53 if there is even the remote possibility of using Display/SD card #else - #define TEMP_0_CS_PIN 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present + #define TEMP_0_CS_PIN PinL0 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present #endif // // Heaters / Fans // #undef HEATER_BED_PIN -#define HEATER_BED_PIN 10 +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 8 // Same as RAMPS_13_EEF + #define FAN_PIN PinH5 // Same as RAMPS_13_EEF #endif // @@ -102,28 +103,28 @@ #define BEEPER_PIN -1 // Direction buttons - #define BTN_UP 37 - #define BTN_DOWN 35 - #define BTN_LEFT 33 - #define BTN_RIGHT 32 + #define BTN_UP PinC0 + #define BTN_DOWN PinC2 + #define BTN_LEFT PinC4 + #define BTN_RIGHT PinC5 // 'R' button #undef BTN_ENC - #define BTN_ENC 31 + #define BTN_ENC PinC6 // Disable encoder #undef BTN_EN1 #undef BTN_EN2 #undef SD_DETECT_PIN - #define SD_DETECT_PIN 22 + #define SD_DETECT_PIN PinA0 #elif IS_RRD_SC #undef SD_DETECT_PIN - #define SD_DETECT_PIN 22 + #define SD_DETECT_PIN PinA0 #undef KILL_PIN - #define KILL_PIN 32 + #define KILL_PIN PinC5 #endif diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h index 8242f1a77294..58eb9f659e2f 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h @@ -23,6 +23,7 @@ /** * RIGIDBOARD V2 Arduino Mega with RAMPS v1.4 pin assignments + * ATmega2560, ATmega1280 */ #define BOARD_INFO_NAME "RigidBoard V2" @@ -44,7 +45,7 @@ #define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 #define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V #define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 -#define DAC_DISABLE_PIN 42 // set low to enable DAC +#define DAC_DISABLE_PIN PinL7 // set low to enable DAC #define DAC_OR_ADDRESS 0x01 #ifndef DAC_MOTOR_CURRENT_DEFAULT diff --git a/Marlin/src/pins/ramps/pins_RL200.h b/Marlin/src/pins/ramps/pins_RL200.h index 00fb39a43901..4a240d5ece44 100644 --- a/Marlin/src/pins/ramps/pins_RL200.h +++ b/Marlin/src/pins/ramps/pins_RL200.h @@ -24,6 +24,7 @@ /** * Rapide Lite 200 v1 (RUMBA clone) pin assignments. Has slightly different assignment for * extruder motors due to dual Z motors. Pinout therefore based on pins_RUMBA.h. + * ATmega2560 */ #define BOARD_INFO_NAME "RL200" @@ -37,16 +38,16 @@ #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200." #endif -#define E0_STEP_PIN 26 // (RUMBA E1 pins) -#define E0_DIR_PIN 25 -#define E0_ENABLE_PIN 27 +#define E0_STEP_PIN PinA4 // (RUMBA E1 pins) +#define E0_DIR_PIN PinA3 +#define E0_ENABLE_PIN PinA5 -#define E1_STEP_PIN 29 // (RUMBA E2 pins) -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 39 +#define E1_STEP_PIN PinA7 // (RUMBA E2 pins) +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinG2 -#define Z2_STEP_PIN 23 // (RUMBA E0 pins) -#define Z2_DIR_PIN 22 -#define Z2_ENABLE_PIN 24 +#define Z2_STEP_PIN PinA1 // (RUMBA E0 pins) +#define Z2_DIR_PIN PinA0 +#define Z2_ENABLE_PIN PinA2 #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index eb049c48dd99..e659f74f0673 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -23,6 +23,7 @@ /** * RUMBA pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -42,71 +43,68 @@ // // Servos // -#define SERVO0_PIN 5 +#define SERVO0_PIN PinE3 // // Limit Switches // #ifndef X_MIN_PIN - #define X_MIN_PIN 37 -#endif -#ifndef X_MIN_PIN - #define X_MIN_PIN 37 + #define X_MIN_PIN PinC0 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 36 + #define X_MAX_PIN PinC1 #endif #ifndef Y_MIN_PIN - #define Y_MIN_PIN 35 + #define Y_MIN_PIN PinC2 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 34 + #define Y_MAX_PIN PinC3 #endif #ifndef Z_MIN_PIN - #define Z_MIN_PIN 33 + #define Z_MIN_PIN PinC4 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 32 + #define Z_MAX_PIN PinC5 #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 17 -#define X_DIR_PIN 16 -#define X_ENABLE_PIN 48 +#define X_STEP_PIN PinH0 +#define X_DIR_PIN PinH1 +#define X_ENABLE_PIN PinL1 -#define Y_STEP_PIN 54 -#define Y_DIR_PIN 47 -#define Y_ENABLE_PIN 55 +#define Y_STEP_PIN PinF0 +#define Y_DIR_PIN PinL2 +#define Y_ENABLE_PIN PinF1 -#define Z_STEP_PIN 57 -#define Z_DIR_PIN 56 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinF3 +#define Z_DIR_PIN PinF2 +#define Z_ENABLE_PIN PinK0 #ifndef E0_STEP_PIN - #define E0_STEP_PIN 23 - #define E0_DIR_PIN 22 - #define E0_ENABLE_PIN 24 + #define E0_STEP_PIN PinA1 + #define E0_DIR_PIN PinA0 + #define E0_ENABLE_PIN PinA2 #endif #ifndef E1_STEP_PIN - #define E1_STEP_PIN 26 - #define E1_DIR_PIN 25 - #define E1_ENABLE_PIN 27 + #define E1_STEP_PIN PinA4 + #define E1_DIR_PIN PinA3 + #define E1_ENABLE_PIN PinA5 #endif #if E1_STEP_PIN != 29 - #define E2_STEP_PIN 29 - #define E2_DIR_PIN 28 - #define E2_ENABLE_PIN 39 + #define E2_STEP_PIN PinA7 + #define E2_DIR_PIN PinA6 + #define E2_ENABLE_PIN PinG2 #endif // @@ -114,137 +112,137 @@ // #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 6 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) + #define TEMP_0_PIN PinH3 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) #else - #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) + #define TEMP_0_PIN PinJ0 // Analog Input (default connector for thermistor *T0* on rumba board is used) #endif #endif #ifndef TEMP_1_PIN #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) + #define TEMP_1_PIN PinE3 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) #else - #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) + #define TEMP_1_PIN PinJ1 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) + #define TEMP_2_PIN PinH4 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) #else - #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) + #define TEMP_2_PIN PinB7 // Analog Input (default connector for thermistor *T2* on rumba board is used) #endif // Optional for extruder 4 or chamber: -//#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) +//#define TEMP_X_PIN PinB6 // Analog Input (default connector for thermistor *T3* on rumba board is used) #ifndef TEMP_CHAMBER_PIN - //#define TEMP_CHAMBER_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) + //#define TEMP_CHAMBER_PIN PinB6 // Analog Input (default connector for thermistor *T3* on rumba board is used) #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) + #define TEMP_BED_PIN PinH4 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) #else - #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) + #define TEMP_BED_PIN PinB5 // Analog Input (default connector for thermistor *THB* on rumba board is used) #endif // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 8 -#define HEATER_BED_PIN 9 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_2_PIN PinH3 +#define HEATER_3_PIN PinH5 +#define HEATER_BED_PIN PinH6 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN PinH4 #endif #ifndef FAN1_PIN - #define FAN1_PIN 8 + #define FAN1_PIN PinH5 #endif // // Misc. Functions // -#define LED_PIN 13 -#define PS_ON_PIN 45 -#define KILL_PIN 46 +#define LED_PIN PinB7 +#define PS_ON_PIN PinL4 +#define KILL_PIN PinL3 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 45 + #define CASE_LIGHT_PIN PinL4 #endif // // M3/M4/M5 - Spindle/Laser Control // #ifndef SPINDLE_LASER_PWM_PIN - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM. Pin 4 interrupts OC0* and OC1* always in use? + #define SPINDLE_LASER_PWM_PIN PinG5 // Hardware PWM. Pin 4 interrupts OC0* and OC1* always in use? #endif #ifndef SPINDLE_LASER_ENA_PIN - #define SPINDLE_LASER_ENA_PIN 14 // Pullup! + #define SPINDLE_LASER_ENA_PIN PinJ1 // Pullup! #endif #ifndef SPINDLE_DIR_PIN - #define SPINDLE_DIR_PIN 15 + #define SPINDLE_DIR_PIN PinJ0 #endif // // LCD / Controller // #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 38 // Set as output on init - #define LCD_PINS_RS 41 // Pull low for 1s to init + #define LCD_PINS_DC PinD7 // Set as output on init + #define LCD_PINS_RS PinG0 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 19 - #define DOGLCD_MOSI 42 - #define DOGLCD_SCK 18 + #define DOGLCD_CS PinD2 + #define DOGLCD_MOSI PinL7 + #define DOGLCD_SCK PinD3 #define DOGLCD_A0 LCD_PINS_DC #elif ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS 42 - #define DOGLCD_A0 19 - #define DOGLCD_MOSI 51 - #define DOGLCD_SCK 52 + #define DOGLCD_CS PinL7 + #define DOGLCD_A0 PinD2 + #define DOGLCD_MOSI PinB2 + #define DOGLCD_SCK PinB1 //#define FORCE_SOFT_SPI // Use this if default of hardware SPI causes display problems // results in LCD soft SPI mode 3, SD soft SPI mode 0 - #define LCD_RESET_PIN 18 // Must be high or open for LCD to operate normally. + #define LCD_RESET_PIN PinD3 // Must be high or open for LCD to operate normally. #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN 41 + #define RGB_LED_R_PIN PinG0 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN 38 + #define RGB_LED_G_PIN PinD7 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN 40 + #define RGB_LED_B_PIN PinG1 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN 38 + #define NEOPIXEL_PIN PinD7 #endif #else - #define LCD_PINS_RS 19 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 18 - #define LCD_PINS_D5 38 - #define LCD_PINS_D6 41 + #define LCD_PINS_RS PinD2 + #define LCD_PINS_ENABLE PinL7 + #define LCD_PINS_D4 PinD3 + #define LCD_PINS_D5 PinD7 + #define LCD_PINS_D6 PinG0 #endif -#define LCD_PINS_D7 40 +#define LCD_PINS_D7 PinG1 // // Beeper, SD Card, Encoder // -#define BEEPER_PIN 44 +#define BEEPER_PIN PinL5 #if ENABLED(SDSUPPORT) - #define SDSS 53 - #define SD_DETECT_PIN 49 + #define SDSS PinB0 + #define SD_DETECT_PIN PinL0 #endif #if IS_NEWPANEL - #define BTN_EN1 11 - #define BTN_EN2 12 - #define BTN_ENC 43 + #define BTN_EN1 PinB5 + #define BTN_EN2 PinB6 + #define BTN_ENC PinL6 #endif diff --git a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h index 39942613ffbf..dfe784ca7527 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h +++ b/Marlin/src/pins/ramps/pins_RUMBA_RAISE3D.h @@ -21,11 +21,13 @@ */ #pragma once +// ATmega2560 + #define BOARD_INFO_NAME "Raise3D Rumba" #define DEFAULT_MACHINE_NAME "Raise3D N Series" // Raise3D uses thermocouples on the standard input pins -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 14 // Analog Input +#define TEMP_0_PIN PinJ0 // Analog Input +#define TEMP_1_PIN PinJ1 // Analog Input #include "pins_RUMBA.h" diff --git a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h index d25029a7a39c..dff2b8651427 100644 --- a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h +++ b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h @@ -23,6 +23,7 @@ /** * Sainsmart 2-in-1 pin assignments + * ATmega2560, ATmega1280 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -34,9 +35,9 @@ // // Heaters / Fans // -#define MOSFET_A_PIN 9 // E -#define MOSFET_B_PIN 7 // F PART FAN in front of board next to Extruder heat - // MOSFET_C_PIN 8 // B -#define MOSFET_D_PIN 10 // F / E +#define MOSFET_A_PIN PinH6 // E +#define MOSFET_B_PIN PinH4 // F PART FAN in front of board next to Extruder heat + // MOSFET_C_PIN PinH5 // B +#define MOSFET_D_PIN PinB4 // F / E #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 451d2f874d7f..3d86ba5a1842 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -23,30 +23,31 @@ /** * BIQU Tango pin assignments + * ATmega2560 */ #define BOARD_INFO_NAME "Tango" -#define FAN_PIN 8 +#define FAN_PIN PinH5 #define FAN1_PIN -1 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 7 + #define E0_AUTO_FAN_PIN PinH4 #endif #ifndef TEMP_0_PIN #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) + #define TEMP_0_PIN PinB4 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) #else - #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) + #define TEMP_0_PIN PinJ0 // Analog Input (default connector for thermistor *T0* on rumba board is used) #endif #endif #ifndef TEMP_1_PIN #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) + #define TEMP_1_PIN PinH6 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) #else - #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) + #define TEMP_1_PIN PinJ1 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index b11487b21d36..d608348f1c33 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -23,6 +23,7 @@ /** * Tenlog pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -38,90 +39,90 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 6 +#define SERVO0_PIN PinB5 +#define SERVO1_PIN PinH3 #define SERVO2_PIN -1 // Original pin 5 used for hotend fans -#define SERVO3_PIN 4 +#define SERVO3_PIN PinG5 // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 14 -//#define Y_MAX_PIN 15 // Connected to "DJ" plug on extruder heads -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinJ1 +//#define Y_MAX_PIN PinJ0 // Connected to "DJ" plug on extruder heads +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 15 // Ramps is normally 32 + #define Z_MIN_PROBE_PIN PinJ0 // Ramps is normally 32 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 //#ifndef X_CS_PIN - //#define X_CS_PIN 53 + //#define X_CS_PIN PinB0 //#endif -#define X2_STEP_PIN 36 -#define X2_DIR_PIN 34 -#define X2_ENABLE_PIN 30 +#define X2_STEP_PIN PinC1 +#define X2_DIR_PIN PinC3 +#define X2_ENABLE_PIN PinC7 //#ifndef X2_CS_PIN - //#define X2_CS_PIN 53 + //#define X2_CS_PIN PinB0 //#endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 //#ifndef Y_CS_PIN - //#define Y_CS_PIN 49 + //#define Y_CS_PIN PinL0 //#endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 //#ifndef Z_CS_PIN - //#define Z_CS_PIN 40 + //#define Z_CS_PIN PinG1 //#endif -#define Z2_STEP_PIN 65 -#define Z2_DIR_PIN 66 -#define Z2_ENABLE_PIN 64 +#define Z2_STEP_PIN PinK3 +#define Z2_DIR_PIN PinK4 +#define Z2_ENABLE_PIN PinK2 //#ifndef Z2_CS_PIN - //#define Z2_CS_PIN 40 + //#define Z2_CS_PIN PinG1 //#endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 //#ifndef E0_CS_PIN - //define E0_CS_PIN 42 + //define E0_CS_PIN PinL7 //#endif -#define E1_STEP_PIN 57 -#define E1_DIR_PIN 58 -#define E1_ENABLE_PIN 59 +#define E1_STEP_PIN PinF3 +#define E1_DIR_PIN PinF4 +#define E1_ENABLE_PIN PinF5 //#ifndef E1_CS_PIN - //define E1_CS_PIN 44 + //define E1_CS_PIN PinL5 //#endif -//#define E2_STEP_PIN 42 -//#define E2_DIR_PIN 43 -//#define E2_ENABLE_PIN 44 +//#define E2_STEP_PIN PinL7 +//#define E2_DIR_PIN PinL6 +//#define E2_ENABLE_PIN PinL5 // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) @@ -133,33 +134,33 @@ // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 11 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinB5 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 9 -#define FAN1_PIN 5 // Normally this would be a servo pin +#define FAN_PIN PinH6 +#define FAN1_PIN PinE3 // Normally this would be a servo pin // XXX Runout support unknown? //#define NUM_RUNOUT_SENSORS 0 -//#define FIL_RUNOUT_PIN 22 -//#define FIL_RUNOUT2_PIN 21 +//#define FIL_RUNOUT_PIN PinA0 +//#define FIL_RUNOUT2_PIN PinD0 // // Misc. Functions // -//#define PS_ON_PIN 40 // The M80/M81 PSU pin for boards v2.1-2.3 -//#define CASE_LIGHT_PIN 5 -#define SDSS 53 +//#define PS_ON_PIN PinG1 // The M80/M81 PSU pin for boards v2.1-2.3 +//#define CASE_LIGHT_PIN PinE3 +#define SDSS PinB0 //#ifndef LED_PIN - //#define LED_PIN 13 + //#define LED_PIN PinB7 //#endif //#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM -//#define SPINDLE_LASER_ENA_PIN 4 // Pullup! +//#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -//#define FILWIDTH_PIN 5 // Analog Input +//#define FILWIDTH_PIN PinE3 // Analog Input // // LCD / Controller @@ -173,12 +174,12 @@ #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 #define LCD_PINS_D7 -1 -//#define BTN_EN1 31 -//#define BTN_EN2 33 -//#define BTN_ENC 35 -#define SD_DETECT_PIN 49 +//#define BTN_EN1 PinC6 +//#define BTN_EN2 PinC4 +//#define BTN_ENC PinC2 +#define SD_DETECT_PIN PinL0 //#ifndef KILL_PIN - //#define KILL_PIN 41 + //#define KILL_PIN PinG0 //#endif //#ifndef BEEPER_PIN #define BEEPER_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h index 71dfb8c70441..1acec82bd8fc 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_13.h @@ -23,21 +23,22 @@ /** * Arduino Mega with RAMPS v1.3 for Anycubic + * ATmega2560 */ #define BOARD_INFO_NAME "Anycubic RAMPS 1.3" -#define MOSFET_B_PIN 44 +#define MOSFET_B_PIN PinL5 #define E1_STEP_PIN -1 #define E1_DIR_PIN -1 #define E1_ENABLE_PIN -1 #define E1_CS_PIN -1 -#define FAN2_PIN 9 +#define FAN2_PIN PinH6 #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 9 + #define E0_AUTO_FAN_PIN PinH6 #endif #include "pins_RAMPS_13.h" // ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index 1156804b7c0e..8c8f7556b123 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -23,6 +23,7 @@ /** * Arduino Mega with RAMPS v1.4 for Anycubic + * ATmega2560 */ #define BOARD_INFO_NAME "Anycubic RAMPS 1.4" @@ -31,23 +32,23 @@ // Servos // #if MB(TRIGORILLA_14_11) - #define SERVO0_PIN 5 - #define SERVO1_PIN 4 - #define SERVO2_PIN 11 - #define SERVO3_PIN 6 + #define SERVO0_PIN PinE3 + #define SERVO1_PIN PinG5 + #define SERVO2_PIN PinB5 + #define SERVO3_PIN PinH3 #endif // // PWM FETS // -#define MOSFET_B_PIN 45 // HEATER1 +#define MOSFET_B_PIN PinL4 // HEATER1 // // Heaters / Fans // -#define FAN_PIN 9 // FAN0 -#define FAN1_PIN 7 // FAN1 -#define FAN2_PIN 44 // FAN2 +#define FAN_PIN PinH6 // FAN0 +#define FAN1_PIN PinH4 // FAN1 +#define FAN2_PIN PinL5 // FAN2 #ifndef E0_AUTO_FAN_PIN #define E0_AUTO_FAN_PIN FAN2_PIN #endif @@ -65,52 +66,52 @@ // //#define ANYCUBIC_4_MAX_PRO_ENDSTOPS #if ENABLED(ANYCUBIC_4_MAX_PRO_ENDSTOPS) - #define X_MAX_PIN 43 - #define Y_STOP_PIN 19 + #define X_MAX_PIN PinL6 + #define Y_STOP_PIN PinD2 #elif EITHER(TRIGORILLA_MAPPING_CHIRON, TRIGORILLA_MAPPING_I3MEGA) // Chiron uses AUX header for Y and Z endstops - #define Y_STOP_PIN 42 // AUX - #define Z_STOP_PIN 43 // AUX - #define Z2_MIN_PIN 18 // Z- + #define Y_STOP_PIN PinL7 // AUX + #define Z_STOP_PIN PinL6 // AUX + #define Z2_MIN_PIN PinD3 // Z- #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 2 + #define Z_MIN_PROBE_PIN PinE4 #endif #define CONTROLLER_FAN_PIN FAN1_PIN #if ENABLED(POWER_LOSS_RECOVERY) - #define OUTAGETEST_PIN 79 - #define OUTAGECON_PIN 58 + #define OUTAGETEST_PIN PinE6 + #define OUTAGECON_PIN PinF4 #endif #if ENABLED(TRIGORILLA_MAPPING_CHIRON) #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 33 + #define FIL_RUNOUT_PIN PinC4 #endif // Chiron swaps the Z stepper connections - #define Z_STEP_PIN 36 - #define Z_DIR_PIN 34 - #define Z_ENABLE_PIN 30 - #define Z_CS_PIN 44 + #define Z_STEP_PIN PinC1 + #define Z_DIR_PIN PinC3 + #define Z_ENABLE_PIN PinC7 + #define Z_CS_PIN PinL5 - #define Z2_STEP_PIN 46 - #define Z2_DIR_PIN 48 - #define Z2_ENABLE_PIN 62 - #define Z2_CS_PIN 40 + #define Z2_STEP_PIN PinL3 + #define Z2_DIR_PIN PinL1 + #define Z2_ENABLE_PIN PinK0 + #define Z2_CS_PIN PinG1 #define HEATER_BED_PIN MOSFET_B_PIN // HEATER1 #else #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 19 + #define FIL_RUNOUT_PIN PinD2 #endif #endif #endif #if EITHER(ANYCUBIC_LCD_CHIRON, ANYCUBIC_LCD_I3MEGA) - #define BEEPER_PIN 31 - #define SD_DETECT_PIN 49 + #define BEEPER_PIN PinC6 + #define SD_DETECT_PIN PinL0 #endif #if HAS_TMC_UART @@ -139,25 +140,25 @@ // LCD Display output pins #if BOTH(IS_NEWPANEL, PANEL_ONE) #undef LCD_PINS_D6 - #define LCD_PINS_D6 57 + #define LCD_PINS_D6 PinF3 #endif // LCD Display input pins #if IS_NEWPANEL #if EITHER(VIKI2, miniVIKI) #undef DOGLCD_A0 - #define DOGLCD_A0 23 + #define DOGLCD_A0 PinA1 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #undef BEEPER_PIN - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 #undef LCD_BACKLIGHT_PIN - #define LCD_BACKLIGHT_PIN 67 + #define LCD_BACKLIGHT_PIN PinK5 #endif #elif ENABLED(MINIPANEL) #undef BEEPER_PIN - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 #undef DOGLCD_A0 - #define DOGLCD_A0 42 + #define DOGLCD_A0 PinL7 #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h index 04c6af67b002..ba1b4b837873 100644 --- a/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h +++ b/Marlin/src/pins/ramps/pins_TRONXY_V3_1_0.h @@ -23,6 +23,7 @@ /** * Arduino Mega for Tronxy X5S-2E, etc. + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -37,7 +38,7 @@ // // Servos // -#define SERVO1_PIN 12 // 2560 PIN 25/PB6 +#define SERVO1_PIN PinB6 // 2560 PIN 25/PB6 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index ea670be0d91e..9a0bf5ee7e92 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -21,6 +21,8 @@ */ #pragma once +// ATmega2560 + #include "env_validate.h" #if HOTENDS > 5 || E_STEPPERS > 5 @@ -33,20 +35,20 @@ // // Servos // -#define SERVO0_PIN 11 -#define SERVO1_PIN 12 -#define SERVO2_PIN 5 -#define SERVO3_PIN 4 +#define SERVO0_PIN PinB5 +#define SERVO1_PIN PinB6 +#define SERVO2_PIN PinE3 +#define SERVO3_PIN PinG5 // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) @@ -58,44 +60,44 @@ // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 -#define X_CS_PIN 57 - -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 -#define Y_CS_PIN 58 - -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 -#define Z_CS_PIN 53 - -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 -#define E0_CS_PIN 49 - -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 +#define X_CS_PIN PinF3 + +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 +#define Y_CS_PIN PinF4 + +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 +#define Z_CS_PIN PinB0 + +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 +#define E0_CS_PIN PinL0 + +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #define E1_CS_PIN E0_CS_PIN -#define E2_STEP_PIN 63 -#define E2_DIR_PIN 22 -#define E2_ENABLE_PIN 59 +#define E2_STEP_PIN PinK1 +#define E2_DIR_PIN PinA0 +#define E2_ENABLE_PIN PinF5 #define E2_CS_PIN E0_CS_PIN -#define E3_STEP_PIN 32 -#define E3_DIR_PIN 40 -#define E3_ENABLE_PIN 39 +#define E3_STEP_PIN PinC5 +#define E3_DIR_PIN PinG1 +#define E3_ENABLE_PIN PinG2 #define E3_CS_PIN E0_CS_PIN -#define E4_STEP_PIN 43 -#define E4_DIR_PIN 42 -#define E4_ENABLE_PIN 47 +#define E4_STEP_PIN PinL6 +#define E4_DIR_PIN PinL7 +#define E4_ENABLE_PIN PinL2 #define E4_CS_PIN E0_CS_PIN #if HAS_TMC_UART @@ -151,64 +153,64 @@ // Default pins for TMC SPI // //#ifndef TMC_SPI_MOSI -// #define TMC_SPI_MOSI 66 +// #define TMC_SPI_MOSI PinK4 //#endif //#ifndef TMC_SPI_MISO -// #define TMC_SPI_MISO 44 +// #define TMC_SPI_MISO PinL5 //#endif //#ifndef TMC_SPI_SCK -// #define TMC_SPI_SCK 64 +// #define TMC_SPI_SCK PinK2 //#endif // // Temperature Sensors // -#define TEMP_0_PIN 13 -#define TEMP_1_PIN 15 -#define TEMP_2_PIN 10 -#define TEMP_3_PIN 11 -#define TEMP_BED_PIN 14 +#define TEMP_0_PIN PinB7 +#define TEMP_1_PIN PinJ0 +#define TEMP_2_PIN PinB4 +#define TEMP_3_PIN PinB5 +#define TEMP_BED_PIN PinJ1 #if TEMP_SENSOR_CHAMBER > 0 - #define TEMP_CHAMBER_PIN 12 + #define TEMP_CHAMBER_PIN PinB6 #else - #define TEMP_4_PIN 12 + #define TEMP_4_PIN PinB6 #endif // SPI for MAX Thermocouple //#if DISABLED(SDSUPPORT) -// #define TEMP_0_CS_PIN 66 // Don't use 53 if using Display/SD card +// #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card //#else -// #define TEMP_0_CS_PIN 66 // Don't use 49 (SD_DETECT_PIN) +// #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) //#endif // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 44 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinL5 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 9 +#define FAN_PIN PinH6 #if EXTRUDERS >= 5 - #define HEATER_4_PIN 6 + #define HEATER_4_PIN PinH3 #else - #define FAN1_PIN 6 + #define FAN1_PIN PinH3 #endif #if EXTRUDERS >= 4 - #define HEATER_3_PIN 45 + #define HEATER_3_PIN PinL4 #else - #define FAN2_PIN 45 + #define FAN2_PIN PinL4 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 //#ifndef FILWIDTH_PIN // #define FILWIDTH_PIN 5 // Analog Input @@ -218,7 +220,7 @@ //#define FIL_RUNOUT_PIN SERVO3_PIN #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN PinB6 #endif // @@ -226,13 +228,13 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #endif #endif @@ -241,9 +243,9 @@ // #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) #if !NUM_SERVOS // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -252,13 +254,13 @@ // #if 0 && HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN 58 // Y_CS_PIN + #define E_MUX0_PIN PinF4 // Y_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN 53 // Z_CS_PIN + #define E_MUX1_PIN PinB0 // Z_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN 49 // En_CS_PIN + #define E_MUX2_PIN PinL0 // En_CS_PIN #endif #endif @@ -273,63 +275,63 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS PinL0 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinB2 // SID (MOSI) + #define LCD_PINS_D4 PinB1 // SCK (CLK) clock #elif BOTH(IS_NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 65 - #define LCD_PINS_D5 66 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 64 + #define LCD_PINS_RS PinG1 + #define LCD_PINS_ENABLE PinL7 + #define LCD_PINS_D4 PinK3 + #define LCD_PINS_D5 PinK4 + #define LCD_PINS_D6 PinL5 + #define LCD_PINS_D7 PinK2 #elif ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS 64 - #define LCD_PINS_ENABLE 44 - #define LCD_PINS_D4 63 - #define LCD_PINS_D5 40 - #define LCD_PINS_D6 42 - #define LCD_PINS_D7 65 - #define ADC_KEYPAD_PIN 12 + #define LCD_PINS_RS PinK2 + #define LCD_PINS_ENABLE PinL5 + #define LCD_PINS_D4 PinK1 + #define LCD_PINS_D5 PinG1 + #define LCD_PINS_D6 PinL7 + #define LCD_PINS_D7 PinK3 + #define ADC_KEYPAD_PIN PinB6 #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 25 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinA3 #if !IS_NEWPANEL - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 #endif #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC 25 // Set as output on init - #define LCD_PINS_RS 27 // Pull low for 1s to init + #define LCD_PINS_DC PinA3 // Set as output on init + #define LCD_PINS_RS PinA5 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS 16 - #define DOGLCD_MOSI 17 - #define DOGLCD_SCK 23 + #define DOGLCD_CS PinH1 + #define DOGLCD_MOSI PinH0 + #define DOGLCD_SCK PinA1 #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 #endif - #define LCD_PINS_D7 29 + #define LCD_PINS_D7 PinA7 #if !IS_NEWPANEL - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 #endif #endif @@ -337,10 +339,10 @@ #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK_PIN 38 - //#define SHIFT_LD_PIN 42 - //#define SHIFT_OUT_PIN 40 - //#define SHIFT_EN_PIN 17 + //#define SHIFT_CLK_PIN PinD7 + //#define SHIFT_LD_PIN PinL7 + //#define SHIFT_OUT_PIN PinG1 + //#define SHIFT_EN_PIN PinH0 #endif #endif @@ -356,118 +358,118 @@ #if IS_RRD_SC - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 17 - #define BTN_EN2 23 + #define BTN_EN1 PinH0 + #define BTN_EN2 PinA1 #else - #define BTN_EN1 31 - #define BTN_EN2 33 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 #endif - #define BTN_ENC 35 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN 39 + #define LCD_BACKLIGHT_PIN PinG2 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + #define BTN_EN1 PinK2 + #define BTN_EN2 PinF5 + #define BTN_ENC PinK1 + #define SD_DETECT_PIN PinL7 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - //#define KILL_PIN 41 + #define BTN_EN1 PinL2 + #define BTN_EN2 PinL6 + #define BTN_ENC PinC5 + #define LCD_SDSS PinB0 + //#define KILL_PIN PinG0 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 PinA0 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 PinH4 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + #define LCD_SDSS PinB0 + #define SD_DETECT_PIN PinL0 #elif EITHER(VIKI2, miniVIKI) - #define DOGLCD_CS 45 - #define DOGLCD_A0 44 + #define DOGLCD_CS PinL4 + #define DOGLCD_A0 PinL5 - #define BEEPER_PIN 33 - #define STAT_LED_RED_PIN 32 - #define STAT_LED_BLUE_PIN 35 + #define BEEPER_PIN PinC4 + #define STAT_LED_RED_PIN PinC5 + #define STAT_LED_BLUE_PIN PinC2 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 PinA0 + #define BTN_EN2 PinH4 + #define BTN_ENC PinG2 - #define SDSS 53 + #define SDSS PinB0 #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - //#define KILL_PIN 31 + //#define KILL_PIN PinC6 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define DOGLCD_CS PinA7 + #define DOGLCD_A0 PinA5 - #define BEEPER_PIN 23 - #define LCD_BACKLIGHT_PIN 33 + #define BEEPER_PIN PinA1 + #define LCD_BACKLIGHT_PIN PinC4 - #define BTN_EN1 35 - #define BTN_EN2 37 - #define BTN_ENC 31 + #define BTN_EN1 PinC2 + #define BTN_EN2 PinC0 + #define BTN_ENC PinC6 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define LCD_SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 27 - #define DOGLCD_CS 25 + #define DOGLCD_A0 PinA5 + #define DOGLCD_CS PinA3 - #define BEEPER_PIN 37 + #define BEEPER_PIN PinC0 - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - //#define SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 64 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + //#define SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinK2 //#define LCD_CONTRAST_INIT 190 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN PinL7 // not connected to a pin - #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 + #define DOGLCD_A0 PinL5 + #define DOGLCD_CS PinK4 - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinK1 + #define BTN_ENC PinF5 - #define SDSS 53 - #define SD_DETECT_PIN 49 - //#define KILL_PIN 64 + #define SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinK2 //#define LCD_CONTRAST_INIT 190 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -475,29 +477,29 @@ #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 // Buttons are directly attached to AUX-2 #if IS_RRW_KEYPAD - #define SHIFT_OUT_PIN 40 - #define SHIFT_CLK_PIN 44 - #define SHIFT_LD_PIN 42 - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_CLK_PIN PinL5 + #define SHIFT_LD_PIN PinL7 + #define BTN_EN1 PinK2 + #define BTN_EN2 PinF5 + #define BTN_ENC PinK1 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 PinF5 // AUX2 PIN 3 + #define BTN_EN2 PinK1 // AUX2 PIN 4 + #define BTN_ENC PinL0 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 + #define BTN_EN1 PinC0 + #define BTN_EN2 PinC2 + #define BTN_ENC PinC6 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - //#define KILL_PIN 41 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 0b15cd35ade9..0e8147a314cd 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -23,6 +23,7 @@ /** * Ultiboard v2.0 pin assignments + * ATmega2560 */ /** @@ -43,36 +44,36 @@ // // Limit Switches // -#define X_STOP_PIN 22 -#define Y_STOP_PIN 26 -#define Z_STOP_PIN 29 +#define X_STOP_PIN PinA0 +#define Y_STOP_PIN PinA4 +#define Z_STOP_PIN PinA7 // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 32 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 31 +#define Y_STEP_PIN PinC5 +#define Y_DIR_PIN PinC3 +#define Y_ENABLE_PIN PinC6 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 36 -#define Z_ENABLE_PIN 34 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinC1 +#define Z_ENABLE_PIN PinC3 -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 +#define E0_STEP_PIN PinL7 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinC0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 -#define MOTOR_CURRENT_PWM_XY_PIN 44 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 46 +#define MOTOR_CURRENT_PWM_XY_PIN PinL5 +#define MOTOR_CURRENT_PWM_Z_PIN PinL4 +#define MOTOR_CURRENT_PWM_E_PIN PinL3 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE #define MOTOR_CURRENT_PWM_RANGE 2000 @@ -82,60 +83,60 @@ // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +#define TEMP_1_PIN PinH6 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN PinH4 #endif #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 77 + #define E0_AUTO_FAN_PIN PinJ6 #endif // // Misc. Functions // -#define SDSS 53 -#define SD_DETECT_PIN 39 -#define LED_PIN 8 -//#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered -//#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. +#define SDSS PinB0 +#define SD_DETECT_PIN PinG2 +#define LED_PIN PinH5 +//#define SAFETY_TRIGGERED_PIN PinA6 // PIN to detect the safety circuit has triggered +//#define MAIN_VOLTAGE_MEASURE_PIN PinJ1 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. // // LCD / Controller // -#define BEEPER_PIN 18 +#define BEEPER_PIN PinD3 -#define LCD_PINS_RS 20 -#define LCD_PINS_ENABLE 15 -#define LCD_PINS_D4 14 -#define LCD_PINS_D5 21 -#define LCD_PINS_D6 5 -#define LCD_PINS_D7 6 +#define LCD_PINS_RS PinD1 +#define LCD_PINS_ENABLE PinJ0 +#define LCD_PINS_D4 PinJ1 +#define LCD_PINS_D5 PinD0 +#define LCD_PINS_D6 PinE3 +#define LCD_PINS_D7 PinH3 // Buttons are directly attached -#define BTN_EN1 40 -#define BTN_EN2 41 -#define BTN_ENC 19 +#define BTN_EN1 PinG1 +#define BTN_EN2 PinG0 +#define BTN_ENC PinD2 // // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER // use the LED_PIN for spindle speed control or case light #undef LED_PIN - #define SPINDLE_DIR_PIN 16 - #define SPINDLE_LASER_ENA_PIN 17 // Pullup! - #define SPINDLE_LASER_PWM_PIN 8 // Hardware PWM + #define SPINDLE_DIR_PIN PinH1 + #define SPINDLE_LASER_ENA_PIN PinH0 // Pullup! + #define SPINDLE_LASER_PWM_PIN PinH5 // Hardware PWM #else #undef LED_PIN - #define CASE_LIGHT_PIN 8 + #define CASE_LIGHT_PIN PinH5 #endif diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index 0bc04d962aaf..8bc85da0c9de 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -23,6 +23,7 @@ /** * Ultimaker pin assignments + * ATmega2560, ATmega1280 */ /** @@ -42,76 +43,76 @@ // // Servos // -#define SERVO0_PIN 11 +#define SERVO0_PIN PinB5 // // Limit Switches // -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN 32 +#define X_MIN_PIN PinA0 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinA4 +#define Y_MAX_PIN PinA6 +#define Z_MIN_PIN PinC7 +#define Z_MAX_PIN PinC5 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN PinC0 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinC2 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN PinL6 +#define E0_DIR_PIN PinL4 +#define E0_ENABLE_PIN PinG0 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 9 // Analog Input -#define TEMP_BED_PIN 10 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +#define TEMP_1_PIN PinH6 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 7 + #define FAN_PIN PinH4 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 +#define SUICIDE_PIN PinF0 // PIN that has to be turned on right after start, to keep power flowing. #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 8 + #define CASE_LIGHT_PIN PinH5 #endif // @@ -119,38 +120,38 @@ // #if HAS_WIRED_LCD - #define BEEPER_PIN 18 + #define BEEPER_PIN PinD3 #if IS_NEWPANEL - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinH1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 // Buttons directly attached - #define BTN_EN1 40 - #define BTN_EN2 42 - #define BTN_ENC 19 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinL7 + #define BTN_ENC PinD2 - #define SD_DETECT_PIN 38 + #define SD_DETECT_PIN PinD7 #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define SHIFT_CLK_PIN PinD7 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinH3 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinD1 + #define LCD_PINS_D7 PinD2 #define SD_DETECT_PIN -1 @@ -161,6 +162,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 10 // Pullup! -#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header +#define SPINDLE_LASER_PWM_PIN PinH6 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinB4 // Pullup! +#define SPINDLE_DIR_PIN PinB5 // use the EXP3 PWM header diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index 146c519ff962..f9f57b46893f 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -23,6 +23,7 @@ /** * Ultimaker pin assignments (Old electronics) + * ATmega2560, ATmega1280 */ /** @@ -78,36 +79,36 @@ // Limit Switches // #if ENABLED(BOARD_REV_1_1_TO_1_3) - #define X_MIN_PIN 15 // SW1 - #define X_MAX_PIN 14 // SW2 - #define Y_MIN_PIN 17 // SW3 - #define Y_MAX_PIN 16 // SW4 - #define Z_MIN_PIN 19 // SW5 - #define Z_MAX_PIN 18 // SW6 + #define X_MIN_PIN PinJ0 // SW1 + #define X_MAX_PIN PinJ1 // SW2 + #define Y_MIN_PIN PinH0 // SW3 + #define Y_MAX_PIN PinH1 // SW4 + #define Z_MIN_PIN PinD2 // SW5 + #define Z_MAX_PIN PinD3 // SW6 #endif #if ENABLED(BOARD_REV_1_0) #if HAS_CUTTER - #define X_STOP_PIN 13 // SW1 (didn't change) - also has a useable hardware PWM - #define Y_STOP_PIN 12 // SW2 - #define Z_STOP_PIN 11 // SW3 + #define X_STOP_PIN PinB7 // SW1 (didn't change) - also has a useable hardware PWM + #define Y_STOP_PIN PinB6 // SW2 + #define Z_STOP_PIN PinB5 // SW3 #else - #define X_MIN_PIN 13 // SW1 - #define X_MAX_PIN 12 // SW2 - #define Y_MIN_PIN 11 // SW3 - #define Y_MAX_PIN 10 // SW4 - #define Z_MIN_PIN 9 // SW5 - #define Z_MAX_PIN 8 // SW6 + #define X_MIN_PIN PinB7 // SW1 + #define X_MAX_PIN PinB6 // SW2 + #define Y_MIN_PIN PinB5 // SW3 + #define Y_MAX_PIN PinB4 // SW4 + #define Z_MIN_PIN PinH6 // SW5 + #define Z_MAX_PIN PinH5 // SW6 #endif #endif #if ENABLED(BOARD_REV_1_5) - #define X_MIN_PIN 22 - #define X_MAX_PIN 24 - #define Y_MIN_PIN 26 - #define Y_MAX_PIN 28 - #define Z_MIN_PIN 30 - #define Z_MAX_PIN 32 + #define X_MIN_PIN PinA0 + #define X_MAX_PIN PinA2 + #define Y_MIN_PIN PinA4 + #define Y_MAX_PIN PinA6 + #define Z_MIN_PIN PinC7 + #define Z_MAX_PIN PinC5 #endif // @@ -120,92 +121,92 @@ // // Steppers // -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_ENABLE_PIN 27 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 29 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_ENABLE_PIN 35 +#define Z_STEP_PIN PinC0 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinC2 #if BOTH(HAS_CUTTER, BOARD_REV_1_1_TO_1_3) && EXTRUDERS == 1 // Move E0 to the spare and get Spindle/Laser signals from E0 - #define E0_STEP_PIN 49 - #define E0_DIR_PIN 47 - #define E0_ENABLE_PIN 48 + #define E0_STEP_PIN PinL0 + #define E0_DIR_PIN PinL2 + #define E0_ENABLE_PIN PinL1 #else - #define E0_STEP_PIN 43 - #define E0_DIR_PIN 45 - #define E0_ENABLE_PIN 41 + #define E0_STEP_PIN PinL6 + #define E0_DIR_PIN PinL4 + #define E0_ENABLE_PIN PinG0 - #define E1_STEP_PIN 49 - #define E1_DIR_PIN 47 - #define E1_ENABLE_PIN 48 + #define E1_STEP_PIN PinL0 + #define E1_DIR_PIN PinL2 + #define E1_ENABLE_PIN PinL1 #endif // // Temperature Sensors // -#define TEMP_0_PIN 8 // Analog Input -#define TEMP_1_PIN 1 // Analog Input +#define TEMP_0_PIN PinH5 // Analog Input +#define TEMP_1_PIN PinE1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 2 -//#define HEATER_1_PIN 3 // used for case light Rev A said "1" -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE4 +//#define HEATER_1_PIN PinE5 // used for case light Rev A said "1" +#define HEATER_BED_PIN PinG5 // // LCD / Controller // #if EITHER(BOARD_REV_1_0, BOARD_REV_1_1_TO_1_3) - #define LCD_PINS_RS 24 - #define LCD_PINS_ENABLE 22 - #define LCD_PINS_D4 36 - #define LCD_PINS_D5 34 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 30 + #define LCD_PINS_RS PinA2 + #define LCD_PINS_ENABLE PinA0 + #define LCD_PINS_D4 PinC1 + #define LCD_PINS_D5 PinC3 + #define LCD_PINS_D6 PinC5 + #define LCD_PINS_D7 PinC7 #elif BOTH(BOARD_REV_1_5, HAS_WIRED_LCD) - #define BEEPER_PIN 18 + #define BEEPER_PIN PinD3 #if IS_NEWPANEL - #define LCD_PINS_RS 20 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 16 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 6 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinH1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 // Buttons directly attached - #define BTN_EN1 40 - #define BTN_EN2 42 - #define BTN_ENC 19 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinL7 + #define BTN_ENC PinD2 - #define SD_DETECT_PIN 38 + #define SD_DETECT_PIN PinD7 #else // !IS_NEWPANEL - Old style panel with shift register // Buttons attached to a shift register - #define SHIFT_CLK_PIN 38 - #define SHIFT_LD_PIN 42 - #define SHIFT_OUT_PIN 40 - #define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 6 - #define LCD_PINS_D5 21 - #define LCD_PINS_D6 20 - #define LCD_PINS_D7 19 + #define SHIFT_CLK_PIN PinD7 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinH3 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinD1 + #define LCD_PINS_D7 PinD2 #endif // !IS_NEWPANEL @@ -215,7 +216,7 @@ // case light - see spindle section for more info on available hardware PWMs // #if !PIN_EXISTS(CASE_LIGHT) && ENABLED(BOARD_REV_1_5) - #define CASE_LIGHT_PIN 7 // use PWM - MUST BE HARDWARE PWM + #define CASE_LIGHT_PIN PinH4 // use PWM - MUST BE HARDWARE PWM #endif // @@ -223,9 +224,9 @@ // #if HAS_CUTTER #if EITHER(BOARD_REV_1_0, BOARD_REV_1_5) // Use the last three SW positions - #define SPINDLE_DIR_PIN 10 // 1.0: SW4 1.5: EXP3-6 ("10") - #define SPINDLE_LASER_PWM_PIN 9 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM - #define SPINDLE_LASER_ENA_PIN 8 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! + #define SPINDLE_DIR_PIN PinB4 // 1.0: SW4 1.5: EXP3-6 ("10") + #define SPINDLE_LASER_PWM_PIN PinH6 // 1.0: SW5 1.5: EXP3-7 ( "9") .. MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENA_PIN PinH5 // 1.0: SW6 1.5: EXP3-8 ( "8") .. Pin should have a pullup! #elif ENABLED(BOARD_REV_1_1_TO_1_3) /** * Only four hardware PWMs physically connected to anything on these boards: @@ -239,14 +240,14 @@ * They have an LED and resistor pullup to +24V which could damage 3.3V-5V ICs. */ #if EXTRUDERS == 1 - #define SPINDLE_DIR_PIN 43 - #define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 41 // Pullup! + #define SPINDLE_DIR_PIN PinL6 + #define SPINDLE_LASER_PWM_PIN PinL4 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinG0 // Pullup! #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available #undef HEATER_BED_PIN - #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - Special precautions usually needed. - #define SPINDLE_LASER_ENA_PIN 40 // Pullup! (Probably pin 6 on the 10-pin + #define SPINDLE_DIR_PIN PinD7 // Probably pin 4 on 10 pin connector closest to the E0 socket + #define SPINDLE_LASER_PWM_PIN PinG5 // Hardware PWM - Special precautions usually needed. + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup! (Probably pin 6 on the 10-pin // connector closest to the E0 socket) #endif #endif diff --git a/Marlin/src/pins/ramps/pins_VORON.h b/Marlin/src/pins/ramps/pins_VORON.h index 93903810104f..91e7290ac65b 100644 --- a/Marlin/src/pins/ramps/pins_VORON.h +++ b/Marlin/src/pins/ramps/pins_VORON.h @@ -24,11 +24,12 @@ /** * VORON Design v2 pin assignments * See https://github.com/mzbotreprap/VORON/blob/master/Firmware/Marlin/pins_RAMPS_VORON.h + * ATmega2560 */ #define BOARD_INFO_NAME "VORON Design v2" -#define MOSFET_C_PIN 11 +#define MOSFET_C_PIN PinB5 #include "pins_RAMPS.h" @@ -36,17 +37,17 @@ // Heaters / Fans // #undef FAN_PIN -#define FAN_PIN 5 // Using the pin for the controller fan since controller fan is always on. -#define CONTROLLER_FAN_PIN 8 +#define FAN_PIN PinE3 // Using the pin for the controller fan since controller fan is always on. +#define CONTROLLER_FAN_PIN PinH5 // // Auto fans // #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan + #define E0_AUTO_FAN_PIN PinH3 // Servo pin 6 for E3D Fan #endif #ifndef E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN 6 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) + #define E1_AUTO_FAN_PIN PinH3 // Servo pin 6 for E3D Fan (same pin for both extruders since it's the same fan) #endif // diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 3078b9f77bbe..e2d3d3d350ac 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -24,6 +24,7 @@ /** * ZRIB V2.0 & V3.0 pin assignments * V2 and V3 Boards only differ in USB controller, nothing affecting the pins. + * ATmega2560, ATmega1280 */ #include "pins_MKS_GEN_13.h" // ... RAMPS @@ -32,20 +33,20 @@ // Auto fans // #ifndef E0_AUTO_FAN_PIN - #define E0_AUTO_FAN_PIN 6 // Fan + #define E0_AUTO_FAN_PIN PinH3 // Fan #endif #ifndef E1_AUTO_FAN_PIN - #define E1_AUTO_FAN_PIN 6 + #define E1_AUTO_FAN_PIN PinH3 #endif #ifndef E2_AUTO_FAN_PIN - #define E2_AUTO_FAN_PIN 6 + #define E2_AUTO_FAN_PIN PinH3 #endif #ifndef E3_AUTO_FAN_PIN - #define E3_AUTO_FAN_PIN 6 + #define E3_AUTO_FAN_PIN PinH3 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 11 // Analog Input + #define FILWIDTH_PIN PinB5 // Analog Input #endif #if ENABLED(ZONESTAR_LCD) @@ -65,12 +66,12 @@ #undef BTN_EN2 #undef BTN_ENC - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 - #define ADC_KEYPAD_PIN 10 // Analog Input - #define BEEPER_PIN 37 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 + #define ADC_KEYPAD_PIN PinB4 // Analog Input + #define BEEPER_PIN PinC0 #endif diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V52.h b/Marlin/src/pins/ramps/pins_ZRIB_V52.h index 44e0beaa9fb9..8cd380cadeb4 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V52.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V52.h @@ -23,6 +23,7 @@ /** * ZRIB V5.2 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * ATmega2560, ATmega1280 */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -36,25 +37,25 @@ // // Heaters / Fans // -#define HEATER_1_PIN 7 -#define FAN_PIN 9 // PH6 ** Pin18 ** PWM9 -#define FAN1_PIN 6 +#define HEATER_1_PIN PinH4 +#define FAN_PIN PinH6 // PH6 ** Pin18 ** PWM9 +#define FAN1_PIN PinH3 // // Extra Extruder / Stepper for V5.2 // -#define E2_STEP_PIN 4 -#define E2_DIR_PIN 5 -#define E2_ENABLE_PIN 22 +#define E2_STEP_PIN PinG5 +#define E2_DIR_PIN PinE3 +#define E2_ENABLE_PIN PinA0 // // Servos / XS3 Connector // #ifndef SERVO0_PIN - #define SERVO0_PIN 65 // PWM + #define SERVO0_PIN PinK3 // PWM #endif #ifndef SERVO1_PIN - #define SERVO1_PIN 66 // PWM + #define SERVO1_PIN PinK4 // PWM #endif #include "pins_MKS_BASE_common.h" // ... RAMPS diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 7a5cf1479166..2c1cc9fd885c 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -23,6 +23,7 @@ /** * ZRIB V5.3 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * ATmega2560, ATmega1280 */ #include "env_validate.h" @@ -38,34 +39,34 @@ // // PIN 12 Connector // -#define PIN_12_PIN 12 +#define PIN_12_PIN PinB6 // // XS1 Connector // -#define XS1_01_PIN 42 -#define XS1_03_PIN 43 -#define XS1_05_PIN 44 -#define XS1_07_PIN 45 -#define XS1_08_PIN 47 +#define XS1_01_PIN PinL7 +#define XS1_03_PIN PinL6 +#define XS1_05_PIN PinL5 +#define XS1_07_PIN PinL4 +#define XS1_08_PIN PinL2 // // XS6 Connector // -#define XS6_01_PIN 20 -#define XS6_03_PIN 52 -#define XS6_05_PIN 51 -#define XS6_07_PIN 50 -#define XS6_08_PIN 21 +#define XS6_01_PIN PinD1 +#define XS6_03_PIN PinB1 +#define XS6_05_PIN PinB2 +#define XS6_07_PIN PinB3 +#define XS6_08_PIN PinD0 // // Servos / XS3 Connector // #ifndef SERVO0_PIN - #define SERVO0_PIN 65 // PWM + #define SERVO0_PIN PinK3 // PWM #endif #ifndef SERVO1_PIN - #define SERVO1_PIN 66 // PWM + #define SERVO1_PIN PinK4 // PWM #endif // @@ -73,26 +74,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN 3 + #define X_MIN_PIN PinE5 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN 14 + #define Y_MIN_PIN PinJ1 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN 15 + #define Y_MAX_PIN PinJ0 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN 18 + #define Z_MIN_PIN PinD3 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN 19 + #define Z_MAX_PIN PinD2 #endif #endif @@ -100,81 +101,81 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #if NUM_Z_STEPPERS == 2 - #define Z2_STEP_PIN 26 // E0 connector - #define Z2_DIR_PIN 28 - #define Z2_ENABLE_PIN 24 + #define Z2_STEP_PIN PinA4 // E0 connector + #define Z2_DIR_PIN PinA6 + #define Z2_ENABLE_PIN PinA2 - #define E0_STEP_PIN 36 // E1 connector - #define E0_DIR_PIN 34 - #define E0_ENABLE_PIN 30 + #define E0_STEP_PIN PinC1 // E1 connector + #define E0_DIR_PIN PinC3 + #define E0_ENABLE_PIN PinC7 - #define E1_STEP_PIN 4 // E2 connector - #define E1_DIR_PIN 5 - #define E1_ENABLE_PIN 22 + #define E1_STEP_PIN PinG5 // E2 connector + #define E1_DIR_PIN PinE3 + #define E1_ENABLE_PIN PinA0 #else - #define E0_STEP_PIN 26 - #define E0_DIR_PIN 28 - #define E0_ENABLE_PIN 24 + #define E0_STEP_PIN PinA4 + #define E0_DIR_PIN PinA6 + #define E0_ENABLE_PIN PinA2 - #define E1_STEP_PIN 36 - #define E1_DIR_PIN 34 - #define E1_ENABLE_PIN 30 + #define E1_STEP_PIN PinC1 + #define E1_DIR_PIN PinC3 + #define E1_ENABLE_PIN PinC7 - #define E2_STEP_PIN 4 - #define E2_DIR_PIN 5 - #define E2_ENABLE_PIN 22 + #define E2_STEP_PIN PinG5 + #define E2_DIR_PIN PinE3 + #define E2_ENABLE_PIN PinA0 #endif // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN 13 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN 15 // Analog Input + #define TEMP_1_PIN PinJ0 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN 14 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // Heaters / Fans Connectors // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define FAN_PIN 9 -#define HEATER_BED_PIN 8 -#define FAN1_PIN 6 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define FAN_PIN PinH6 +#define HEATER_BED_PIN PinH5 +#define FAN1_PIN PinH3 // // Misc. Functions // #ifndef SDSS - #define SDSS 53 + #define SDSS PinB0 #endif -#define LED_PIN 13 +#define LED_PIN PinB7 #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN XS1_01_PIN @@ -309,23 +310,23 @@ */ #ifndef EXP1_08_PIN - #define EXP1_01_PIN 37 - #define EXP1_02_PIN 35 - #define EXP1_03_PIN 17 - #define EXP1_04_PIN 16 - #define EXP1_05_PIN 23 - #define EXP1_06_PIN 25 - #define EXP1_07_PIN 27 - #define EXP1_08_PIN 29 + #define EXP1_01_PIN PinC0 + #define EXP1_02_PIN PinC2 + #define EXP1_03_PIN PinH0 + #define EXP1_04_PIN PinH1 + #define EXP1_05_PIN PinA1 + #define EXP1_06_PIN PinA3 + #define EXP1_07_PIN PinA5 + #define EXP1_08_PIN PinA7 #define EXP2_01_PIN XS6_07_PIN #define EXP2_02_PIN XS6_03_PIN - #define EXP2_03_PIN 31 - #define EXP2_04_PIN 53 - #define EXP2_05_PIN 33 + #define EXP2_03_PIN PinC6 + #define EXP2_04_PIN PinB0 + #define EXP2_05_PIN PinC4 #define EXP2_06_PIN XS6_05_PIN - #define EXP2_07_PIN 49 - #define EXP2_08_PIN 41 + #define EXP2_07_PIN PinL0 + #define EXP2_08_PIN PinG0 #endif ////////////////////////// @@ -334,26 +335,26 @@ #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" - #define LCD_SDSS 16 - #define LCD_PINS_RS 16 // ST7920_CS_PIN LCD_PIN_RS (PIN4 of LCD module) - #define LCD_PINS_ENABLE 23 // ST7920_DAT_PIN LCD_PIN_R/W (PIN5 of LCD module) - #define LCD_PINS_D4 17 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) - #define BTN_EN2 25 - #define BTN_EN1 27 - #define BTN_ENC 29 - #define BEEPER_PIN 37 - #define KILL_PIN 35 + #define LCD_SDSS PinH1 + #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS (PIN4 of LCD module) + #define LCD_PINS_ENABLE PinA1 // ST7920_DAT_PIN LCD_PIN_R/W (PIN5 of LCD module) + #define LCD_PINS_D4 PinH0 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) + #define BTN_EN2 PinA3 + #define BTN_EN1 PinA5 + #define BTN_ENC PinA7 + #define BEEPER_PIN PinC0 + #define KILL_PIN PinC2 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "Reprap LCD12864" // Use EXP1 & EXP2 connector - #define LCD_PINS_RS 16 // ST7920_CS_PIN LCD_PIN_RS - #define LCD_PINS_ENABLE 17 // ST7920_DAT_PIN LCD_PIN_ENABLE - #define LCD_PINS_D4 23 // ST7920_CLK_PIN LCD_PIN_R/W - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 - #define BEEPER_PIN 37 - #define KILL_PIN 41 + #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS + #define LCD_PINS_ENABLE PinH0 // ST7920_DAT_PIN LCD_PIN_ENABLE + #define LCD_PINS_D4 PinA1 // ST7920_CLK_PIN LCD_PIN_R/W + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define BEEPER_PIN PinC0 + #define KILL_PIN PinG0 #endif //================================================================================ @@ -362,21 +363,21 @@ #if EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) #define LCDSCREEN_NAME "ZONESTAR 12864OLED" - #define LCD_SDSS 16 - #define LCD_PINS_RS 23 // RESET Pull low for 1s to init - #define LCD_PINS_DC 17 - #define DOGLCD_CS 16 // CS - #define BTN_EN2 25 - #define BTN_EN1 27 - #define BTN_ENC 29 + #define LCD_SDSS PinH1 + #define LCD_PINS_RS PinA1 // RESET Pull low for 1s to init + #define LCD_PINS_DC PinH0 + #define DOGLCD_CS PinH1 // CS + #define BTN_EN2 PinA3 + #define BTN_EN1 PinA5 + #define BTN_ENC PinA7 #define BEEPER_PIN -1 #define KILL_PIN -1 #if EITHER(OLED_HW_IIC, OLED_HW_SPI) #error "Oops! You must choose SW SPI for ZRIB V53 board and connect the OLED screen to EXP1 connector." #else // SW_SPI #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_MOSI 35 // SDA - #define DOGLCD_SCK 37 // SCK + #define DOGLCD_MOSI PinC2 // SDA + #define DOGLCD_SCK PinC0 // SCK #endif #endif // OLED 128x64 @@ -392,7 +393,7 @@ #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN #define LCD_PINS_D7 EXP1_08_PIN - #define ADC_KEYPAD_PIN 10 // A10 for ADCKEY + #define ADC_KEYPAD_PIN PinB4 // A10 for ADCKEY #define BEEPER_PIN EXP1_01_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index f15d4d7e3f0f..02e2c2a4c23a 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -23,6 +23,7 @@ /** * Z-Bolt X Series board – based on Arduino Mega2560 + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -38,81 +39,81 @@ // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN 11 + #define SERVO0_PIN PinB5 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN 4 + #define SERVO3_PIN PinG5 #endif // // Limit Switches // -#define X_MIN_PIN 3 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN 2 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN #define X_CS_PIN -1 #endif -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN #define Y_CS_PIN -1 #endif -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN #define Z_CS_PIN -1 #endif -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN #define E0_CS_PIN -1 #endif -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN #define E1_CS_PIN -1 #endif // Red -#define E2_STEP_PIN 42 -#define E2_DIR_PIN 40 -#define E2_ENABLE_PIN 65 +#define E2_STEP_PIN PinL7 +#define E2_DIR_PIN PinG1 +#define E2_ENABLE_PIN PinK3 #ifndef E2_CS_PIN #define E2_CS_PIN -1 #endif // Black -#define E3_STEP_PIN 44 -#define E3_DIR_PIN 64 -#define E3_ENABLE_PIN 66 +#define E3_STEP_PIN PinL5 +#define E3_DIR_PIN PinK2 +#define E3_ENABLE_PIN PinK4 #ifndef E3_CS_PIN #define E3_CS_PIN -1 #endif @@ -120,47 +121,47 @@ // // Temperature Sensors // -#define TEMP_0_PIN 13 // Analog Input -#define TEMP_1_PIN 15 // Analog Input -#define TEMP_2_PIN 5 // Analog Input (BLACK) -#define TEMP_3_PIN 9 // Analog Input (RED) -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_2_PIN PinE3 // Analog Input (BLACK) +#define TEMP_3_PIN PinH6 // Analog Input (RED) +#define TEMP_BED_PIN PinJ1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 6 -#define HEATER_3_PIN 5 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinH3 +#define HEATER_3_PIN PinE3 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 9 +#define FAN_PIN PinH6 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 5 // Analog Input on AUX2 + #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 #endif // Оn the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 4 + #define FIL_RUNOUT_PIN PinG5 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN 12 + #define PS_ON_PIN PinB6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN 6 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN 44 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -169,13 +170,13 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM - #define SPINDLE_DIR_PIN 5 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN 40 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // Hardware PWM - #define SPINDLE_DIR_PIN 65 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #endif #endif @@ -183,13 +184,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI 66 + #define TMC_SPI_MOSI PinK4 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO 44 + #define TMC_SPI_MISO PinL5 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK 64 + #define TMC_SPI_SCK PinK2 #endif #if HAS_TMC_UART @@ -212,10 +213,10 @@ //#define E4_HARDWARE_SERIAL Serial1 #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 40 + #define X_SERIAL_TX_PIN PinG1 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 63 + #define X_SERIAL_RX_PIN PinK1 #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 @@ -225,10 +226,10 @@ #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 59 + #define Y_SERIAL_TX_PIN PinF5 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 64 + #define Y_SERIAL_RX_PIN PinK2 #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 @@ -238,10 +239,10 @@ #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 42 + #define Z_SERIAL_TX_PIN PinL7 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 65 + #define Z_SERIAL_RX_PIN PinK3 #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN -1 @@ -251,10 +252,10 @@ #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 44 + #define E0_SERIAL_TX_PIN PinL5 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 66 + #define E0_SERIAL_RX_PIN PinK4 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 From 8dcc5dd16e63b37df224c70db118e1bc7c95fd3c Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 8 Dec 2022 23:13:38 +0100 Subject: [PATCH 32/83] - fixed a typo in the fastio_644.h update - refactored the sanguino 8bit AVR pin headers to use pin names instead of internal numbers --- Marlin/src/HAL/AVR/fastio/fastio_644.h | 52 +----- Marlin/src/pins/sanguino/pins_ANET_10.h | 94 +++++----- .../src/pins/sanguino/pins_GEN3_MONOLITHIC.h | 38 ++-- Marlin/src/pins/sanguino/pins_GEN3_PLUS.h | 42 ++--- Marlin/src/pins/sanguino/pins_GEN6.h | 54 +++--- Marlin/src/pins/sanguino/pins_GEN7_12.h | 70 ++++---- Marlin/src/pins/sanguino/pins_GEN7_14.h | 54 +++--- Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h | 72 ++++---- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 13 +- Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h | 13 +- Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h | 21 +-- Marlin/src/pins/sanguino/pins_OMCA.h | 58 +++--- Marlin/src/pins/sanguino/pins_OMCA_A.h | 42 ++--- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 168 +++++++++--------- Marlin/src/pins/sanguino/pins_SETHI.h | 52 +++--- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 80 ++++----- 16 files changed, 439 insertions(+), 484 deletions(-) diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index bf3bdb76f057..8755016c1dee 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -204,7 +204,7 @@ #define DIO16_WPORT PORTC #define DIO16_DDR DDRC #define DIO16_PWM nullptr -#define PinD0 16 +#define PinC0 16 #define DIO17_PIN PINC1 #define DIO17_RPORT PINC @@ -311,52 +311,4 @@ #define DIO31_PWM nullptr #define PinA0 31 -#define DIO_NUM 32 - -#define AIO0_PIN PINA0 -#define AIO0_RPORT PINA -#define AIO0_WPORT PORTA -#define AIO0_DDR DDRA -#define AIO0_PWM nullptr - -#define AIO1_PIN PINA1 -#define AIO1_RPORT PINA -#define AIO1_WPORT PORTA -#define AIO1_DDR DDRA -#define AIO1_PWM nullptr - -#define AIO2_PIN PINA2 -#define AIO2_RPORT PINA -#define AIO2_WPORT PORTA -#define AIO2_DDR DDRA -#define AIO2_PWM nullptr - -#define AIO3_PIN PINA3 -#define AIO3_RPORT PINA -#define AIO3_WPORT PORTA -#define AIO3_DDR DDRA -#define AIO3_PWM nullptr - -#define AIO4_PIN PINA4 -#define AIO4_RPORT PINA -#define AIO4_WPORT PORTA -#define AIO4_DDR DDRA -#define AIO4_PWM nullptr - -#define AIO5_PIN PINA5 -#define AIO5_RPORT PINA -#define AIO5_WPORT PORTA -#define AIO5_DDR DDRA -#define AIO5_PWM nullptr - -#define AIO6_PIN PINA6 -#define AIO6_RPORT PINA -#define AIO6_WPORT PORTA -#define AIO6_DDR DDRA -#define AIO6_PWM nullptr - -#define AIO7_PIN PINA7 -#define AIO7_RPORT PINA -#define AIO7_WPORT PORTA -#define AIO7_DDR DDRA -#define AIO7_PWM nullptr \ No newline at end of file +#define DIO_NUM 32 \ No newline at end of file diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index bd69e167dc05..fc2dc1e57510 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -111,49 +111,49 @@ // // Limit Switches // -#define X_STOP_PIN 18 -#define Y_STOP_PIN 19 -#define Z_STOP_PIN 20 +#define X_STOP_PIN PinC2 +#define Y_STOP_PIN PinC3 +#define Z_STOP_PIN PinC4 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 21 -#define X_ENABLE_PIN 14 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC5 +#define X_ENABLE_PIN PinD6 -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 -#define Y_ENABLE_PIN 14 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC7 +#define Y_ENABLE_PIN PinD6 -#define Z_STEP_PIN 3 -#define Z_DIR_PIN 2 -#define Z_ENABLE_PIN 26 +#define Z_STEP_PIN PinB3 +#define Z_DIR_PIN PinB2 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN 1 -#define E0_DIR_PIN 0 -#define E0_ENABLE_PIN 14 +#define E0_STEP_PIN PinB1 +#define E0_DIR_PIN PinB0 +#define E0_ENABLE_PIN PinD6 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN 13 // (extruder) -#define HEATER_BED_PIN 12 // (bed) +#define HEATER_0_PIN PinD5 // (extruder) +#define HEATER_BED_PIN PinD4 // (bed) #ifndef FAN_PIN - #define FAN_PIN 4 + #define FAN_PIN PinB4 #endif // // Misc. Functions // -#define SDSS 31 +#define SDSS PinA0 #define LED_PIN -1 /** @@ -167,18 +167,18 @@ #if HAS_WIRED_LCD - #define LCD_SDSS 28 + #define LCD_SDSS PinA3 #if HAS_ADC_BUTTONS - #define SERVO0_PIN 27 // free for BLTouch/3D-Touch - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 - #define ADC_KEYPAD_PIN 1 + #define SERVO0_PIN PinA4 // free for BLTouch/3D-Touch + #define LCD_PINS_RS PinA3 + #define LCD_PINS_ENABLE PinA2 + #define LCD_PINS_D4 PinD2 + #define LCD_PINS_D5 PinD3 + #define LCD_PINS_D6 PinC0 + #define LCD_PINS_D7 PinC1 + #define ADC_KEYPAD_PIN PinB1 #elif IS_RRD_FG_SC @@ -187,26 +187,26 @@ // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) - #define SERVO0_PIN 30 - #define BEEPER_PIN 27 - #define LCD_PINS_RS 29 - #define LCD_PINS_ENABLE 16 - #define LCD_PINS_D4 11 - #define BTN_EN1 28 - #define BTN_EN2 10 - #define BTN_ENC 17 + #define SERVO0_PIN PinA1 + #define BEEPER_PIN PinA4 + #define LCD_PINS_RS PinA2 + #define LCD_PINS_ENABLE PinC0 + #define LCD_PINS_D4 PinD3 + #define BTN_EN1 PinA3 + #define BTN_EN2 PinD2 + #define BTN_ENC PinC1 #define BOARD_ST7920_DELAY_1 250 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 250 #else - #define SERVO0_PIN 29 // free for BLTouch/3D-Touch - #define BEEPER_PIN 17 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 28 - #define LCD_PINS_D4 30 - #define BTN_EN1 11 - #define BTN_EN2 10 - #define BTN_ENC 16 + #define SERVO0_PIN PinA2 // free for BLTouch/3D-Touch + #define BEEPER_PIN PinC1 + #define LCD_PINS_RS PinA4 + #define LCD_PINS_ENABLE PinA3 + #define LCD_PINS_D4 PinA1 + #define BTN_EN1 PinD3 + #define BTN_EN2 PinD2 + #define BTN_ENC PinC0 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 63 #define BOARD_ST7920_DELAY_3 125 @@ -215,7 +215,7 @@ #endif #else - #define SERVO0_PIN 27 + #define SERVO0_PIN PinA4 #endif #ifndef FIL_RUNOUT_PIN diff --git a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h index 1343739a119e..93a21970616d 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h @@ -52,47 +52,47 @@ #include "env_validate.h" #define BOARD_INFO_NAME "Gen3 Monolithic" -#define DEBUG_PIN 0 +#define DEBUG_PIN PinB0 // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN PinC4 +#define Y_STOP_PIN PinA6 +#define Z_STOP_PIN PinA1 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 // actually uses Y_enable_pin +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC2 +#define X_ENABLE_PIN PinA7 // actually uses Y_enable_pin -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 // shared with X_enable_pin +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 // shared with X_enable_pin -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN PinA4 +#define Z_DIR_PIN PinA3 +#define Z_ENABLE_PIN PinA2 -#define E0_STEP_PIN 12 -#define E0_DIR_PIN 17 -#define E0_ENABLE_PIN 3 +#define E0_STEP_PIN PinD4 +#define E0_DIR_PIN PinC1 +#define E0_ENABLE_PIN PinB3 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input +#define TEMP_0_PIN PinB0 // Analog Input // // Heaters // -#define HEATER_0_PIN 16 +#define HEATER_0_PIN PinC0 // // Misc. Functions // -#define PS_ON_PIN 14 // Alex, does this work on the card? +#define PS_ON_PIN PinD6 // Alex, does this work on the card? // Alex extras from Gen3+ diff --git a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h index 7cab1bd762c5..a68ca114496b 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h @@ -56,43 +56,43 @@ // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN PinC4 +#define Y_STOP_PIN PinA6 +#define Z_STOP_PIN PinA1 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 19 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC2 +#define X_ENABLE_PIN PinC3 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN PinA4 +#define Z_DIR_PIN PinA3 +#define Z_ENABLE_PIN PinA2 -#define E0_STEP_PIN 17 -#define E0_DIR_PIN 21 -#define E0_ENABLE_PIN 13 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC5 +#define E0_ENABLE_PIN PinD5 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 5 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB0 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN PinB5 // Analog Input (pin 34 bed) // // Heaters // -#define HEATER_0_PIN 12 -#define HEATER_BED_PIN 16 +#define HEATER_0_PIN PinD4 +#define HEATER_BED_PIN PinC0 // // Misc. Functions // -#define SDSS 4 -#define PS_ON_PIN 14 +#define SDSS PinB4 +#define PS_ON_PIN PinD6 diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index 51e8200b9570..6a1e79e5a084 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -60,61 +60,61 @@ // // Limit Switches // -#define X_STOP_PIN 20 -#define Y_STOP_PIN 25 -#define Z_STOP_PIN 30 +#define X_STOP_PIN PinC4 +#define Y_STOP_PIN PinA6 +#define Z_STOP_PIN PinA1 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 19 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC2 +#define X_ENABLE_PIN PinC3 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 +#define Z_STEP_PIN PinA4 +#define Z_DIR_PIN PinA3 +#define Z_ENABLE_PIN PinA2 -#define E0_STEP_PIN 4 // Edited @ EJE Electronics 20100715 -#define E0_DIR_PIN 2 // Edited @ EJE Electronics 20100715 -#define E0_ENABLE_PIN 3 // Added @ EJE Electronics 20100715 +#define E0_STEP_PIN PinB4 // Edited @ EJE Electronics 20100715 +#define E0_DIR_PIN PinB2 // Edited @ EJE Electronics 20100715 +#define E0_ENABLE_PIN PinB3 // Added @ EJE Electronics 20100715 // // Temperature Sensor // -#define TEMP_0_PIN 5 // Analog Input +#define TEMP_0_PIN PinB5 // Analog Input // // Heaters // -#define HEATER_0_PIN 14 // changed @ rkoeppl 20110410 +#define HEATER_0_PIN PinD6 // changed @ rkoeppl 20110410 #if !MB(GEN6) - #define HEATER_BED_PIN 1 // changed @ rkoeppl 20110410 - #define TEMP_BED_PIN 0 // Analog Input + #define HEATER_BED_PIN PinB1 // changed @ rkoeppl 20110410 + #define TEMP_BED_PIN PinB0 // Analog Input #endif // // Misc. Functions // -#define SDSS 17 -#define DEBUG_PIN 0 +#define SDSS PinC1 +#define DEBUG_PIN PinB0 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 16 // Hardware PWM + #define CASE_LIGHT_PIN PinC0 // Hardware PWM #endif // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN PinD4 +#define RX_ENABLE_PIN PinD5 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#define SPINDLE_LASER_ENA_PIN PinB5 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN PinC0 // Hardware PWM +#define SPINDLE_DIR_PIN PinB6 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index 0834da78c45c..b3b65dd3ea52 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -58,89 +58,89 @@ #endif #ifndef GEN7_VERSION - #define GEN7_VERSION 12 // v1.x + #define GEN7_VERSION PinD4 // v1.x #endif // // Limit Switches // -#define X_MIN_PIN 7 -#define Y_MIN_PIN 5 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 -#define Y_MAX_PIN 2 -#define X_MAX_PIN 6 +#define X_MIN_PIN PinB7 +#define Y_MIN_PIN PinB5 +#define Z_MIN_PIN PinB1 +#define Z_MAX_PIN PinB0 +#define Y_MAX_PIN PinB2 +#define X_MAX_PIN PinB6 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 0 + #define Z_MIN_PROBE_PIN PinB0 #endif // // Steppers // -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinC3 +#define X_DIR_PIN PinC2 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN PinA5 +#define Z_DIR_PIN PinA6 +#define Z_ENABLE_PIN PinA7 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA3 +#define E0_DIR_PIN PinA4 +#define E0_ENABLE_PIN PinA7 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN PinB4 +#define HEATER_BED_PIN PinB3 #if !defined(FAN_PIN) && GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin - #define FAN_PIN 31 + #define FAN_PIN PinA0 #endif // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN PinD7 #if GEN7_VERSION < 13 - #define CASE_LIGHT_PIN 16 // Hardware PWM + #define CASE_LIGHT_PIN PinC0 // Hardware PWM #else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header - #define CASE_LIGHT_PIN 15 // Hardware PWM + #define CASE_LIGHT_PIN PinD7 // Hardware PWM #endif // All these generations of Gen7 supply thermistor power // via PS_ON, so ignore bad thermistor readings //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 -#define DEBUG_PIN 0 +#define DEBUG_PIN PinB0 // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN PinD4 +#define RX_ENABLE_PIN PinD5 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! -#define SPINDLE_DIR_PIN 11 +#define SPINDLE_LASER_ENA_PIN PinD2 // Pullup or pulldown! +#define SPINDLE_DIR_PIN PinD3 #if GEN7_VERSION < 13 - #define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinC0 // Hardware PWM #else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header - #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinD7 // Hardware PWM #endif diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index 97bfdd28a727..ddd3f15005dc 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -60,60 +60,60 @@ // // Limit switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN PinB0 +#define Y_STOP_PIN PinB1 +#define Z_STOP_PIN PinB2 // // Steppers // -#define X_STEP_PIN 29 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 25 +#define X_STEP_PIN PinA2 +#define X_DIR_PIN PinA3 +#define X_ENABLE_PIN PinA6 -#define Y_STEP_PIN 27 -#define Y_DIR_PIN 26 -#define Y_ENABLE_PIN 25 +#define Y_STEP_PIN PinA4 +#define Y_DIR_PIN PinA5 +#define Y_ENABLE_PIN PinA6 -#define Z_STEP_PIN 23 -#define Z_DIR_PIN 22 -#define Z_ENABLE_PIN 25 +#define Z_STEP_PIN PinC7 +#define Z_DIR_PIN PinC6 +#define Z_ENABLE_PIN PinA6 -#define E0_STEP_PIN 19 -#define E0_DIR_PIN 18 -#define E0_ENABLE_PIN 25 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinC2 +#define E0_ENABLE_PIN PinA6 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB0 // Analog Input // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN PinB4 +#define HEATER_BED_PIN PinB3 // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN PinD7 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 15 // Hardware PWM + #define CASE_LIGHT_PIN PinD7 // Hardware PWM #endif // A pin for debugging -#define DEBUG_PIN 0 +#define DEBUG_PIN PinB0 // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN PinD4 +#define RX_ENABLE_PIN PinD5 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 20 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 21 +#define SPINDLE_LASER_ENA_PIN PinC4 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN PinC0 // Hardware PWM +#define SPINDLE_DIR_PIN PinC5 diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 6d7678e6e3d2..3b555a47f354 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -61,49 +61,49 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN PinB0 +#define Y_STOP_PIN PinB1 +#define Z_STOP_PIN PinB2 // // Steppers // -#define X_STEP_PIN 21 // different from standard GEN7 -#define X_DIR_PIN 20 // different from standard GEN7 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinC5 // different from standard GEN7 +#define X_DIR_PIN PinC4 // different from standard GEN7 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN PinA5 +#define Z_DIR_PIN PinA6 +#define Z_ENABLE_PIN PinA7 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA3 +#define E0_DIR_PIN PinA4 +#define E0_ENABLE_PIN PinA7 // // Temperature Sensors // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_BED_PIN 1 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB2 // Analog Input +#define TEMP_BED_PIN PinB1 // Analog Input (pin 34 bed) // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 // (bed) +#define HEATER_0_PIN PinB4 +#define HEATER_BED_PIN PinB3 // (bed) // // Misc. Functions // -#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support -#define PS_ON_PIN 19 +#define SDSS PinA0 // SCL pin of I2C header || CS Pin for SD Card support +#define PS_ON_PIN PinC3 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 15 // Hardware PWM + #define CASE_LIGHT_PIN PinD7 // Hardware PWM #endif // A pin for debugging @@ -115,25 +115,25 @@ #define BEEPER_PIN -1 // 4bit LCD Support -#define LCD_PINS_RS 18 -#define LCD_PINS_ENABLE 17 -#define LCD_PINS_D4 16 -#define LCD_PINS_D5 15 -#define LCD_PINS_D6 13 -#define LCD_PINS_D7 14 +#define LCD_PINS_RS PinC2 +#define LCD_PINS_ENABLE PinC1 +#define LCD_PINS_D4 PinC0 +#define LCD_PINS_D5 PinD7 +#define LCD_PINS_D6 PinD5 +#define LCD_PINS_D7 PinD6 // Buttons are directly attached -#define BTN_EN1 11 -#define BTN_EN2 10 -#define BTN_ENC 12 +#define BTN_EN1 PinD3 +#define BTN_EN2 PinD2 +#define BTN_ENC PinD4 // RS485 pins -//#define TX_ENABLE_PIN 12 -//#define RX_ENABLE_PIN 13 +//#define TX_ENABLE_PIN PinD4 +//#define RX_ENABLE_PIN PinD5 // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // Pullup or pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // Hardware PWM -#define SPINDLE_DIR_PIN 6 +#define SPINDLE_LASER_ENA_PIN PinB5 // Pullup or pulldown! +#define SPINDLE_LASER_PWM_PIN PinC0 // Hardware PWM +#define SPINDLE_DIR_PIN PinB6 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index 83aa5317f939..05b13aa2d64d 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -23,6 +23,7 @@ /** * Melzi (Creality) pin assignments + * ATmega1284P * * The Creality board needs a bootloader installed before Marlin can be uploaded. * If you don't have a chip programmer you can use a spare Arduino plus a few @@ -56,21 +57,21 @@ #undef LCD_PINS_D6 #undef LCD_PINS_D7 -#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) -#define LCD_PINS_RS 28 // ST9720 CS -#define LCD_PINS_ENABLE 17 // ST9720 DAT -#define LCD_PINS_D4 30 // ST9720 CLK +#define LCD_SDSS PinA0 // Smart Controller SD card reader (rather than the Melzi) +#define LCD_PINS_RS PinA3 // ST9720 CS +#define LCD_PINS_ENABLE PinC1 // ST9720 DAT +#define LCD_PINS_D4 PinA1 // ST9720 CLK #if ENABLED(BLTOUCH) #ifndef SERVO0_PIN - #define SERVO0_PIN 27 + #define SERVO0_PIN PinA4 #endif #if SERVO0_PIN == BEEPER_PIN #undef BEEPER_PIN #endif #elif HAS_FILAMENT_SENSOR #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 27 + #define FIL_RUNOUT_PIN PinA4 #endif #if FIL_RUNOUT_PIN == BEEPER_PIN #undef BEEPER_PIN diff --git a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h index a0421dcf5cc6..09a7ff6e95ca 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_MALYAN.h @@ -23,6 +23,7 @@ /** * Melzi (Malyan M150) pin assignments + * ATmega644P, ATmega1284P */ #define BOARD_INFO_NAME "Melzi (Malyan)" @@ -37,9 +38,9 @@ #undef BTN_EN2 #undef BTN_ENC -#define LCD_PINS_RS 17 // ST9720 CS -#define LCD_PINS_ENABLE 16 // ST9720 DAT -#define LCD_PINS_D4 11 // ST9720 CLK -#define BTN_EN1 30 -#define BTN_EN2 29 -#define BTN_ENC 28 +#define LCD_PINS_RS PinC1 // ST9720 CS +#define LCD_PINS_ENABLE PinC0 // ST9720 DAT +#define LCD_PINS_D4 PinD3 // ST9720 CLK +#define BTN_EN1 PinA1 +#define BTN_EN2 PinA2 +#define BTN_ENC PinA3 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h index 3f7b36765f34..9acf19975a27 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_TRONXY.h @@ -23,6 +23,7 @@ /** * Melzi pin assignments + * ATmega644P, ATmega1284P */ #define BOARD_INFO_NAME "Melzi (Tronxy)" @@ -48,13 +49,13 @@ #undef BTN_ENC #undef LCD_SDSS -#define Z_ENABLE_PIN 14 -#define LCD_PINS_RS 30 -#define LCD_PINS_ENABLE 28 -#define LCD_PINS_D4 16 -#define LCD_PINS_D5 17 -#define LCD_PINS_D6 27 -#define LCD_PINS_D7 29 -#define BTN_EN1 10 -#define BTN_EN2 11 -#define BTN_ENC 26 +#define Z_ENABLE_PIN PinD6 +#define LCD_PINS_RS PinA1 +#define LCD_PINS_ENABLE PinA3 +#define LCD_PINS_D4 PinC0 +#define LCD_PINS_D5 PinC1 +#define LCD_PINS_D6 PinA4 +#define LCD_PINS_D7 PinA2 +#define BTN_EN1 PinD2 +#define BTN_EN2 PinD3 +#define BTN_ENC PinA5 diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index 7f18283d1c54..d57d000334f9 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -84,28 +84,28 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN PinB0 +#define Y_STOP_PIN PinB1 +#define Z_STOP_PIN PinB2 // // Steppers // -#define X_STEP_PIN 26 -#define X_DIR_PIN 25 -#define X_ENABLE_PIN 10 +#define X_STEP_PIN PinA5 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinD2 -#define Y_STEP_PIN 28 -#define Y_DIR_PIN 27 -#define Y_ENABLE_PIN 10 +#define Y_STEP_PIN PinA3 +#define Y_DIR_PIN PinA4 +#define Y_ENABLE_PIN PinD2 -#define Z_STEP_PIN 23 -#define Z_DIR_PIN 22 -#define Z_ENABLE_PIN 10 +#define Z_STEP_PIN PinC7 +#define Z_DIR_PIN PinC6 +#define Z_ENABLE_PIN PinD2 -#define E0_STEP_PIN 24 -#define E0_DIR_PIN 21 -#define E0_ENABLE_PIN 10 +#define E0_STEP_PIN PinA7 +#define E0_DIR_PIN PinC5 +#define E0_ENABLE_PIN PinD2 #define E1_STEP_PIN -1 // 21 #define E1_DIR_PIN -1 // 20 @@ -118,32 +118,32 @@ // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input (1,2 or I2C) +#define TEMP_0_PIN PinB0 // Analog Input +#define TEMP_1_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB2 // Analog Input (1,2 or I2C) // // Heaters / Fans // -#define HEATER_0_PIN 3 // DONE PWM on RIGHT connector -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinB3 // DONE PWM on RIGHT connector +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 14 // PWM on MIDDLE connector + #define FAN_PIN PinD6 // PWM on MIDDLE connector #endif // // Misc. Functions // -#define SDSS 11 +#define SDSS PinD3 -#define I2C_SCL_PIN 16 -#define I2C_SDA_PIN 17 +#define I2C_SCL_PIN PinC0 +#define I2C_SDA_PIN PinC1 // future proofing -#define __FS 20 -#define __FD 19 -#define __GS 18 -#define __GD 13 +#define __FS PinC4 +#define __FD PinC3 +#define __GS PinC2 +#define __GD PinD5 -#define UNUSED_PWM 14 // PWM on LEFT connector +#define UNUSED_PWM PinD6 // PWM on LEFT connector diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index a3ceb76a0de9..5799261534c8 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -82,54 +82,54 @@ // // Limit Switches // -#define X_STOP_PIN 0 -#define Y_STOP_PIN 1 -#define Z_STOP_PIN 2 +#define X_STOP_PIN PinB0 +#define Y_STOP_PIN PinB1 +#define Z_STOP_PIN PinB2 // // Steppers // -#define X_STEP_PIN 21 -#define X_DIR_PIN 20 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinC5 +#define X_DIR_PIN PinC4 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN PinA5 +#define Z_DIR_PIN PinA6 +#define Z_ENABLE_PIN PinA7 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA3 +#define E0_DIR_PIN PinA4 +#define E0_ENABLE_PIN PinA7 #define E1_STEP_PIN -1 // 19 #define E1_DIR_PIN -1 // 18 -#define E1_ENABLE_PIN 24 +#define E1_ENABLE_PIN PinA7 #define E2_STEP_PIN -1 // 17 #define E2_DIR_PIN -1 // 16 -#define E2_ENABLE_PIN 24 +#define E2_ENABLE_PIN PinA7 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input (D27) +#define TEMP_0_PIN PinB0 // Analog Input (D27) // // Heaters / Fans // -#define HEATER_0_PIN 4 +#define HEATER_0_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN 3 + #define FAN_PIN PinB3 #endif // // Misc. Functions // -#define SDSS 11 +#define SDSS PinD3 /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 5fe0d3842dd4..0607c7c674af 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -60,60 +60,60 @@ // // Limit Switches // -#define X_STOP_PIN 18 -#define Y_STOP_PIN 19 -#define Z_STOP_PIN 20 +#define X_STOP_PIN PinC2 +#define Y_STOP_PIN PinC3 +#define Z_STOP_PIN PinC4 // // Steppers // -#define X_STEP_PIN 15 -#define X_DIR_PIN 21 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC5 -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC7 -#define Z_STEP_PIN 3 -#define Z_DIR_PIN 2 +#define Z_STEP_PIN PinB3 +#define Z_DIR_PIN PinB2 -#define E0_STEP_PIN 1 -#define E0_DIR_PIN 0 +#define E0_STEP_PIN PinB1 +#define E0_DIR_PIN PinB0 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN 13 // (extruder) +#define HEATER_0_PIN PinD5 // (extruder) #if ENABLED(SANGUINOLOLU_V_1_2) - #define HEATER_BED_PIN 12 // (bed) - #define X_ENABLE_PIN 14 - #define Y_ENABLE_PIN 14 - #define Z_ENABLE_PIN 26 - #define E0_ENABLE_PIN 14 + #define HEATER_BED_PIN PinD4 // (bed) + #define X_ENABLE_PIN PinD6 + #define Y_ENABLE_PIN PinD6 + #define Z_ENABLE_PIN PinA5 + #define E0_ENABLE_PIN PinD6 #if !defined(FAN_PIN) && ENABLED(LCD_I2C_PANELOLU2) - #define FAN_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan + #define FAN_PIN PinB4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan #endif #else - #define HEATER_BED_PIN 14 // (bed) - #define X_ENABLE_PIN 4 - #define Y_ENABLE_PIN 4 - #define Z_ENABLE_PIN 4 - #define E0_ENABLE_PIN 4 + #define HEATER_BED_PIN PinD6 // (bed) + #define X_ENABLE_PIN PinB4 + #define Y_ENABLE_PIN PinB4 + #define Z_ENABLE_PIN PinB4 + #define E0_ENABLE_PIN PinB4 #endif #if !defined(FAN_PIN) && (MB(AZTEEG_X1, STB_11) || IS_MELZI) - #define FAN_PIN 4 // Works for Panelolu2 too + #define FAN_PIN PinB4 // Works for Panelolu2 too #endif // @@ -126,17 +126,17 @@ * If you encounter issues with these pins, upgrade your * Sanguino libraries! See #368. */ -//#define SDSS 24 -#define SDSS 31 +//#define SDSS PinA7 +#define SDSS PinA0 #if IS_MELZI - #define LED_PIN 27 + #define LED_PIN PinA4 #elif MB(STB_11) - #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED + #define LCD_BACKLIGHT_PIN PinC1 // LCD backlight LED #endif #if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define CASE_LIGHT_PIN 4 // Hardware PWM - see if IO Header is available + #define CASE_LIGHT_PIN PinB4 // Hardware PWM - see if IO Header is available #endif /** @@ -159,49 +159,49 @@ #if ENABLED(LCD_FOR_MELZI) - #define LCD_PINS_RS 17 - #define LCD_PINS_ENABLE 16 - #define LCD_PINS_D4 11 - #define KILL_PIN 10 - #define BEEPER_PIN 27 + #define LCD_PINS_RS PinC1 + #define LCD_PINS_ENABLE PinC0 + #define LCD_PINS_D4 PinD3 + #define KILL_PIN PinD2 + #define BEEPER_PIN PinA4 #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI - #define LCD_PINS_RS 30 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 29 // SID (MOSI) - #define LCD_PINS_D4 17 // SCK (CLK) clock + #define LCD_PINS_RS PinA1 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinA2 // SID (MOSI) + #define LCD_PINS_D4 PinC1 // SCK (CLK) clock // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. - #define BEEPER_PIN 27 + #define BEEPER_PIN PinA4 #else // Sanguinololu >=1.3 - #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define LCD_PINS_RS PinB4 + #define LCD_PINS_ENABLE PinC1 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA2 + #define LCD_PINS_D6 PinA3 + #define LCD_PINS_D7 PinA4 #endif #else - #define DOGLCD_A0 30 + #define DOGLCD_A0 PinA1 #if ENABLED(MAKRPANEL) - #define BEEPER_PIN 29 - #define DOGLCD_CS 17 - #define LCD_BACKLIGHT_PIN 28 // PA3 + #define BEEPER_PIN PinA2 + #define DOGLCD_CS PinC1 + #define LCD_BACKLIGHT_PIN PinA3 // PA3 #elif IS_MELZI - #define BEEPER_PIN 27 - #define DOGLCD_CS 28 + #define BEEPER_PIN PinA4 + #define DOGLCD_CS PinA3 #else // !MAKRPANEL - #define DOGLCD_CS 29 + #define DOGLCD_CS PinA2 #endif @@ -211,55 +211,55 @@ #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define LCD_PINS_RS 28 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 16 - #define LCD_PINS_D7 17 + #define LCD_PINS_RS PinA3 + #define LCD_PINS_ENABLE PinA2 + #define LCD_PINS_D4 PinD2 + #define LCD_PINS_D5 PinD3 + #define LCD_PINS_D6 PinC0 + #define LCD_PINS_D7 PinC1 #else - #define LCD_PINS_RS 4 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 30 - #define LCD_PINS_D5 29 - #define LCD_PINS_D6 28 - #define LCD_PINS_D7 27 + #define LCD_PINS_RS PinB4 + #define LCD_PINS_ENABLE PinC1 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA2 + #define LCD_PINS_D6 PinA3 + #define LCD_PINS_D7 PinA4 #endif #if ENABLED(LCD_FOR_MELZI) - #define BTN_ENC 28 - #define BTN_EN1 29 - #define BTN_EN2 30 + #define BTN_ENC PinA3 + #define BTN_EN1 PinA2 + #define BTN_EN2 PinA1 #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define ADC_KEYPAD_PIN 1 + #define ADC_KEYPAD_PIN PinB1 #define BTN_EN1 -1 #define BTN_EN2 -1 #elif ENABLED(LCD_I2C_PANELOLU2) #if IS_MELZI - #define BTN_ENC 29 - #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi + #define BTN_ENC PinA2 + #define LCD_SDSS PinA1 // Panelolu2 SD card reader rather than the Melzi #else - #define BTN_ENC 30 + #define BTN_ENC PinA1 #endif #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 - #define BTN_ENC 16 - #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi + #define BTN_ENC PinC0 + #define LCD_SDSS PinA3 // Smart Controller SD card reader rather than the Melzi #endif #if IS_NEWPANEL && !defined(BTN_EN1) - #define BTN_EN1 11 - #define BTN_EN2 10 + #define BTN_EN1 PinD3 + #define BTN_EN2 PinD2 #endif #endif // HAS_WIRED_LCD @@ -270,9 +270,9 @@ #if HAS_CUTTER #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define SPINDLE_LASER_ENA_PIN 10 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN 4 // Hardware PWM - #define SPINDLE_DIR_PIN 11 + #define SPINDLE_LASER_ENA_PIN PinD2 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinB4 // Hardware PWM + #define SPINDLE_DIR_PIN PinD3 #elif !MB(MELZI) // use X stepper motor socket @@ -306,11 +306,11 @@ #undef X_DIR_PIN #undef X_ENABLE_PIN #undef X_STEP_PIN - #define X_DIR_PIN 0 - #define X_ENABLE_PIN 14 - #define X_STEP_PIN 1 - #define SPINDLE_LASER_PWM_PIN 15 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN 21 // Pullup! + #define X_DIR_PIN PinB0 + #define X_ENABLE_PIN PinD6 + #define X_STEP_PIN PinB1 + #define SPINDLE_LASER_PWM_PIN PinD7 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinC5 // Pullup! #define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin #endif #endif diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index a2240b385b2b..14bd12311c07 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -55,69 +55,69 @@ #define BOARD_INFO_NAME "Sethi 3D_1" #ifndef GEN7_VERSION - #define GEN7_VERSION 12 // v1.x + #define GEN7_VERSION PinD4 // v1.x #endif // // Limit Switches // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 0 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 +#define X_STOP_PIN PinB2 +#define Y_STOP_PIN PinB0 +#define Z_MIN_PIN PinB1 +#define Z_MAX_PIN PinB0 // // Steppers // -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinC3 +#define X_DIR_PIN PinC2 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC7 +#define Y_DIR_PIN PinC6 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 +#define Z_STEP_PIN PinA5 +#define Z_DIR_PIN PinA6 +#define Z_ENABLE_PIN PinA7 -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define E0_STEP_PIN PinA3 +#define E0_DIR_PIN PinA4 +#define E0_ENABLE_PIN PinA7 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB2 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN PinB4 +#define HEATER_BED_PIN PinB3 #ifndef FAN_PIN #if GEN7_VERSION >= 13 // Gen7 v1.3 removed the fan pin #define FAN_PIN -1 #else - #define FAN_PIN 31 + #define FAN_PIN PinA0 #endif #endif // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN PinD7 // All these generations of Gen7 supply thermistor power // via PS_ON, so ignore bad thermistor readings //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 // our pin for debugging. -#define DEBUG_PIN 0 +#define DEBUG_PIN PinB0 // our RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN PinD4 +#define RX_ENABLE_PIN PinD5 diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index aa3ce556d16e..81039782312a 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -87,78 +87,78 @@ // // Limit Switches // -#define X_MIN_PIN 21 -#define Y_MIN_PIN 18 +#define X_MIN_PIN PinC5 +#define Y_MIN_PIN PinC2 #if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) - #define Z_MIN_PIN 25 + #define Z_MIN_PIN PinA6 #else - #define Z_MIN_PIN 13 + #define Z_MIN_PIN PinD5 #endif // // Steppers // -#define X_STEP_PIN 23 -#define X_DIR_PIN 22 -#define X_ENABLE_PIN 24 +#define X_STEP_PIN PinC7 +#define X_DIR_PIN PinC6 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 20 -#define Y_DIR_PIN 19 -#define Y_ENABLE_PIN 24 +#define Y_STEP_PIN PinC4 +#define Y_DIR_PIN PinC3 +#define Y_ENABLE_PIN PinA7 #if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) - #define Z_STEP_PIN 27 - #define Z_DIR_PIN 26 + #define Z_STEP_PIN PinA4 + #define Z_DIR_PIN PinA5 #else - #define Z_STEP_PIN 17 - #define Z_DIR_PIN 16 + #define Z_STEP_PIN PinC1 + #define Z_DIR_PIN PinC0 #endif -#define Z_ENABLE_PIN 24 +#define Z_ENABLE_PIN PinA7 #if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) - #define E0_STEP_PIN 15 - #define E0_DIR_PIN 14 + #define E0_STEP_PIN PinD7 + #define E0_DIR_PIN PinD6 #else - #define E0_STEP_PIN 27 - #define E0_DIR_PIN 26 + #define E0_STEP_PIN PinA4 + #define E0_DIR_PIN PinA5 #endif -#define E0_ENABLE_PIN 24 +#define E0_ENABLE_PIN PinA7 -#define E1_STEP_PIN 15 -#define E1_DIR_PIN 14 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN PinD7 +#define E1_DIR_PIN PinD6 +#define E1_ENABLE_PIN PinA7 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 0 -#define HEATER_BED_PIN 1 -#define FAN_PIN 28 +#define HEATER_0_PIN PinB0 +#define HEATER_BED_PIN PinB1 +#define FAN_PIN PinA3 #define FAN1_PIN -1 // // Filament Runout Sensor // #if EITHER(Z6S_ZFAULT, Z6BS_ZFAULT) - #define FIL_RUNOUT_PIN 13 + #define FIL_RUNOUT_PIN PinD5 #else - #define FIL_RUNOUT_PIN 25 // Z-MIN + #define FIL_RUNOUT_PIN PinA6 // Z-MIN #endif // // SD card // #if ENABLED(SDSUPPORT) - #define SDSS 4 + #define SDSS PinB4 #endif #define SD_DETECT_PIN -1 @@ -171,18 +171,18 @@ * (GND) | 9 10 | (5V) * ------ */ -#define EXP1_01_PIN 5 -#define EXP1_02_PIN 7 -#define EXP1_03_PIN 11 -#define EXP1_04_PIN 10 -#define EXP1_05_PIN 12 +#define EXP1_01_PIN PinB5 +#define EXP1_02_PIN PinB7 +#define EXP1_03_PIN PinD3 +#define EXP1_04_PIN PinD2 +#define EXP1_05_PIN PinD4 #ifndef IS_ZMIB_V2 - #define EXP1_06_PIN 4 // ZMIB V1 + #define EXP1_06_PIN PinB4 // ZMIB V1 #else - #define EXP1_06_PIN 3 // ZMIB V2 + #define EXP1_06_PIN PinB3 // ZMIB V2 #endif -#define EXP1_07_PIN 29 -#define EXP1_08_PIN 2 +#define EXP1_07_PIN PinA2 +#define EXP1_08_PIN PinB2 #if ENABLED(ZONESTAR_12864LCD) // From a5b0fdf6739ab27d993594c8f51264055c83c59b Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Fri, 9 Dec 2022 00:19:15 +0100 Subject: [PATCH 33/83] - fixed a typo in the fastio_AT90USB.h update - refactored the teensy2 8bit AVR board pin header files to use pin names instead of internal numbers --- Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h | 50 +----- Marlin/src/pins/teensy2/pins_5DPRINT.h | 66 ++++---- Marlin/src/pins/teensy2/pins_BRAINWAVE.h | 56 +++---- Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h | 50 +++--- Marlin/src/pins/teensy2/pins_PRINTRBOARD.h | 92 +++++------ .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 146 +++++++++--------- Marlin/src/pins/teensy2/pins_SAV_MKI.h | 64 ++++---- Marlin/src/pins/teensy2/pins_TEENSY2.h | 72 ++++----- Marlin/src/pins/teensy2/pins_TEENSYLU.h | 68 ++++---- 9 files changed, 308 insertions(+), 356 deletions(-) diff --git a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h index 5b380d2acfca..1ca475e11f39 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_AT90USB.h @@ -103,7 +103,7 @@ #define DIO8_WPORT PORTE #define DIO8_PWM 0 #define DIO8_DDR DDRE -#define PinD0 8 +#define PinE0 8 #define DIO9_PIN PINE1 #define DIO9_RPORT PINE @@ -387,54 +387,6 @@ //-- end not supported by Teensyduino -#define AIO0_PIN PINF0 -#define AIO0_RPORT PINF -#define AIO0_WPORT PORTF -#define AIO0_PWM 0 -#define AIO0_DDR DDRF - -#define AIO1_PIN PINF1 -#define AIO1_RPORT PINF -#define AIO1_WPORT PORTF -#define AIO1_PWM 0 -#define AIO1_DDR DDRF - -#define AIO2_PIN PINF2 -#define AIO2_RPORT PINF -#define AIO2_WPORT PORTF -#define AIO2_PWM 0 -#define AIO2_DDR DDRF - -#define AIO3_PIN PINF3 -#define AIO3_RPORT PINF -#define AIO3_WPORT PORTF -#define AIO3_PWM 0 -#define AIO3_DDR DDRF - -#define AIO4_PIN PINF4 -#define AIO4_RPORT PINF -#define AIO4_WPORT PORTF -#define AIO4_PWM 0 -#define AIO4_DDR DDRF - -#define AIO5_PIN PINF5 -#define AIO5_RPORT PINF -#define AIO5_WPORT PORTF -#define AIO5_PWM 0 -#define AIO5_DDR DDRF - -#define AIO6_PIN PINF6 -#define AIO6_RPORT PINF -#define AIO6_WPORT PORTF -#define AIO6_PWM 0 -#define AIO6_DDR DDRF - -#define AIO7_PIN PINF7 -#define AIO7_RPORT PINF -#define AIO7_WPORT PORTF -#define AIO7_PWM 0 -#define AIO7_DDR DDRF - /** * Some of the pin mapping functions of the Teensduino extension to the Arduino IDE * do not function the same as the other Arduino extensions. diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 6e1f9c021746..70f1de077cd2 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -76,69 +76,69 @@ // // Servos // -#define SERVO0_PIN 41 -#define SERVO1_PIN 42 -#define SERVO2_PIN 43 -#define SERVO3_PIN 44 +#define SERVO0_PIN PinF3 +#define SERVO1_PIN PinF4 +#define SERVO2_PIN PinF5 +#define SERVO3_PIN PinF6 // // Limit Switches // -#define X_STOP_PIN 37 // E5 -#define Y_STOP_PIN 36 // E4 -#define Z_STOP_PIN 19 // E7 +#define X_STOP_PIN PinE5 // E5 +#define Y_STOP_PIN PinE4 // E4 +#define Z_STOP_PIN PinE7 // E7 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 17 // C7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinC7 // C7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 13 // C3 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinC3 // C3 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 12 // C2 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC2 // C2 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 11 // C1 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC1 // C1 // // Digital Microstepping // -#define X_MS1_PIN 25 // B5 -#define X_MS2_PIN 26 // B6 -#define Y_MS1_PIN 9 // E1 -#define Y_MS2_PIN 8 // E0 -#define Z_MS1_PIN 7 // D7 -#define Z_MS2_PIN 6 // D6 -#define E0_MS1_PIN 5 // D5 -#define E0_MS2_PIN 4 // D4 +#define X_MS1_PIN PinB5 // B5 +#define X_MS2_PIN PinB6 // B6 +#define Y_MS1_PIN PinE1 // E1 +#define Y_MS2_PIN PinE0 // E0 +#define Z_MS1_PIN PinD7 // D7 +#define Z_MS2_PIN PinD6 // D6 +#define E0_MS1_PIN PinD5 // D5 +#define E0_MS2_PIN PinD4 // D4 // // Temperature Sensors // -#define TEMP_0_PIN 1 // F1 Analog Input -#define TEMP_BED_PIN 0 // F0 Analog Input +#define TEMP_0_PIN PinD1 // F1 Analog Input +#define TEMP_BED_PIN PinD0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 -#define HEATER_BED_PIN 14 // C4 +#define HEATER_0_PIN PinC5 // C5 +#define HEATER_BED_PIN PinC4 // C4 #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 +#define SDSS PinB0 // B0 //DIGIPOTS slave addresses #ifndef DIGIPOT_I2C_ADDRESS_A diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index cdcc249c00d2..6c1ab0308dd9 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -77,50 +77,50 @@ // // Limit Switches // -#define X_STOP_PIN 35 // A7 -#define Y_STOP_PIN 34 // A6 -#define Z_STOP_PIN 33 // A5 +#define X_STOP_PIN PinA7 // A7 +#define Y_STOP_PIN PinA6 // A6 +#define Z_STOP_PIN PinA5 // A5 // // Steppers // -#define X_STEP_PIN 3 // D3 -#define X_DIR_PIN 5 // D5 -#define X_ENABLE_PIN 4 // D4 -#define X_ATT_PIN 2 // D2 - -#define Y_STEP_PIN 7 // D7 -#define Y_DIR_PIN 9 // E1 -#define Y_ENABLE_PIN 8 // E0 -#define Y_ATT_PIN 6 // D6 - -#define Z_STEP_PIN 11 // C1 -#define Z_DIR_PIN 13 // C3 -#define Z_ENABLE_PIN 12 // C2 -#define Z_ATT_PIN 10 // C0 - -#define E0_STEP_PIN 15 // C5 -#define E0_DIR_PIN 17 // C7 -#define E0_ENABLE_PIN 16 // C6 -#define E0_ATT_PIN 14 // C4 +#define X_STEP_PIN PinD3 // D3 +#define X_DIR_PIN PinD5 // D5 +#define X_ENABLE_PIN PinD4 // D4 +#define X_ATT_PIN PinD2 // D2 + +#define Y_STEP_PIN PinD7 // D7 +#define Y_DIR_PIN PinE1 // E1 +#define Y_ENABLE_PIN PinE0 // E0 +#define Y_ATT_PIN PinD6 // D6 + +#define Z_STEP_PIN PinC1 // C1 +#define Z_DIR_PIN PinC3 // C3 +#define Z_ENABLE_PIN PinC2 // C2 +#define Z_ATT_PIN PinC0 // C0 + +#define E0_STEP_PIN PinC5 // C5 +#define E0_DIR_PIN PinC7 // C7 +#define E0_ENABLE_PIN PinC6 // C6 +#define E0_ATT_PIN PinC4 // C4 // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input -#define TEMP_BED_PIN 6 // F6 Analog Input +#define TEMP_0_PIN PinD7 // F7 Analog Input +#define TEMP_BED_PIN PinD6 // F6 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 32 // A4 Extruder -#define HEATER_BED_PIN 18 // E6 Bed +#define HEATER_0_PIN PinA4 // A4 Extruder +#define HEATER_BED_PIN PinE6 // E6 Bed #ifndef FAN_PIN - #define FAN_PIN 31 // A3 Fan + #define FAN_PIN PinA3 // A3 Fan #endif // // Misc. Functions // -#define LED_PIN 19 // E7 +#define LED_PIN PinE7 // E7 diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index 319130ef968d..46fff4984d30 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -82,55 +82,55 @@ // // Limit Switches // -#define X_STOP_PIN 45 // F7 -#define Y_STOP_PIN 12 // C2 -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN PinF7 // F7 +#define Y_STOP_PIN PinC2 // C2 +#define Z_STOP_PIN PinE4 // E4 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 11 // C1 + #define Z_MIN_PROBE_PIN PinC1 // C1 #endif // // Steppers // -#define X_STEP_PIN 9 // E1 -#define X_DIR_PIN 8 // E0 -#define X_ENABLE_PIN 23 // B3 +#define X_STEP_PIN PinE1 // E1 +#define X_DIR_PIN PinE0 // E0 +#define X_ENABLE_PIN PinB3 // B3 -#define Y_STEP_PIN 7 // D7 -#define Y_DIR_PIN 6 // D6 -#define Y_ENABLE_PIN 20 // B0 +#define Y_STEP_PIN PinD7 // D7 +#define Y_DIR_PIN PinD6 // D6 +#define Y_ENABLE_PIN PinB0 // B0 -#define Z_STEP_PIN 5 // D5 -#define Z_DIR_PIN 4 // D4 -#define Z_ENABLE_PIN 37 // E5 +#define Z_STEP_PIN PinD5 // D5 +#define Z_DIR_PIN PinD4 // D4 +#define Z_ENABLE_PIN PinE5 // E5 -#define E0_STEP_PIN 47 // E3 -#define E0_DIR_PIN 46 // E2 -#define E0_ENABLE_PIN 25 // B5 +#define E0_STEP_PIN PinE3 // E3 +#define E0_DIR_PIN PinE2 // E2 +#define E0_ENABLE_PIN PinB5 // B5 // // Temperature Sensors // -#define TEMP_0_PIN 2 // F2 Analog Input -#define TEMP_1_PIN 1 // F1 Analog Input -#define TEMP_BED_PIN 0 // F0 Analog Input +#define TEMP_0_PIN PinD2 // F2 Analog Input +#define TEMP_1_PIN PinD1 // F1 Analog Input +#define TEMP_BED_PIN PinD0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 27 // B7 -#define HEATER_BED_PIN 26 // B6 Bed +#define HEATER_0_PIN PinB7 // B7 +#define HEATER_BED_PIN PinB6 // B6 Bed #ifndef FAN_PIN - #define FAN_PIN 16 // C6 Fan, PWM3A + #define FAN_PIN PinC6 // C6 Fan, PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 -#define SD_DETECT_PIN 24 // B4 -#define LED_PIN 13 // C3 +#define SDSS PinB0 // B0 +#define SD_DETECT_PIN PinB4 // B4 +#define LED_PIN PinC3 // C3 diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index ddf0d53ea60a..4f3b1d07fcb1 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -72,99 +72,99 @@ // // Limit Switches // -#define X_STOP_PIN 47 // E3 -#define Y_STOP_PIN 20 // B0 SS -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN PinE3 // E3 +#define Y_STOP_PIN PinB0 // B0 SS +#define Z_STOP_PIN PinE4 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN PinD1 // Analog Input +#define TEMP_BED_PIN PinD0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_1_PIN 44 // F6 -#define HEATER_2_PIN 45 // F7 -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_1_PIN PinF6 // F6 +#define HEATER_2_PIN PinF7 // F7 +#define HEATER_BED_PIN PinC4 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // // Misc. Functions // -#define FILWIDTH_PIN 2 // Analog Input +#define FILWIDTH_PIN PinD2 // Analog Input // // LCD / Controller // #if HAS_WIRED_LCD && IS_NEWPANEL - #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 - #define LCD_PINS_D4 7 // D7 JP11-8 - #define LCD_PINS_D5 6 // D6 JP11-7 - #define LCD_PINS_D6 5 // D5 JP11-6 - #define LCD_PINS_D7 4 // D4 JP11-5 + #define LCD_PINS_RS PinE1 // E1 JP11-11 + #define LCD_PINS_ENABLE PinE0 // E0 JP11-10 + #define LCD_PINS_D4 PinD7 // D7 JP11-8 + #define LCD_PINS_D5 PinD6 // D6 JP11-7 + #define LCD_PINS_D6 PinD5 // D5 JP11-6 + #define LCD_PINS_D7 PinD4 // D4 JP11-5 #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN 8 // E0 JP11-10 + #define BEEPER_PIN PinE0 // E0 JP11-10 - #define DOGLCD_A0 40 // F2 JP2-2 - #define DOGLCD_CS 41 // F3 JP2-4 + #define DOGLCD_A0 PinF2 // F2 JP2-2 + #define DOGLCD_CS PinF3 // F3 JP2-4 - #define BTN_EN1 2 // D2 TX1 JP2-5 - #define BTN_EN2 3 // D3 RX1 JP2-7 - #define BTN_ENC 45 // F7 TDI JP2-12 + #define BTN_EN1 PinD2 // D2 TX1 JP2-5 + #define BTN_EN2 PinD3 // D3 RX1 JP2-7 + #define BTN_ENC PinF7 // F7 TDI JP2-12 - #define SDSS 43 // F5 TMS JP2-8 + #define SDSS PinF5 // F5 TMS JP2-8 - #define STAT_LED_RED_PIN 12 // C2 JP11-14 - #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 + #define STAT_LED_RED_PIN PinC2 // C2 JP11-14 + #define STAT_LED_BLUE_PIN PinC0 // C0 JP11-12 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 3 // D3 RX1 JP2-7 - #define BTN_EN2 2 // D2 TX1 JP2-5 - #define BTN_ENC 41 // F3 JP2-4 + #define BTN_EN1 PinD3 // D3 RX1 JP2-7 + #define BTN_EN2 PinD2 // D2 TX1 JP2-5 + #define BTN_ENC PinF3 // F3 JP2-4 - #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 + #define SDSS PinF0 // F0 B-THERM connector - use SD card on Panelolu2 #else - #define BTN_EN1 10 // C0 JP11-12 - #define BTN_EN2 11 // C1 JP11-13 - #define BTN_ENC 12 // C2 JP11-14 + #define BTN_EN1 PinC0 // C0 JP11-12 + #define BTN_EN2 PinC1 // C1 JP11-13 + #define BTN_ENC PinC2 // C2 JP11-14 #endif #endif // HAS_WIRED_LCD && IS_NEWPANEL #ifndef SDSS - #define SDSS 26 // B6 SDCS + #define SDSS PinB6 // B6 SDCS #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index 18673980870f..f9ba526fd56c 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -97,46 +97,46 @@ // // Limit Switches // -#define X_STOP_PIN 47 // E3 -#define Y_STOP_PIN 24 // B4 PWM2A -#define Z_STOP_PIN 36 // E4 +#define X_STOP_PIN PinE3 // E3 +#define Y_STOP_PIN PinB4 // B4 PWM2A +#define Z_STOP_PIN PinE4 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define E1_STEP_PIN 25 // B5 - #define E1_DIR_PIN 37 // E5 - #define E1_ENABLE_PIN 42 // F4 + #define E1_STEP_PIN PinB5 // B5 + #define E1_DIR_PIN PinE5 // E5 + #define E1_ENABLE_PIN PinF4 // F4 - #define E2_STEP_PIN 2 // D2 - #define E2_DIR_PIN 3 // D3 - #define E2_ENABLE_PIN 43 // F5 + #define E2_STEP_PIN PinD2 // D2 + #define E2_DIR_PIN PinD3 // D3 + #define E2_ENABLE_PIN PinF5 // F5 #else - #define E1_STEP_PIN 2 // D2 - #define E1_DIR_PIN 3 // D3 - #define E1_ENABLE_PIN 43 // F5 + #define E1_STEP_PIN PinD2 // D2 + #define E1_DIR_PIN PinD3 // D3 + #define E1_ENABLE_PIN PinF5 // F5 - #define E2_STEP_PIN 25 // B5 - #define E2_DIR_PIN 37 // E5 - #define E2_ENABLE_PIN 42 // F4 + #define E2_STEP_PIN PinB5 // B5 + #define E2_DIR_PIN PinE5 // E5 + #define E2_ENABLE_PIN PinF4 // F4 #endif #endif // NO_EXTRUDRBOARD @@ -161,37 +161,37 @@ // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input (Extruder) -#define TEMP_BED_PIN 0 // Analog Input (Bed) +#define TEMP_0_PIN PinD1 // Analog Input (Extruder) +#define TEMP_BED_PIN PinD0 // Analog Input (Bed) #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define TEMP_1_PIN 2 // Analog Input (Extrudrboard A THERM) - #define TEMP_2_PIN 3 // Analog Input (Extrudrboard B THERM) + #define TEMP_1_PIN PinD2 // Analog Input (Extrudrboard A THERM) + #define TEMP_2_PIN PinD3 // Analog Input (Extrudrboard B THERM) #else - #define TEMP_1_PIN 3 // Analog Input (Extrudrboard B THERM) - #define TEMP_2_PIN 2 // Analog Input (Extrudrboard A THERM) + #define TEMP_1_PIN PinD3 // Analog Input (Extrudrboard B THERM) + #define TEMP_2_PIN PinD2 // Analog Input (Extrudrboard A THERM) #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define HEATER_1_PIN 44 // F6 - Extrudrboard A HOTEND - #define HEATER_2_PIN 45 // F7 - Extrudrboard B HOTEND + #define HEATER_1_PIN PinF6 // F6 - Extrudrboard A HOTEND + #define HEATER_2_PIN PinF7 // F7 - Extrudrboard B HOTEND #else - #define HEATER_1_PIN 45 // F7 - Extrudrboard B HOTEND - #define HEATER_2_PIN 44 // F6 - Extrudrboard A HOTEND + #define HEATER_1_PIN PinF7 // F7 - Extrudrboard B HOTEND + #define HEATER_2_PIN PinF6 // F6 - Extrudrboard A HOTEND #endif #endif #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // @@ -200,27 +200,27 @@ //#define USE_INTERNAL_SD #if HAS_WIRED_LCD - #define LCD_PINS_RS 9 // E1 JP11-11 - #define LCD_PINS_ENABLE 8 // E0 JP11-10 - #define LCD_PINS_D4 7 // D7 JP11-8 - #define LCD_PINS_D5 6 // D6 JP11-7 - #define LCD_PINS_D6 5 // D5 JP11-6 - #define LCD_PINS_D7 4 // D4 JP11-5 + #define LCD_PINS_RS PinE1 // E1 JP11-11 + #define LCD_PINS_ENABLE PinE0 // E0 JP11-10 + #define LCD_PINS_D4 PinD7 // D7 JP11-8 + #define LCD_PINS_D5 PinD6 // D6 JP11-7 + #define LCD_PINS_D6 PinD5 // D5 JP11-6 + #define LCD_PINS_D7 PinD4 // D4 JP11-5 #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN 8 // E0 JP11-10 - #define DOGLCD_A0 40 // F2 JP2-2 - #define DOGLCD_CS 41 // F3 JP2-4 + #define BEEPER_PIN PinE0 // E0 JP11-10 + #define DOGLCD_A0 PinF2 // F2 JP2-2 + #define DOGLCD_CS PinF3 // F3 JP2-4 - #define BTN_EN1 2 // D2 TX1 JP2-5 - #define BTN_EN2 3 // D3 RX1 JP2-7 - #define BTN_ENC 45 // F7 TDI JP2-12 + #define BTN_EN1 PinD2 // D2 TX1 JP2-5 + #define BTN_EN2 PinD3 // D3 RX1 JP2-7 + #define BTN_ENC PinF7 // F7 TDI JP2-12 - #define SDSS 3 // F5 TMS JP2-8 + #define SDSS PinD3 // F5 TMS JP2-8 - #define STAT_LED_RED_PIN 12 // C2 JP11-14 - #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 + #define STAT_LED_RED_PIN PinC2 // C2 JP11-14 + #define STAT_LED_BLUE_PIN PinC0 // C0 JP11-12 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -228,22 +228,22 @@ #if DISABLED(USE_INTERNAL_SD) // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define SDSS 11 // 36 C1 EXP2-13 EXP2-07 - #define SD_DETECT_PIN 9 // 34 E1 EXP2-11 EXP2-04 + #define SDSS PinC1 // 36 C1 EXP2-13 EXP2-07 + #define SD_DETECT_PIN PinE1 // 34 E1 EXP2-11 EXP2-04 #endif // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define DOGLCD_A0 4 // 29 D4 EXP2-05 EXP1-04 - #define DOGLCD_CS 5 // 30 D5 EXP2-06 EXP1-05 - #define BTN_ENC 6 // 31 D6 EXP2-07 EXP1-09 - #define BEEPER_PIN 7 // 32 D7 EXP2-08 EXP1-10 - #define KILL_PIN 8 // 33 E0 EXP2-10 EXP2-03 - #define BTN_EN1 10 // 35 C0 EXP2-12 EXP2-06 - #define BTN_EN2 12 // 37 C2 EXP2-14 EXP2-08 - //#define LCD_BACKLIGHT_PIN 43 // 56 F5 EXP1-12 Not Implemented - //#define SCK 21 // 11 B1 ICSP-04 EXP2-09 - //#define MOSI 22 // 12 B2 ICSP-03 EXP2-05 - //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 + #define DOGLCD_A0 PinD4 // 29 D4 EXP2-05 EXP1-04 + #define DOGLCD_CS PinD5 // 30 D5 EXP2-06 EXP1-05 + #define BTN_ENC PinD6 // 31 D6 EXP2-07 EXP1-09 + #define BEEPER_PIN PinD7 // 32 D7 EXP2-08 EXP1-10 + #define KILL_PIN PinE0 // 33 E0 EXP2-10 EXP2-03 + #define BTN_EN1 PinC0 // 35 C0 EXP2-12 EXP2-06 + #define BTN_EN2 PinC2 // 37 C2 EXP2-14 EXP2-08 + //#define LCD_BACKLIGHT_PIN PinF5 // 56 F5 EXP1-12 Not Implemented + //#define SCK PinB1 // 11 B1 ICSP-04 EXP2-09 + //#define MOSI PinB2 // 12 B2 ICSP-03 EXP2-05 + //#define MISO PinB3 // 13 B3 ICSP-06 EXP2-05 // Alter timing for graphical display #define BOARD_ST7920_DELAY_1 313 @@ -252,9 +252,9 @@ #else - #define BTN_EN1 10 // C0 JP11-12 - #define BTN_EN2 11 // C1 JP11-13 - #define BTN_ENC 12 // C2 JP11-14 + #define BTN_EN1 PinC0 // C0 JP11-12 + #define BTN_EN2 PinC1 // C1 JP11-13 + #define BTN_ENC PinC2 // C2 JP11-14 #endif @@ -265,7 +265,7 @@ // // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. #ifndef SDSS - #define SDSS 20 // 10 B0 + #define SDSS PinB0 // 10 B0 #endif /** @@ -276,5 +276,5 @@ * which will let you use Channel B on the Extrudrboard as E1. */ #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 2 // Analog Input + #define FILWIDTH_PIN PinD2 // Analog Input #endif diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index cdba535090e4..8a4ea7903473 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -76,51 +76,51 @@ // // Limit Switches // -#define X_STOP_PIN 25 // B5 -#define Y_STOP_PIN 26 // B6 -//#define Z_STOP_PIN 27 // B7 -#define Z_STOP_PIN 36 // E4 For inductive sensor. -//#define E_STOP_PIN 36 // E4 +#define X_STOP_PIN PinB5 // B5 +#define Y_STOP_PIN PinB6 // B6 +//#define Z_STOP_PIN PinB7 // B7 +#define Z_STOP_PIN PinE4 // E4 For inductive sensor. +//#define E_STOP_PIN PinE4 // E4 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) -#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) +#define TEMP_0_PIN PinD7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN PinD6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C - Bed +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C - Bed #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 +#define SDSS PinB0 // B0 // Extension header pin mapping // ---------------------------- @@ -131,11 +131,11 @@ // PWM-D24 A4 (An), IO // 5V GND // 12V GND -#define EXT_AUX_SCL_D0 0 // D0 PWM0B -#define EXT_AUX_SDA_D1 1 // D1 -#define EXT_AUX_RX1_D2 2 // D2 -#define EXT_AUX_TX1_D3 3 // D3 -#define EXT_AUX_PWM_D24 24 // B4 PWM2A +#define EXT_AUX_SCL_D0 PinD0 // D0 PWM0B +#define EXT_AUX_SDA_D1 PinD1 // D1 +#define EXT_AUX_RX1_D2 PinD2 // D2 +#define EXT_AUX_TX1_D3 PinD3 // D3 +#define EXT_AUX_PWM_D24 PinB4 // B4 PWM2A #define EXT_AUX_A0 0 // F0 Analog Input #define EXT_AUX_A0_IO 38 // F0 Digital IO #define EXT_AUX_A1 1 // F1 Analog Input @@ -174,10 +174,10 @@ // // M3/M4/M5 - Spindle/Laser Control // - #define SPINDLE_LASER_PWM_PIN 24 // B4 PWM2A - #define SPINDLE_LASER_ENA_PIN 39 // F1 Pin should have a pullup! - #define SPINDLE_DIR_PIN 40 // F2 + #define SPINDLE_LASER_PWM_PIN PinB4 // B4 PWM2A + #define SPINDLE_LASER_ENA_PIN PinF1 // F1 Pin should have a pullup! + #define SPINDLE_DIR_PIN PinF2 // F2 - #define CASE_LIGHT_PIN 0 // D0 PWM0B + #define CASE_LIGHT_PIN PinD0 // D0 PWM0B #endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index efb409bf3259..2589d1760028 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -114,73 +114,73 @@ // // Limit Switches // -#define X_STOP_PIN 2 // D2 -#define Y_STOP_PIN 3 // D3 -#define Z_STOP_PIN 4 // D4 +#define X_STOP_PIN PinD2 // D2 +#define Y_STOP_PIN PinD3 // D3 +#define Z_STOP_PIN PinD4 // D4 // // Steppers // -#define X_STEP_PIN 28 // A0 Marlin -#define X_DIR_PIN 29 // A1 Marlin -#define X_ENABLE_PIN 26 // B6 +#define X_STEP_PIN PinA0 // A0 Marlin +#define X_DIR_PIN PinA1 // A1 Marlin +#define X_ENABLE_PIN PinB6 // B6 -#define Y_STEP_PIN 30 // A2 Marlin -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 26 // B6 Shared w/x +#define Y_STEP_PIN PinA2 // A2 Marlin +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinB6 // B6 Shared w/x -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 26 // B6 Shared w/x +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinB6 // B6 Shared w/x -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 26 // B6 Shared w/x +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinB6 // B6 Shared w/x // // Temperature Sensors // -#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) -#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) +#define TEMP_0_PIN PinD7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN PinD6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN PinC5 // C5 PWM3B Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A Fan + #define FAN_PIN PinC6 // C6 PWM3A Fan #endif // // Misc. Functions // -#define SDSS 20 // B0 -#define LED_PIN 6 // D6 -#define PS_ON_PIN 27 // B7 +#define SDSS PinB0 // B0 +#define LED_PIN PinD6 // D6 +#define PS_ON_PIN PinB7 // B7 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM + #define CASE_LIGHT_PIN PinD1 // D1 PWM2B MUST BE HARDWARE PWM #endif // // LCD / Controller // #if IS_ULTIPANEL - #define LCD_PINS_RS 8 // E0 - #define LCD_PINS_ENABLE 9 // E1 - #define LCD_PINS_D4 10 // C0 - #define LCD_PINS_D5 11 // C1 - #define LCD_PINS_D6 12 // C2 - #define LCD_PINS_D7 13 // C3 - #define BTN_EN1 38 // F0 - #define BTN_EN2 39 // F1 - #define BTN_ENC 40 // F2 + #define LCD_PINS_RS PinE0 // E0 + #define LCD_PINS_ENABLE PinE1 // E1 + #define LCD_PINS_D4 PinC0 // C0 + #define LCD_PINS_D5 PinC1 // C1 + #define LCD_PINS_D6 PinC2 // C2 + #define LCD_PINS_D7 PinC3 // C3 + #define BTN_EN1 PinF0 // F0 + #define BTN_EN2 PinF1 // F1 + #define BTN_ENC PinF2 // F2 #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENA_PIN 5 // D5 Pin should have a pullup! -#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM -#define SPINDLE_DIR_PIN 7 // D7 +#define SPINDLE_LASER_ENA_PIN PinD5 // D5 Pin should have a pullup! +#define SPINDLE_LASER_PWM_PIN PinD0 // D0 PWM0B MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN PinD7 // D7 diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index ab722478fd93..938a56eda10c 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -85,61 +85,61 @@ // // Limit Switch definitions that match the SCHEMATIC // -//#define X_STOP_PIN 25 // B5 -//#define Y_STOP_PIN 26 // B6 -//#define Z_STOP_PIN 27 // B7 -//#define E_STOP_PIN 36 // E4 +//#define X_STOP_PIN PinB5 // B5 +//#define Y_STOP_PIN PinB6 // B6 +//#define Z_STOP_PIN PinB7 // B7 +//#define E_STOP_PIN PinE4 // E4 // // Limit Switch definitions that match the SILKSCREEN // -#define X_STOP_PIN 26 // B6 -#define Y_STOP_PIN 27 // B7 -#define Z_STOP_PIN 36 // E4 -//#define E_STOP_PIN 25 // B5 +#define X_STOP_PIN PinB6 // B6 +#define Y_STOP_PIN PinB7 // B7 +#define Z_STOP_PIN PinE4 // E4 +//#define E_STOP_PIN PinB5 // B5 // // Steppers // -#define X_STEP_PIN 28 // A0 -#define X_DIR_PIN 29 // A1 -#define X_ENABLE_PIN 19 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN 30 // A2 -#define Y_DIR_PIN 31 // A3 -#define Y_ENABLE_PIN 18 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN 32 // A4 -#define Z_DIR_PIN 33 // A5 -#define Z_ENABLE_PIN 17 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN 34 // A6 -#define E0_DIR_PIN 35 // A7 -#define E0_ENABLE_PIN 13 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) +#define TEMP_0_PIN PinD7 // Analog Input (Extruder) +#define TEMP_BED_PIN PinD6 // Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // C5 PWM3B - Extruder -#define HEATER_BED_PIN 14 // C4 PWM3C +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C #ifndef FAN_PIN - #define FAN_PIN 16 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS 20 // B0 JP31-6 +#define SDSS PinB0 // B0 JP31-6 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B + #define CASE_LIGHT_PIN PinD0 // D0 IO-14 PWM0B #endif // @@ -150,10 +150,10 @@ #define BEEPER_PIN -1 #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 3 // D3 IO-8 - #define BTN_EN2 2 // D2 IO-10 - #define BTN_ENC 41 // F3 IO-7 - #define SDSS 38 // F0 IO-13 use SD card on Panelolu2 + #define BTN_EN1 PinD3 // D3 IO-8 + #define BTN_EN2 PinD2 // D2 IO-10 + #define BTN_ENC PinF3 // F3 IO-7 + #define SDSS PinF0 // F0 IO-13 use SD card on Panelolu2 #endif #define SD_DETECT_PIN -1 @@ -163,6 +163,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENA_PIN 39 // F1 IO-11 - Pin should have a pullup! -#define SPINDLE_DIR_PIN 40 // F2 IO-9 +#define SPINDLE_LASER_PWM_PIN PinB4 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENA_PIN PinF1 // F1 IO-11 - Pin should have a pullup! +#define SPINDLE_DIR_PIN PinF2 // F2 IO-9 From eb2f8c24919ad0702dedba2aa1316f6011aa8200 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Sat, 10 Dec 2022 01:38:14 +0100 Subject: [PATCH 34/83] - refactored the AVR system memory map, using the __AVR_DEFREG macro for code-graph construction - improved the pin device state saving, adding support for powered-down peripherals, adding the _ATmega_savePinAlternates function to save the combined device state of multiple pins --- Marlin/src/HAL/AVR/HAL_SPI_SW.cpp | 21 +- Marlin/src/HAL/AVR/registers.cpp | 20 +- Marlin/src/HAL/AVR/registers.h | 2368 ++++++++++++++++------------- 3 files changed, 1340 insertions(+), 1069 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp index ee1e86a137db..716b3dff6e57 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp @@ -75,7 +75,7 @@ } } - static pin_dev_state_t _spi_sck_devstate, _spi_miso_devstate, _spi_mosi_devstate, _spi_cs_devstate; + static pin_dev_state_t _spi_pin_devstate; static int _spi_sck_pin, _spi_miso_pin, _spi_mosi_pin, _spi_cs_pin; static int _spi_bit_order = SPI_BITORDER_DEFAULT; static bool _spi_is_running = false; @@ -104,14 +104,7 @@ int use_pin_mosi = (hint_mosi >= 0) ? hint_mosi : SD_MOSI_PIN; int use_pin_cs = (hint_cs >= 0) ? hint_cs : SD_SS_PIN; - if (use_pin_sck >= 0) - _spi_sck_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_sck); - if (use_pin_miso >= 0) - _spi_miso_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_miso); - if (use_pin_mosi >= 0) - _spi_mosi_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_mosi); - if (use_pin_cs >= 0) - _spi_cs_devstate = _ATmega_savePinAlternate((unsigned int)use_pin_cs); + _spi_pin_devstate = _ATmega_savePinAlternates({use_pin_sck, use_pin_miso, use_pin_mosi, use_pin_cs}); _spi_sck_pin = use_pin_sck; _spi_miso_pin = use_pin_miso; @@ -138,15 +131,7 @@ _ATmega_digitalWrite(_spi_cs_pin, HIGH); // Restore pin device states. - // Has to be done in reverse order. - if (_spi_cs_pin >= 0) - _ATmega_restorePinAlternate(_spi_cs_pin, _spi_cs_devstate); - if (_spi_mosi_pin >= 0) - _ATmega_restorePinAlternate(_spi_mosi_pin, _spi_mosi_devstate); - if (_spi_miso_pin >= 0) - _ATmega_restorePinAlternate(_spi_miso_pin, _spi_miso_devstate); - if (_spi_sck_pin >= 0) - _ATmega_restorePinAlternate(_spi_sck_pin, _spi_sck_devstate); + _ATmega_restorePinAlternates({_spi_cs_pin, _spi_mosi_pin, _spi_miso_pin, _spi_sck_pin}, _spi_pin_devstate); _spi_is_running = false; } diff --git a/Marlin/src/HAL/AVR/registers.cpp b/Marlin/src/HAL/AVR/registers.cpp index 53576b0c76cb..687705fc7e8e 100644 --- a/Marlin/src/HAL/AVR/registers.cpp +++ b/Marlin/src/HAL/AVR/registers.cpp @@ -22,10 +22,6 @@ #include "registers.h" -#ifndef countof -#define countof(o) ((sizeof(o))/(sizeof(*o))) -#endif - // Since the compiler could be creating multiple copies of function code-graphs for each header inline-inclusion, // we want to off-load the function definitions that define static memory into this solitary compilation unit. // This way the ROM is NOT bloated (who knows if the compiler is optimizing same-content constant objects into one?) @@ -393,35 +389,35 @@ ATmegaPinFunctions _ATmega_getPinFunctions(int pin) { #elif defined(__AVR_TRM02__) if (info.port == eATmegaPort::PORT_A) { if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI7, eATmegaPinFunc::ADC7 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI6, eATmegaPinFunc::ADC6 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI5, eATmegaPinFunc::ADC5 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI4, eATmegaPinFunc::ADC4 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI3, eATmegaPinFunc::ADC3 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI2, eATmegaPinFunc::ADC2 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI1, eATmegaPinFunc::ADC1 }; return { funcs, countof(funcs) }; } else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI0, eATmegaPinFunc::ADC0 }; return { funcs, countof(funcs) }; } } diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index c41f8a0fb658..a4315d2bd428 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -1622,211 +1622,211 @@ __AVR_DEFREG(USART_dev_t, USART3, 0x130); #elif defined(__AVR_TRM02__) // page 637ff of ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf -static volatile PORT_dev_t& _PORTA = *(PORT_dev_t*)0x20; -static volatile PORT_dev_t& _PORTB = *(PORT_dev_t*)0x23; -static volatile PORT_dev_t& _PORTC = *(PORT_dev_t*)0x26; -static volatile PORT_dev_t& _PORTD = *(PORT_dev_t*)0x29; -static volatile TIFR0_reg_t& _TIFR0 = *(TIFR0_reg_t*)0x35; -static volatile TIFR1_reg_t& _TIFR1 = *(TIFR1_reg_t*)0x36; -static volatile TIFR2_reg_t& _TIFR2 = *(TIFR2_reg_t*)0x37; -static volatile TIFR3_reg_t& _TIFR3 = *(TIFR3_reg_t*)0x38; -static volatile PCIFR_reg_t& _PCIFR = *(PCIFR_reg_t*)0x3B; -static volatile EIFR_reg_t& _EIFR = *(EIFR_reg_t*)0x3C; -static volatile EIMSK_reg_t& _EIMSK = *(EIMSK_reg_t*)0x3D; -static volatile _bit_reg_t& _GPIOR0 = *(_bit_reg_t*)0x3E; -static volatile EECR_reg_t& _EECR = *(EECR_reg_t*)0x3F; -static volatile uint8_t& _EEDR = *(uint8_t*)0x40; -static volatile EEAR_reg_t& _EEAR = *(EEAR_reg_t*)0x41; -static volatile GTCCR_reg_t& _GTCCR = *(GTCCR_reg_t*)0x43; -static volatile TIMER_8bit_dev_t& TIMER0 = *(TIMER_8bit_dev_t*)0x44; -static volatile _bit_reg_t& _GPIOR1 = *(_bit_reg_t*)0x4A; -static volatile _bit_reg_t& _GPIOR2 = *(_bit_reg_t*)0x4B; -static volatile SPCR_reg_t& _SPCR = *(SPCR_reg_t*)0x4C; -static volatile SPSR_reg_t& _SPSR = *(SPSR_reg_t*)0x4D; -static volatile uint8_t& _SPDR = *(uint8_t*)0x4E; -static volatile ACSR_reg_t& _ACSR = *(ACSR_reg_t*)0x50; -static volatile SMCR_reg_t& _SMCR = *(SMCR_reg_t*)0x53; -static volatile MCUSR_reg_t& _MCUSR = *(MCUSR_reg_t*)0x54; -static volatile MCUCR_reg_t& _MCUCR = *(MCUCR_reg_t*)0x55; -static volatile SPMCSR_reg_t& _SPMCSR = *(SPMCSR_reg_t*)0x57; -static volatile SP_reg_t& _SP = *(SP_reg_t*)0x5D; -static volatile SREG_reg_t& _SREG = *(SREG_reg_t*)0x5F; -static volatile WDTCSR_reg_t& _WDTCSR = *(WDTCSR_reg_t*)0x60; -static volatile CLKPR_reg_t& _CLKPR = *(CLKPR_reg_t*)0x61; -static volatile PRR0_reg_t& _PRR0 = *(PRR0_reg_t*)0x64; -static volatile PRR1_reg_t& _PRR1 = *(PRR1_reg_t*)0x65; -static volatile uint8_t& _OSCCAL = *(uint8_t*)0x66; -static volatile PCICR_reg_t& _PCICR = *(PCICR_reg_t*)0x68; -static volatile EICRA_reg_t& _EICRA = *(EICRA_reg_t*)0x69; -static volatile _bit_reg_t& _PCMSK0 = *(_bit_reg_t*)0x6B; -static volatile _bit_reg_t& _PCMSK1 = *(_bit_reg_t*)0x6C; -static volatile _bit_reg_t& _PCMSK2 = *(_bit_reg_t*)0x6D; -static volatile TIMSK0_reg_t& _TIMSK0 = *(TIMSK0_reg_t*)0x6E; -static volatile TIMSK1_reg_t& _TIMSK1 = *(TIMSK1_reg_t*)0x6F; -static volatile TIMSK2_reg_t& _TIMSK2 = *(TIMSK2_reg_t*)0x70; -static volatile TIMSK3_reg_t& _TIMSK3 = *(TIMSK3_reg_t*)0x71; -static volatile _bit_reg_t& _PCMSK3 = *(_bit_reg_t*)0x73; -static volatile uint16_t& _ADC = *(uint16_t*)0x78; -static volatile ADCSRA_reg_t& _ADCSRA = *(ADCSRA_reg_t*)0x7A; -static volatile ADCSRB_reg_t& _ADCSRB = *(ADCSRB_reg_t*)0x7B; -static volatile ADMUX_reg_t& _ADMUX = *(ADMUX_reg_t*)0x7C; -static volatile DIDR0_reg_t& _DIDR0 = *(DIDR0_reg_t*)0x7E; -static volatile DIDR1_reg_t& _DIDR1 = *(DIDR1_reg_t*)0x7F; -static volatile TIMER_dev_t& TIMER1 = *(TIMER_dev_t*)0x70; -static volatile TIMER_dev_t& TIMER3 = *(TIMER_dev_t*)0x90; -static volatile TIMER_8bit_dev_t& _TIMER2 = *(TIMER_8bit_dev_t*)0xB0; -static volatile ASSR_reg_t& _ASSR = *(ASSR_reg_t*)0xB6; -static volatile uint8_t& _TWBR = *(uint8_t*)0xB8; -static volatile TWSR_reg_t& _TWSR = *(TWSR_reg_t*)0xB9; -static volatile TWAR_reg_t& _TWAR = *(TWAR_reg_t*)0xBA; -static volatile uint8_t& _TWDR = *(uint8_t*)0xBB; -static volatile TWCR_reg_t& _TWCR = *(TWCR_reg_t*)0xBC; -static volatile TWAMR_reg_t& _TWAMR = *(TWAMR_reg_t*)0xBD; -static volatile USART_dev_t& USART0 = *(USART_dev_t*)0xC0; -static volatile USART_dev_t& USART1 = *(USART_dev_t*)0xC8; +__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); +__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); +__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); +__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); +__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); +__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); +__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); +__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); +__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); +__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); +__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); +__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); +__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); +__AVR_DEFREG(uint8_t, _EEDR, 0x40); +__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); +__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); +__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); +__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); +__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); +__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); +__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); +__AVR_DEFREG(uint8_t, _SPDR, 0x4E); +__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); +__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); +__AVR_DEFREG(MCUSR_reg_t, _MSUSR, 0x54); +__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); +__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); +__AVR_DEFREG(SP_reg_t, _SP, 0x5D); +__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); +__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); +__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); +__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); +__AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); +__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); +__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); +__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); +__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); +__AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); +__AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); +__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); +__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); +__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); +__AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); +__AVR_DEFREG(_bit_reg_t, _PCMSK3, 0x73); +__AVR_DEFREG(uint16_t, _ADC, 0x78); +__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); +__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); +__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); +__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); +__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); +__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); +__AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); +__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); +__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); +__AVR_DEFREG(uint8_t, _TWBR, 0xB8); +__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); +__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); +__AVR_DEFREG(uint8_t, _TWDR, 0xBB); +__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); +__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); +__AVR_DEFREG(USART_dev_t, USART0, 0xC0); +__AVR_DEFREG(USART_dev_t, USART1, 0xC8); #elif defined(__AVR_TRM03__) // page 621ff of ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf -static volatile PORT_dev_t& _PORTB = *(PORT_dev_t*)0x23; -static volatile PORTC_dev_t& _PORTC = *(PORTC_dev_t*)0x26; -static volatile PORT_dev_t& _PORTD = *(PORT_dev_t*)0x29; -static volatile TIFR0_reg_t& _TIFR0 = *(TIFR0_reg_t*)0x35; -static volatile TIFR1_reg_t& _TIFR1 = *(TIFR1_reg_t*)0x36; -static volatile TIFR2_reg_t& _TIFR2 = *(TIFR2_reg_t*)0x37; -static volatile PCIFR_reg_t& _PCIFR = *(PCIFR_reg_t*)0x3B; -static volatile EIFR_reg_t& _EIFR = *(EIFR_reg_t*)0x3C; -static volatile EIMSK_reg_t& _EIMSK = *(EIMSK_reg_t*)0x3D; -static volatile _bit_reg_t& _GPIOR0 = *(_bit_reg_t*)0x3E; -static volatile EECR_reg_t& _EECR = *(EECR_reg_t*)0x3F; -static volatile uint8_t& _EEDR = *(uint8_t*)0x40; -static volatile EEAR_reg_t& _EEAR = *(EEAR_reg_t*)0x41; -static volatile GTCCR_reg_t& _GTCCR = *(GTCCR_reg_t*)0x43; -static volatile TIMER_8bit_dev_t& TIMER0 = *(TIMER_8bit_dev_t*)0x44; -static volatile _bit_reg_t& _GPIOR1 = *(_bit_reg_t*)0x4A; -static volatile _bit_reg_t& _GPIOR2 = *(_bit_reg_t*)0x4B; -static volatile SPCR_reg_t& _SPCR = *(SPCR_reg_t*)0x4C; -static volatile SPSR_reg_t& _SPSR = *(SPSR_reg_t*)0x4D; -static volatile uint8_t& _SPDR = *(uint8_t*)0x4E; -static volatile ACSR_reg_t& _ACSR = *(ACSR_reg_t*)0x50; -static volatile SMCR_reg_t& _SMCR = *(SMCR_reg_t*)0x53; -static volatile MCUSR_reg_t& _MCUSR = *(MCUSR_reg_t*)0x54; -static volatile MCUCR_reg_t& _MCUCR = *(MCUCR_reg_t*)0x55; -static volatile SPMCSR_reg_t& _SPMCSR = *(SPMCSR_reg_t*)0x57; -static volatile SP_reg_t& _SP = *(SP_reg_t*)0x5D; -static volatile SREG_reg_t& _SREG = *(SREG_reg_t*)0x5F; -static volatile WDTCSR_reg_t& _WDTCSR = *(WDTCSR_reg_t*)0x60; -static volatile CLKPR_reg_t& _CLKPR = *(CLKPR_reg_t*)0x61; -static volatile PRR0_reg_t& _PRR0 = *(PRR0_reg_t*)0x64; -static volatile uint8_t& _OSCCAL = *(uint8_t*)0x66; -static volatile PCICR_reg_t& _PCICR = *(PCICR_reg_t*)0x68; -static volatile EICRA_reg_t& _EICRA = *(EICRA_reg_t*)0x69; -static volatile _bit_reg_t& _PCMSK0 = *(_bit_reg_t*)0x6B; -static volatile _bitPCMSK1_reg_t& _PCMSK1 = *(_bitPCMSK1_reg_t*)0x6C; -static volatile _bit_reg_t& _PCMSK2 = *(_bit_reg_t*)0x6D; -static volatile TIMSK0_reg_t& _TIMSK0 = *(TIMSK0_reg_t*)0x6E; -static volatile TIMSK1_reg_t& _TIMSK1 = *(TIMSK1_reg_t*)0x6F; -static volatile TIMSK2_reg_t& _TIMSK2 = *(TIMSK2_reg_t*)0x70; -static volatile uint16_t& _ADC = *(uint16_t*)0x78; -static volatile ADCSRA_reg_t& _ADCSRA = *(ADCSRA_reg_t*)0x7A; -static volatile ADCSRB_reg_t& _ADCSRB = *(ADCSRB_reg_t*)0x7B; -static volatile ADMUX_reg_t& _ADMUX = *(ADMUX_reg_t*)0x7C; -static volatile DIDR0_reg_t& _DIDR0 = *(DIDR0_reg_t*)0x7E; -static volatile DIDR1_reg_t& _DIDR1 = *(DIDR1_reg_t*)0x7F; -static volatile TIMER_dev_t& TIMER1 = *(TIMER_dev_t*)0x80; -static volatile TIMER_8bit_dev_t& _TIMER2 = *(TIMER_8bit_dev_t*)0xB0; -static volatile ASSR_reg_t& _ASSR = *(ASSR_reg_t*)0xB6; -static volatile uint8_t& _TWBR = *(uint8_t*)0xB8; -static volatile TWSR_reg_t& _TWSR = *(TWSR_reg_t*)0xB9; -static volatile TWAR_reg_t& _TWAR = *(TWAR_reg_t*)0xBA; -static volatile uint8_t& _TWDR = *(uint8_t*)0xBB; -static volatile TWCR_reg_t& _TWCR = *(TWCR_reg_t*)0xBC; -static volatile TWAMR_reg_t& _TWAMR = *(TWAMR_reg_t*)0xBD; -static volatile USART_dev_t& USART0 = *(USART_dev_t*)0xC0; +__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); +__AVR_DEFREG(PORTC_dev_t, _PORTC, 0x26); +__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); +__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); +__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); +__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); +__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); +__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); +__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); +__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); +__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); +__AVR_DEFREG(uint8_t, _EEDR, 0x40); +__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); +__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); +__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); +__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); +__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); +__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); +__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); +__AVR_DEFREG(uint8_t, _SPDR, 0x4E); +__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); +__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); +__AVR_DEFREG(MCUSR_reg_t, _MSUCR, 0x54); +__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); +__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); +__AVR_DEFREG(SP_reg_t, _SP, 0x5D); +__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); +__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); +__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); +__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); +__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); +__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); +__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); +__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); +__AVR_DEFREG(_bitPCMSK1_reg_t, _PCMSK1, 0x6C); +__AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); +__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); +__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); +__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); +__AVR_DEFREG(uint16_t, _ADC, 0x78); +__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); +__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); +__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); +__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); +__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); +__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); +__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); +__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); +__AVR_DEFREG(uint8_t, _TWBR, 0xB8); +__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); +__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); +__AVR_DEFREG(uint8_t, _TWDR, 0xBB); +__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); +__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); +__AVR_DEFREG(USART_dev_t, USART0, 0xC0); #elif defined(__AVR_TRM04__) -static volatile PORT_dev_t& _PORTA = *(PORT_dev_t*)0x20; -static volatile PORT_dev_t& _PORTB = *(PORT_dev_t*)0x23; -static volatile PORT_dev_t& _PORTC = *(PORT_dev_t*)0x26; -static volatile PORT_dev_t& _PORTD = *(PORT_dev_t*)0x29; -static volatile PORT_dev_t& _PORTE = *(PORT_dev_t*)0x2C; -static volatile PORT_dev_t& _PORTF = *(PORT_dev_t*)0x2F; -static volatile TIFR0_reg_t& _TIFR0 = *(TIFR0_reg_t*)0x35; -static volatile TIFR1_reg_t& _TIFR1 = *(TIFR1_reg_t*)0x36; -static volatile TIFR2_reg_t& _TIFR2 = *(TIFR2_reg_t*)0x37; -static volatile TIFR3_reg_t& _TIFR3 = *(TIFR3_reg_t*)0x38; -static volatile PCIFR_reg_t& _PCIFR = *(PCIFR_reg_t*)0x3B; -static volatile EIFR_reg_t& _EIFR = *(EIFR_reg_t*)0x3C; -static volatile EIMSK_reg_t& _EIMSK = *(EIMSK_reg_t*)0x3D; -static volatile _bit_reg_t& _GPIOR0 = *(_bit_reg_t*)0x3E; -static volatile EECR_reg_t& _EECR = *(EECR_reg_t*)0x3F; -static volatile uint8_t& _EEDR = *(uint8_t*)0x40; -static volatile EEAR_reg_t& _EEAR = *(EEAR_reg_t*)0x41; -static volatile GTCCR_reg_t& _GTCCR = *(GTCCR_reg_t*)0x43; -static volatile TIMER_8bit_dev_t& TIMER0 = *(TIMER_8bit_dev_t*)0x44; -static volatile PLLCSR_reg_t& _PLLCSR = *(PLLCSR_reg_t*)0x49; -static volatile _bit_reg_t& _GPIOR1 = *(_bit_reg_t*)0x4A; -static volatile _bit_reg_t& _GPIOR2 = *(_bit_reg_t*)0x4B; -static volatile SPCR_reg_t& _SPCR = *(SPCR_reg_t*)0x4C; -static volatile SPSR_reg_t& _SPSR = *(SPSR_reg_t*)0x4D; -static volatile uint8_t& _SPDR = *(uint8_t*)0x4E; -static volatile ACSR_reg_t& _ACSR = *(ACSR_reg_t*)0x50; -static volatile uint8_t& _OCDR = *(uint8_t*)0x51; -static volatile SMCR_reg_t& _SMCR = *(SMCR_reg_t*)0x53; -static volatile MCUSR_reg_t& _MCUSR = *(MCUSR_reg_t*)0x54; -static volatile MCUCR_reg_t& _MCUCR = *(MCUCR_reg_t*)0x55; -static volatile SPMCSR_reg_t& _SPMCSR = *(SPMCSR_reg_t*)0x57; -static volatile RAMPZ_reg_t& _RAMPZ = *(RAMPZ_reg_t*)0x5B; -static volatile SP_reg_t& _SP = *(SP_reg_t*)0x5D; -static volatile SREG_reg_t& _SREG = *(SREG_reg_t*)0x5F; -static volatile WDTCSR_reg_t& _WDTCSR = *(WDTCSR_reg_t*)0x60; -static volatile CLKPR_reg_t& _CLKPR = *(CLKPR_reg_t*)0x61; -static volatile PRR0_reg_t& _PRR0 = *(PRR0_reg_t*)0x64; -static volatile PRR1_reg_t& _PRR1 = *(PRR1_reg_t*)0x65; -static volatile uint8_t& _OSCCAL = *(uint8_t*)0x66; -static volatile PCICR_reg_t& _PCICR = *(PCICR_reg_t*)0x68; -static volatile EICRA_reg_t& _EICRA = *(EICRA_reg_t*)0x69; -static volatile EICRB_reg_t& _EICRB = *(EICRB_reg_t*)0x6A; -static volatile _bit_reg_t& _PCMSK0 = *(_bit_reg_t*)0x6B; -static volatile TIMSK0_reg_t& _TIMSK0 = *(TIMSK0_reg_t*)0x6E; -static volatile TIMSK1_reg_t& _TIMSK1 = *(TIMSK1_reg_t*)0x6F; -static volatile TIMSK2_reg_t& _TIMSK2 = *(TIMSK2_reg_t*)0x70; -static volatile TIMSK3_reg_t& _TIMSK3 = *(TIMSK3_reg_t*)0x71; -static volatile XMCRA_reg_t& _XMCRA = *(XMCRA_reg_t*)0x74; -static volatile XMCRB_reg_t& _XMCRB = *(XMCRB_reg_t*)0x75; -static volatile uint16_t& _ADC = *(uint16_t*)0x78; -static volatile ADCSRA_reg_t& _ADCSRA = *(ADCSRA_reg_t*)0x7A; -static volatile ADCSRB_reg_t& _ADCSRB = *(ADCSRB_reg_t*)0x7B; -static volatile ADMUX_reg_t& _ADMUX = *(ADMUX_reg_t*)0x7C; -static volatile DIDR0_reg_t& _DIDR0 = *(DIDR0_reg_t*)0x7E; -static volatile DIDR1_reg_t& _DIDR1 = *(DIDR1_reg_t*)0x7F; -static volatile TIMER_dev_t& TIMER1 = *(TIMER_dev_t*)0x80; -static volatile TIMER_dev_t& TIMER3 = *(TIMER_dev_t*)0x90; -static volatile UHCON_reg_t& _UHCON = *(UHCON_reg_t*)0x9E; -static volatile UHINT_reg_t& _UHINT = *(UHINT_reg_t*)0x9F; -static volatile UHIEN_reg_t& _UHIEN = *(UHIEN_reg_t*)0xA0; -static volatile UHADDR_reg_t& _UHADDR = *(UHADDR_reg_t*)0xA1; -static volatile UHFNUM_reg_t& _UHFNUM = *(UHFNUM_reg_t*)0xA2; -static volatile uint8_t& _UHFLEN = *(uint8_t*)0xA4; -static volatile uint8_t& _UPINRQX = *(uint8_t*)0xA5; -static volatile UPINTX_reg_t& _UPINTX = *(UPINTX_reg_t*)0xA6; -static volatile UPNUM_reg_t& _UPNUM = *(UPNUM_reg_t*)0xA7; -static volatile UPRST_reg_t& _UPRST = *(UPRST_reg_t*)0xA8; -static volatile UPCONX_reg_t& _UPCONX = *(UPCONX_reg_t*)0xA9; +__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); +__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); +__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); +__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); +__AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); +__AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); +__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); +__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); +__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); +__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); +__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); +__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); +__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); +__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); +__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); +__AVR_DEFREG(uint8_t, _EEDR, 0x40); +__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); +__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); +__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); +__AVR_DEFREG(PLLCSR_reg_t, _PLLCSR, 0x49); +__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); +__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); +__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); +__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); +__AVR_DEFREG(uint8_t, _SPDR, 0x4E); +__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); +__AVR_DEFREG(uint8_t, _OCDR, 0x51); +__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); +__AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); +__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); +__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); +__AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); +__AVR_DEFREG(SP_reg_t, _SP, 0x5D); +__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); +__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); +__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); +__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); +__AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); +__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); +__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); +__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); +__AVR_DEFREG(EICRB_reg_t, _EICRB, 0x6A); +__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); +__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); +__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); +__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); +__AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); +__AVR_DEFREG(XMCRA_reg_t, _XMCRA, 0x74); +__AVR_DEFREG(XMCRB_reg_t, _XMCRB, 0x75); +__AVR_DEFREG(uint16_t, _ADC, 0x78); +__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); +__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); +__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); +__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); +__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); +__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); +__AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); +__AVR_DEFREG(UHCON_reg_t, _UHCON, 0x9E); +__AVR_DEFREG(UHINT_reg_t, _UHINT, 0x9F); +__AVR_DEFREG(UHIEN_reg_t, _UHIEN, 0xA0); +__AVR_DEFREG(UHADDR_reg_t, _UHADDR, 0xA1); +__AVR_DEFREG(UHFNUM_reg_t, _UHFNUM, 0xA2); +__AVR_DEFREG(uint8_t, _UHFLEN, 0xA4); +__AVR_DEFREG(uint8_t, _UPINRQX, 0xA5); +__AVR_DEFREG(UPINTX_reg_t, _UPINTX, 0xA6); +__AVR_DEFREG(UPNUM_reg_t, _UPNUM, 0xA7); +__AVR_DEFREG(UPRST_reg_t, _UPRST, 0xA8); +__AVR_DEFREG(UPCONX_reg_t, _UPCONX, 0xA9); _AVR_DEFREG(UPCFG0X, 0xAA); _AVR_DEFREG(UPCFG1X, 0xAB); _AVR_DEFREG(UPSTAX, 0xAC); -static volatile uint8_t& _UPCFG2X = *(uint8_t*)0xAD; +__AVR_DEFREG(uint8_t, _UPCFG2X, 0xAD); _AVR_DEFREG(UPIENX, 0xAE); -static volatile uint8_t& _UPDATX = *(uint8_t*)0xAF; -static volatile TIMER_8bit_dev_t& _TIMER2 = *(TIMER_8bit_dev_t*)0xB0; -static volatile ASSR_reg_t& _ASSR = *(ASSR_reg_t*)0xB6; -static volatile uint8_t& _TWBR = *(uint8_t*)0xB8; -static volatile TWSR_reg_t& _TWSR = *(TWSR_reg_t*)0xB9; -static volatile TWAR_reg_t& _TWAR = *(TWAR_reg_t*)0xBA; -static volatile uint8_t& _TWDR = *(uint8_t*)0xBB; -static volatile TWCR_reg_t& _TWCR = *(TWCR_reg_t*)0xBC; -static volatile TWAMR_reg_t& _TWAMR = *(TWAMR_reg_t*)0xBD; -static volatile USART_dev_t& USART1 = *(USART_dev_t*)0xC8; +__AVR_DEFREG(uint8_t, _UPDATX, 0xAF); +__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); +__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); +__AVR_DEFREG(uint8_t, _TWBR, 0xB8); +__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); +__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); +__AVR_DEFREG(uint8_t, _TWDR, 0xBB); +__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); +__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); +__AVR_DEFREG(USART_dev_t, USART1, 0xC8); _AVR_DEFREG(UHWCON, 0xD7); _AVR_DEFREG(USBCON, 0xD8); _AVR_DEFREG(USBSTA, 0xD9); @@ -1851,12 +1851,12 @@ _AVR_DEFREG(UECFG1X, 0xED); _AVR_DEFREG(UESTA0X, 0xEE); _AVR_DEFREG(UESTA1X, 0xEF); _AVR_DEFREG(UEIENX, 0xF0); -static uint8_t& _UEDATX = *(uint8_t*)0xF1; +__AVR_DEFREG(uint8_t, _UEDATx, 0xF1); _AVR_DEFREG(UEBCX, 0xF2); _AVR_DEFREG(UEINT, 0xF4); _AVR_DEFREG(UPERRX, 0xF5); _AVR_DEFREG(UPBCX, 0xF6); -static uint8_t& _UPINT = *(uint8_t*)0xF8; +__AVR_DEFREG(uint8_t, _UPINT, 0xF8); _AVR_DEFREG(OTGTCON, 0xF9); #endif @@ -2606,6 +2606,7 @@ struct pin_dev_state_t { uint8_t _COM1C : 2; uint8_t _COM2A : 2; uint8_t _COM2B : 2; + uint8_t _COM3A : 2; uint8_t _COM3B : 2; uint8_t _COM3C : 2; uint8_t _COM4A : 2; @@ -2633,7 +2634,14 @@ struct pin_dev_state_t { uint8_t _PCIE1 : 1; uint8_t _PCIE2 : 1; uint8_t _PCIE3 : 1; - uint8_t _ADCnD : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; uint8_t _SPE : 1; uint8_t _COM0A : 2; uint8_t _COM0B : 2; @@ -2647,6 +2655,7 @@ struct pin_dev_state_t { uint8_t _USART1_TXEN : 1; uint8_t _USART1_RXEN : 1; uint8_t _USART0_TXEN : 1; + uint8_t _USART0_RXEN : 1; #elif defined(__AVR_TRM03__) uint8_t _AS2 : 1; uint8_t _PCIE0 : 1; @@ -2660,7 +2669,14 @@ struct pin_dev_state_t { uint8_t _COM0A : 2; uint8_t _COM0B : 2; uint8_t _TWEN : 1; - uint8_t _ADCnD : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; uint8_t _UMSEL : 2; uint8_t _USART0_TXEN : 1; uint8_t _USART0_RXEN : 1; @@ -2677,7 +2693,14 @@ struct pin_dev_state_t { uint8_t _USART1_RXEN : 1; uint8_t _USART1_TXEN : 1; uint8_t _TWEN : 1; - uint8_t _INTn : 1; + uint8_t _INT7 : 1; + uint8_t _INT6 : 1; + uint8_t _INT5 : 1; + uint8_t _INT4 : 1; + uint8_t _INT3 : 1; + uint8_t _INT2 : 1; + uint8_t _INT1 : 1; + uint8_t _INT0; uint8_t _UVCONE : 1; uint8_t _UIDE : 1; //uint8_t _JTAGEN : 1; @@ -3087,1021 +3110,1288 @@ inline ATmegaPinInfo _ATmega_getPinInfo(uint8_t pin) { #endif } -inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { - ATmegaPinInfo info = _ATmega_getPinInfo(pin); - - // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that - // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should - // add power-reduction awareness to this logic! - - pin_dev_state_t state; - +enum class eATmegaPeripheral { + UNDEFINED, #if defined(__AVR_TRM01__) - // See page 75ff of ATmega2560 technical reference manual. - if (info.port == eATmegaPort::PORT_A) { - state._SRE = _XMCRA._SRE; - - _XMCRA._SRE = false; - } - else if (info.port == eATmegaPort::PORT_B) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - - if (info.pinidx == 7) { - state._COM1C = TIMER1._TCCRnA._COMnC; - - TIMER1._TCCRnA._COMnC = 0; - } - else if (info.pinidx == 6) { - state._COM1B = TIMER1._TCCRnA._COMnB; - - TIMER1._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 5) { - state._COM1A = TIMER1._TCCRnA._COMnA; - - TIMER1._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 4) { - state._COM2A = _TIMER2._TCCRnA._COMnA; - - _TIMER2._TCCRnA._COMnA = 0; - } - else if (info.pinidx <= 3) { - state._SPE = _SPCR._SPE; - - _SPCR._SPE = false; - } - } - else if (info.port == eATmegaPort::PORT_C) { - state._SRE = _XMCRA._SRE; - - _XMCRA._SRE = false; - } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 5 || info.pinidx == 3) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; - - USART1._UCSRnB._TXEN = false; - } - if (info.pinidx == 5 || info.pinidx == 2) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; - - USART1._UCSRnB._RXEN = false; - } - if (info.pinidx <= 3) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx >= 4 && info.pinidx <= 7) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - if (info.pinidx == 5) { - state._COM3C = TIMER3._TCCRnA._COMnC; - - TIMER3._TCCRnA._COMnC = 0; - } - if (info.pinidx == 4 || info.pinidx == 3) { - state._COM3B = TIMER3._TCCRnA._COMnB; - - TIMER3._TCCRnA._COMnB = 0; - } - if (info.pinidx == 2 || info.pinidx == 0) { - state._USART0_RXEN = USART0._UCSRnB._RXEN; + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PUSART2, PUSART3, PTIM3, PTIM4, PTIM5 +#elif defined(__AVR_TRM02__) + PADC, PUSART0, PSPI, PTIM1, PUSART1, PTIM0, PTIM2, PTWI, PTIM3 +#elif defined(__AVR_TRM03__) + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI +#elif defined(__AVR_TRM04__) + PADC, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PTIM3, PUSB +#endif + , NUM_PERIPHERALS +}; - USART0._UCSRnB._RXEN = false; - } - if (info.pinidx == 2 || info.pinidx == 1) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; +enum class eATmegaPinFunc : uint8_t { +#if defined(__AVR_TRM01__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, + PCI8, PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, + PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TOSC1, TOSC2, + TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, + TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, + USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, + TWI_SDA, TWI_CLK, + CLK0, PDO, PDI, + AIN0, AIN1, + ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 +#elif defined(__AVR_TRM02__) + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + EINT2, EINT1, EINT0, + TIMER3_ICP, + TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, + TIMER1_ICP, + TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, + AIN1, AIN0, + USART0_CLK, USART1_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, + CLK0, + TOSC2, TOSC1, + TWI_SDA, TWI_CLK +#elif defined(__AVR_TRM03__) + ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + XTAL2, XTAL1, + TOSC2, TOSC1, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, + TIMER1_ICP, + TIMER1_ECI, TIMER0_ECI, + TWI_CLK, TWI_SDA, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + CLK0, + AIN1, AIN0, + USART_CLK, + USART_TXD, USART_RXD, + EINT1, EINT0 +#elif defined(__AVR_TRM04__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, + CLK0, PDO, PDI, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TIMER3_ICP, TIMER1_ICP, + TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, + USART1_CLK, USART1_TXD, USART1_RXD, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + TWI_SDA, TWI_CLK, + AIN1, AIN0, + TOSC2, + UID, UVCON, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 +#endif + , NUM_FUNCS +}; - USART0._UCSRnB._TXEN = false; - } - if (info.pinidx == 0) { - state._PCIE1 = _PCICR._PCIE1; +#ifndef countof +#define countof(x) (sizeof(x) / sizeof(*x)) +#endif - _PCICR._PCIE1 = false; +struct ATmegaPinFunctions { + inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} + inline ATmegaPinFunctions() = default; + inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; + + const eATmegaPinFunc *funcs = nullptr; + uint8_t cnt = 0; + + inline bool hasFunc(eATmegaPinFunc query) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + + if (func == query) + return true; } + return false; } - // Port F ignored. - else if (info.port == eATmegaPort::PORT_G) { - if (info.pinidx == 5) { - state._COM0B = TIMER0._TCCRnA._COMnB; - TIMER0._TCCRnA._COMnB = 0; - } - if (info.pinidx == 4 || info.pinidx == 3) { - state._AS2 = _ASSR._AS2; + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; - _ASSR._AS2 = false; + cb(func); } - if (info.pinidx <= 2) { - state._SRE = _XMCRA._SRE; + } +}; - _XMCRA._SRE = false; - } +ATmegaPinFunctions _ATmega_getPinFunctions(int pin); + +struct ATmegaPinFuncSet { + inline ATmegaPinFuncSet() noexcept { + for (bool& f : this->funcs) + f = false; } - else if (info.port == eATmegaPort::PORT_H) { - if (info.pinidx == 6) { - state._COM2B = _TIMER2._TCCRnA._COMnB; + template + inline ATmegaPinFuncSet(eATmegaPinFunc func, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(func, ((funcItemType&&)items)...); + } + template + inline ATmegaPinFuncSet(int pin, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + addFromPin(pin, ((funcItemType&&)items)...); + } + inline ATmegaPinFuncSet(const ATmegaPinFuncSet&) = default; - _TIMER2._TCCRnA._COMnB = 0; - } - if (info.pinidx == 5) { - state._COM4C = TIMER4._TCCRnA._COMnC; + inline void add(eATmegaPinFunc value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPinFunc value, funcItemType&&... items) { + add(value); + add(((eATmegaPinFunc&&)items)...); + } - TIMER4._TCCRnA._COMnC = 0; - } - if (info.pinidx == 4) { - state._COM4B = TIMER4._TCCRnA._COMnB; + inline void addFromPin(int pin) noexcept { + ATmegaPinFunctions funcs = _ATmega_getPinFunctions(pin); - TIMER4._TCCRnA._COMnB = 0; - } - if (info.pinidx == 3) { - state._COM4A = TIMER4._TCCRnA._COMnA; + funcs.iterate( + [this]( eATmegaPinFunc func ) noexcept { + this->add(func); + } + ); + } + template + inline void addFromPin(int pin, itemType&&... items) noexcept { + addFromPin(pin); + addFromPin(((itemType&&)items)...); + } - TIMER4._TCCRnA._COMnA = 0; - } - if (info.pinidx == 2 || info.pinidx == 0) { - state._USART2_RXEN = USART2._UCSRnB._RXEN; + inline bool hasFunc(eATmegaPinFunc value) const noexcept { + return this->funcs[(uint8_t)value]; + } - USART2._UCSRnB._RXEN = false; - } - if (info.pinidx == 2 || info.pinidx == 1) { - state._USART2_TXEN = USART2._UCSRnB._TXEN; + inline bool hasAnyFunc() const noexcept { + return false; + } + template + inline bool hasAnyFunc(funcItem&& item, otherFuncItem&&... funcs) const noexcept { + return hasFunc(item) || hasAnyFunc(((otherFuncItem&&)funcs)...); + } - USART2._UCSRnB._TXEN = false; + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(this->funcs); n++) { + const bool& f = this->funcs[n]; + if (f) { + cb((eATmegaPinFunc)n); + } } } - else if (info.port == eATmegaPort::PORT_J) { - if (info.pinidx <= 6) { - state._PCIE1 = _PCICR._PCIE1; - _PCICR._PCIE1 = false; - } - if (info.pinidx == 2 || info.pinidx == 0) { - state._USART3_RXEN = USART3._UCSRnB._RXEN; +private: + bool funcs[(uint8_t)eATmegaPinFunc::NUM_FUNCS]; +}; - USART3._UCSRnB._RXEN = false; - } - if (info.pinidx == 2 || info.pinidx == 1) { - state._USART3_TXEN = USART3._UCSRnB._TXEN; +inline void _ATmega_setPeripheralPower(eATmegaPeripheral peri, bool fullPower) { + bool reducePower = (fullPower == false); + switch(peri) { +#if defined(__AVR_TRM01__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PUSART2: _PRR1._PRUSART2 = reducePower; break; + case eATmegaPeripheral::PUSART3: _PRR1._PRUSART3 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PTIM4: _PRR1._PRTIM4 = reducePower; break; + case eATmegaPeripheral::PTIM5: _PRR1._PRTIM5 = reducePower; break; +#elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR0._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; +#elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; +#elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PUSB: _PRR1._PRUSB = reducePower; break; +#endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } +} - USART3._UCSRnB._TXEN = false; - } +inline bool _ATmega_getPeripheralPower(eATmegaPeripheral peri) { + switch(peri) { +#if defined(__AVR_TRM01__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PUSART2: return _PRR1._PRUSART2 == false; + case eATmegaPeripheral::PUSART3: return _PRR1._PRUSART3 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PTIM4: return _PRR1._PRTIM4 == false; + case eATmegaPeripheral::PTIM5: return _PRR1._PRTIM5 == false; +#elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PUSART1: return _PRR0._PRUSART1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; +#elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; +#elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PUSB: return _PRR1._PRUSB == false; +#endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } + return false; +} + +inline eATmegaPeripheral _ATmega_getPeripheralForFunc( eATmegaPinFunc func ) { + // In C++20 there is the "using-enum" statement. I wish we had C++20 over here... + //using enum eATmegaPinFunc + switch(func) { +#if defined(__AVR_TRM01__) + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1C: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC4A: case eATmegaPinFunc::TOC4B: case eATmegaPinFunc::TOC4C: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TOC5A: case eATmegaPinFunc::TOC5B: case eATmegaPinFunc::TOC5C: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_CLKI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER3_CLKI: case eATmegaPinFunc::TIMER3_ICP: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER4_CLKI: case eATmegaPinFunc::TIMER4_ICP: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TIMER5_CLKI: case eATmegaPinFunc::TIMER5_ICP: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::USART2_CLK: case eATmegaPinFunc::USART2_TXD: case eATmegaPinFunc::USART2_RXD: return eATmegaPeripheral::PUSART2; + case eATmegaPinFunc::USART3_CLK: case eATmegaPinFunc::USART3_TXD: case eATmegaPinFunc::USART3_RXD: return eATmegaPeripheral::PUSART3; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::ADC15: case eATmegaPinFunc::ADC14: case eATmegaPinFunc::ADC13: case eATmegaPinFunc::ADC12: case eATmegaPinFunc::ADC11: case eATmegaPinFunc::ADC10: case eATmegaPinFunc::ADC9: case eATmegaPinFunc::ADC8: + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; +#elif defined(__AVR_TRM02__) + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_ECI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ECI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3A: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; +#elif defined(__AVR_TRM03__) + case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_ECI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TWI_CLK: case eATmegaPinFunc::TWI_SDA: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::USART_CLK: case eATmegaPinFunc::USART_TXD: case eATmegaPinFunc::USART_RXD: return eATmegaPeripheral::PUSART0; +#elif defined(__AVR_TRM04__) + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1C: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_CLKI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_CLKI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::UID: case eATmegaPinFunc::UVCON: return eATmegaPeripheral::PUSB; + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; +#endif + // There are quite some pin functions that have no peripheral assignment, and that is OK! + default: break; + } + return eATmegaPeripheral::UNDEFINED; +} + +struct ATmegaPeripheralSet { + inline ATmegaPeripheralSet() noexcept { + for (bool& f : this->funcs) + f = false; } - else if (info.port == eATmegaPort::PORT_K) { - state._PCIE2 = _PCICR._PCIE2; + template + inline ATmegaPeripheralSet(funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(((eATmegaPinFunc&&)items)...); + } + inline ATmegaPeripheralSet(const ATmegaPeripheralSet&) = default; - _PCICR._PCIE2 = false; + inline void add(eATmegaPeripheral value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPeripheral value, funcItemType&&... items) noexcept { + add(value); + add(((funcItemType&&)items)...); } - else if (info.port == eATmegaPort::PORT_L) { - if (info.pinidx == 5) { - state._COM5C = TIMER5._TCCRnA._COMnC; - TIMER5._TCCRnA._COMnC = 0; - } - if (info.pinidx == 4) { - state._COM5B = TIMER5._TCCRnA._COMnB; + inline bool hasItem(eATmegaPeripheral value) const noexcept { + return this->funcs[(uint8_t)value]; + } + template + inline bool hasItem(eATmegaPeripheral&& item, otherFuncItem&&... funcs) const noexcept { + return hasItem(item) || hasItem(((otherFuncItem&&)funcs)...); + } - TIMER5._TCCRnA._COMnB = 0; + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(funcs); n++) { + const bool& f = this->funcs[n]; + if (f) { + cb( (eATmegaPeripheral)n ); + } } - if (info.pinidx == 3) { - state._COM5A = TIMER5._TCCRnA._COMnA; + } - TIMER5._TCCRnA._COMnA = 0; - } + inline void fromPinFuncs(const ATmegaPinFuncSet& funcSet) { + funcSet.iterate( + [this]( eATmegaPinFunc func ) noexcept { + this->add( _ATmega_getPeripheralForFunc(func) ); + } + ); } -#elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { + +private: + bool funcs[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; +}; + +struct ATmegaPeripheralPowerGate { + inline ATmegaPeripheralPowerGate(ATmegaPeripheralSet& periSet) noexcept : periSet(periSet) { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + this->states[(uint8_t)peri] = _ATmega_getPeripheralPower(peri); + _ATmega_setPeripheralPower(peri, true); + } + ); + } + inline ATmegaPeripheralPowerGate(const ATmegaPeripheralPowerGate&) = delete; + + inline ~ATmegaPeripheralPowerGate() { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + _ATmega_setPeripheralPower(peri, this->states[(uint8_t)peri]); + } + ); + } + + inline ATmegaPeripheralPowerGate& operator = (const ATmegaPeripheralPowerGate&) = delete; + +private: + ATmegaPeripheralSet& periSet; + bool states[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; +}; + +inline pin_dev_state_t _ATmega_savePinAlternates(const ATmegaPinFuncSet& funcSet) { + // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that + // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should + // add power-reduction awareness to this logic! + + pin_dev_state_t state; + + ATmegaPeripheralSet periSet; + periSet.fromPinFuncs(funcSet); + + ATmegaPeripheralPowerGate pgate(periSet); + +#if defined(__AVR_TRM01__) + // See page 75ff of ATmega2560 technical reference manual. + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + state._SRE = _XMCRA._SRE; + + _XMCRA._SRE = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { state._PCIE0 = _PCICR._PCIE0; _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; - if (info.pinidx == 7) { - state._ADCnD = _DIDR0._ADC7D; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; - _DIDR0._ADC7D = false; - } - else if (info.pinidx == 6) { - state._ADCnD = _DIDR0._ADC6D; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; - _DIDR0._ADC6D = false; - } - else if (info.pinidx == 5) { - state._ADCnD = _DIDR0._ADC5D; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; - _DIDR0._ADC5D = false; - } - else if (info.pinidx == 4) { - state._ADCnD = _DIDR0._ADC4D; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; - _DIDR0._ADC4D = false; - } - else if (info.pinidx == 3) { - state._ADCnD = _DIDR0._ADC3D; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; - _DIDR0._ADC3D = false; - } - else if (info.pinidx == 2) { - state._ADCnD = _DIDR0._ADC2D; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + state._COM3C = TIMER3._TCCRnA._COMnC; - _DIDR0._ADC2D = false; - } - else if (info.pinidx == 1) { - state._ADCnD = _DIDR0._ADC1D; + TIMER3._TCCRnA._COMnC = 0; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + state._COM3B = TIMER3._TCCRnA._COMnB; - _DIDR0._ADC1D = false; - } - else if (info.pinidx == 0) { - state._ADCnD = _DIDR0._ADC0D; + TIMER3._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + state._COM3A = TIMER3._TCCRnA._COMnA; - _DIDR0._ADC0D = false; - } + TIMER3._TCCRnA._COMnA = 0; } - else if (info.port == eATmegaPort::PORT_B) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + + USART0._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { state._PCIE1 = _PCICR._PCIE1; _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; - if (info.pinidx <= 7 && info.pinidx >= 4) { - state._SPE = _SPCR._SPE; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; - _SPCR._SPE = false; - } - - if (info.pinidx == 4) { - state._COM0A = TIMER0._TCCRnA._COMnA; + _ASSR._AS2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; - TIMER0._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 5) { - state._COM0B = TIMER0._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + state._COM4C = TIMER4._TCCRnA._COMnC; - TIMER0._TCCRnA._COMnB = 0; - } + TIMER4._TCCRnA._COMnC = 0; } - else if (info.port == eATmegaPort::PORT_C) { - state._AS2 = _ASSR._AS2; - state._PCIE2 = _PCICR._PCIE2; + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + state._COM4B = TIMER4._TCCRnA._COMnB; - _ASSR._AS2 = false; - _PCICR._PCIE2 = false; + TIMER4._TCCRnA._COMnB = 0; } - else if (info.port == eATmegaPort::PORT_D) { - state._PCIE3 = _PCICR._PCIE3; + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + state._COM4A = TIMER4._TCCRnA._COMnA; - _PCICR._PCIE3 = false; + TIMER4._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_RXEN = USART2._UCSRnB._RXEN; - if (info.pinidx == 7) { - state._COM2A = _TIMER2._TCCRnA._COMnA; + USART2._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_TXEN = USART2._UCSRnB._TXEN; - _TIMER2._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 6) { - state._COM2B = _TIMER2._TCCRnA._COMnB; + USART2._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_RXEN = USART3._UCSRnB._RXEN; - _TIMER2._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 5) { - state._COM1A = TIMER1._TCCRnA._COMnA; + USART3._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_TXEN = USART3._UCSRnB._TXEN; - TIMER1._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 4) { - state._COM1B = TIMER1._TCCRnA._COMnB; + USART3._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { + state._PCIE2 = _PCICR._PCIE2; - TIMER1._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 3) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + state._COM5C = TIMER5._TCCRnA._COMnC; - USART1._UCSRnB._TXEN = false; - } - else if (info.pinidx == 2 || info.pinidx == 0) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; + TIMER5._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + state._COM5B = TIMER5._TCCRnA._COMnB; - USART1._UCSRnB._RXEN = false; - } - else if (info.pinidx == 1) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; + TIMER5._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + state._COM5A = TIMER5._TCCRnA._COMnA; - USART0._UCSRnB._TXEN = false; - } + TIMER5._TCCRnA._COMnA = 0; } -#elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { +#elif defined(__AVR_TRM02__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { state._PCIE0 = _PCICR._PCIE0; _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + state._ADC7D = _DIDR0._ADC7D; - if (info.pinidx <= 7 && info.pinidx <= 6) { - state._AS2 = _ASSR._AS2; + _DIDR0._ADC7D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + state._ADC6D = _DIDR0._ADC6D; - _ASSR._AS2 = false; - } - else if (info.pinidx <= 5 && info.pinidx >= 2) { - state._SPE = _SPCR._SPE; + _DIDR0._ADC6D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; - _SPCR._SPE = false; - } + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; - if (info.pinidx == 3) { - state._COM2A = _TIMER2._TCCRnA._COMnA; + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; - _TIMER2._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 2) { - state._COM1B = TIMER1._TCCRnA._COMnB; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; - TIMER1._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 1) { - state._COM1A = TIMER1._TCCRnA._COMnA; + _DIDR0._ADC2D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; - TIMER1._TCCRnA._COMnA = 0; - } + _DIDR0._ADC1D = false; } - else if (info.port == eATmegaPort::PORT_C) { + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + + _DIDR0._ADC0D = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { state._PCIE1 = _PCICR._PCIE1; _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; - if (info.pinidx <= 5 && info.pinidx >= 4) { - state._TWEN = _TWCR._TWEN; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; - _TWCR._TWEN = false; - } + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; - if (info.pinidx == 5) { - state._ADCnD = _DIDR0._ADC5D; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; - _DIDR0._ADC5D = false; - } - else if (info.pinidx == 4) { - state._ADCnD = _DIDR0._ADC4D; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; - _DIDR0._ADC4D = false; - } - if (info.pinidx == 3) { - state._ADCnD = _DIDR0._ADC3D; + _PCICR._PCIE2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + state._PCIE3 = _PCICR._PCIE3; - _DIDR0._ADC3D = false; - } - if (info.pinidx == 2) { - state._ADCnD = _DIDR0._ADC2D; + _PCICR._PCIE3 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; - _DIDR0._ADC2D = false; - } - if (info.pinidx == 1) { - state._ADCnD = _DIDR0._ADC1D; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; - _DIDR0._ADC1D = false; - } - if (info.pinidx == 0) { - state._ADCnD = _DIDR0._ADC0D; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; - _DIDR0._ADC0D = false; - } + TIMER1._TCCRnA._COMnA = 0; } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 2) { - state._PCIE1 = _PCICR._PCIE1; + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; - _PCICR._PCIE1 = false; - } - else { - state._PCIE2 = _PCICR._PCIE2; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; - _PCICR._PCIE2 = false; - } + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; - if (info.pinidx == 6) { - state._COM0A = TIMER0._TCCRnA._COMnA; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; - TIMER0._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 5) { - state._COM0B = TIMER0._TCCRnA._COMnB; + USART0._UCSRnB._TXEN = false; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; - TIMER0._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 4) { - state._UMSEL = USART0._UCSRnC._UMSEL; + USART0._UCSRnB._RXEN = false; + } +#elif defined(__AVR_TRM03__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; - USART0._UCSRnC._UMSEL = 0; - } - else if (info.pinidx == 3) { - state._COM2B = _TIMER2._TCCRnA._COMnB; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; - _TIMER2._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 1) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; - USART0._UCSRnB._TXEN = false; - } - else if (info.pinidx == 0) { - state._USART0_RXEN = USART0._UCSRnB._RXEN; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; - USART0._UCSRnB._RXEN = false; - } + _TIMER2._TCCRnA._COMnA = 0; } -#elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { - state._SRE = _XMCRA._SRE; + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; - _XMCRA._SRE = false; + TIMER1._TCCRnA._COMnB = 0; } - else if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - state._COM1C = TIMER1._TCCRnA._COMnC; + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; - TIMER1._TCCRnA._COMnC = 0; - } - else if (info.pinidx == 6) { - state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; - TIMER1._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 5) { - state._COM1A = TIMER1._TCCRnA._COMnA; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + state._TWEN = _TWCR._TWEN; - TIMER1._TCCRnA._COMnA = 0; - } - else if (info.pinidx == 4) { - state._COM2A = _TIMER2._TCCRnA._COMnA; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; - _TIMER2._TCCRnA._COMnA = 0; - } - else if (info.pinidx <= 3) { - state._SPE = _SPCR._SPE; + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; - _SPCR._SPE = false; - } + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; - state._PCIE0 = _PCICR._PCIE0; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; - _PCICR._PCIE0 = false; + _DIDR0._ADC2D = false; } - else if (info.port == eATmegaPort::PORT_C) { + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; + + _DIDR0._ADC1D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + + _DIDR0._ADC0D = false; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + state._UMSEL = USART0._UCSRnC._UMSEL; + + USART0._UCSRnC._UMSEL = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + + USART0._UCSRnB._RXEN = false; + } +#elif defined(__AVR_TRM04__) + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { state._SRE = _XMCRA._SRE; _XMCRA._SRE = false; } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 5) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; - state._USART1_TXEN = USART1._UCSRnB._TXEN; + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; - USART1._UCSRnB._RXEN = false; - USART1._UCSRnB._TXEN = false; - } - else if (info.pinidx == 3) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; - USART1._UCSRnB._TXEN = false; - } - else if (info.pinidx == 2) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; - USART1._UCSRnB._RXEN = false; - } - else if (info.pinidx <= 1) { - state._TWEN = _TWCR._TWEN; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; - _TWCR._TWEN = false; - } + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; - if (info.pinidx == 1) { - state._COM2B = _TIMER2._TCCRnA._COMnB; + _SPCR._SPE = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; - _TIMER2._TCCRnA._COMnB = 0; - } - else if (info.pinidx == 0) { - state._COM0B = TIMER0._TCCRnA._COMnB; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; - TIMER0._TCCRnA._COMnB = 0; - } + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; - if (info.pinidx == 3) { - state._INTn = _EIMSK._INT3; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + state._TWEN = _TWCR._TWEN; - _EIMSK._INT3 = false; - } - else if (info.pinidx == 2) { - state._INTn = _EIMSK._INT2; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; - _EIMSK._INT2 = false; - } - else if (info.pinidx == 1) { - state._INTn = _EIMSK._INT1; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; - _EIMSK._INT1 = false; - } - else if (info.pinidx == 0) { - state._INTn = _EIMSK._INT0; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + state._INT3 = _EIMSK._INT3; - _EIMSK._INT0 = false; - } + _EIMSK._INT3 = false; } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx == 7) { - state._UVCONE = _UHWCON._UVCONE; + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + state._INT2 = _EIMSK._INT2; - _UHWCON._UVCONE = false; - } - else if (info.pinidx == 3) { - state._UIDE = _UHWCON._UIDE; + _EIMSK._INT2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + state._INT1 = _EIMSK._INT1; - _UHWCON._UIDE = false; - } - else if (info.pinidx <= 2) { - state._SRE = _XMCRA._SRE; + _EIMSK._INT1 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + state._INT0 = _EIMSK._INT0; - _XMCRA._SRE = false; - } + _EIMSK._INT0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + state._UVCONE = _UHWCON._UVCONE; - if (info.pinidx == 7) { - state._INTn = _EIMSK._INT7; + _UHWCON._UVCONE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + state._UIDE = _UHWCON._UIDE; - _EIMSK._INT7 = false; - } - else if (info.pinidx == 6) { - state._INTn = _EIMSK._INT6; + _UHWCON._UIDE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + state._INT7 = _EIMSK._INT7; - _EIMSK._INT6 = false; - } - else if (info.pinidx == 5) { - state._INTn = _EIMSK._INT5; + _EIMSK._INT7 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + state._INT6 = _EIMSK._INT6; - _EIMSK._INT5 = false; - } - else if (info.pinidx == 4) { - state._INTn = _EIMSK._INT4; + _EIMSK._INT6 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + state._INT5 = _EIMSK._INT5; - _EIMSK._INT4 = false; - } + _EIMSK._INT5 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + state._INT4 = _EIMSK._INT4; + + _EIMSK._INT4 = false; } - // Ignore port F. #endif return state; } -inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& state) { - ATmegaPinInfo info = _ATmega_getPinInfo(pin); +inline void _ATmega_restorePinAlternates(const ATmegaPinFuncSet& funcSet, const pin_dev_state_t& state) { + ATmegaPeripheralSet periSet; + periSet.fromPinFuncs(funcSet); + + ATmegaPeripheralPowerGate pgate(periSet); #if defined(__AVR_TRM01__) // See page 75ff of ATmega2560 technical reference manual. - if (info.port == eATmegaPort::PORT_A) { + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { _XMCRA._SRE = state._SRE; } - else if (info.port == eATmegaPort::PORT_B) { + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { _PCICR._PCIE0 = state._PCIE0; - - if (info.pinidx == 7) { - TIMER1._TCCRnA._COMnC = state._COM1C; - } - else if (info.pinidx == 6) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - else if (info.pinidx == 5) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - else if (info.pinidx == 4) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - else if (info.pinidx <= 3) { - _SPCR._SPE = state._SPE; - } } - else if (info.port == eATmegaPort::PORT_C) { - _XMCRA._SRE = state._SRE; + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 5 || info.pinidx == 3) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - if (info.pinidx == 5 || info.pinidx == 2) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - if (info.pinidx <= 3) { - _PCICR._PCIE0 = state._PCIE0; - } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx >= 4 && info.pinidx <= 7) { - _PCICR._PCIE0 = state._PCIE0; - } - if (info.pinidx == 5) { - TIMER3._TCCRnA._COMnC = state._COM3C; - } - if (info.pinidx == 4 || info.pinidx == 3) { - TIMER3._TCCRnA._COMnB = state._COM3B; - } - if (info.pinidx == 2 || info.pinidx == 0) { - USART0._UCSRnB._RXEN = state._USART0_RXEN; - } - if (info.pinidx == 2 || info.pinidx == 1) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } - if (info.pinidx == 0) { - _PCICR._PCIE1 = state._PCIE1; - } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; } - // Port F ignored. - else if (info.port == eATmegaPort::PORT_G) { - if (info.pinidx == 5) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - if (info.pinidx == 4 || info.pinidx == 3) { - _ASSR._AS2 = state._AS2; - } - if (info.pinidx <= 2) { - _XMCRA._SRE = state._SRE; - } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; } - else if (info.port == eATmegaPort::PORT_H) { - if (info.pinidx == 6) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - if (info.pinidx == 5) { - TIMER4._TCCRnA._COMnC = state._COM4C; - } - if (info.pinidx == 4) { - TIMER4._TCCRnA._COMnB = state._COM4B; - } - if (info.pinidx == 3) { - TIMER4._TCCRnA._COMnA = state._COM4A; - } - if (info.pinidx == 2 || info.pinidx == 0) { - USART2._UCSRnB._RXEN = state._USART2_RXEN; - } - if (info.pinidx == 2 || info.pinidx == 1) { - USART2._UCSRnB._TXEN = state._USART2_TXEN; - } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + TIMER3._TCCRnA._COMnC = state._COM3C; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + TIMER3._TCCRnA._COMnB = state._COM3B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + TIMER3._TCCRnA._COMnA = state._COM3A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + TIMER4._TCCRnA._COMnC = state._COM4C; } - else if (info.port == eATmegaPort::PORT_J) { - if (info.pinidx <= 6) { - _PCICR._PCIE1 = state._PCIE1; - } - if (info.pinidx == 2 || info.pinidx == 0) { - USART3._UCSRnB._RXEN = state._USART3_RXEN; - } - if (info.pinidx == 2 || info.pinidx == 1) { - USART3._UCSRnB._TXEN = state._USART3_TXEN; - } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + TIMER4._TCCRnA._COMnB = state._COM4B; } - else if (info.port == eATmegaPort::PORT_K) { + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + TIMER4._TCCRnA._COMnA = state._COM4A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._RXEN = state._USART2_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._TXEN = state._USART2_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._RXEN = state._USART3_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._TXEN = state._USART3_TXEN; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { _PCICR._PCIE2 = state._PCIE2; } - else if (info.port == eATmegaPort::PORT_L) { - if (info.pinidx == 5) { - TIMER5._TCCRnA._COMnC = state._COM5C; - } - if (info.pinidx == 4) { - TIMER5._TCCRnA._COMnB = state._COM5B; - } - if (info.pinidx == 3) { - TIMER5._TCCRnA._COMnA = state._COM5A; - } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + TIMER5._TCCRnA._COMnC = state._COM5C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + TIMER5._TCCRnA._COMnB = state._COM5B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + TIMER5._TCCRnA._COMnA = state._COM5A; } #elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { _PCICR._PCIE0 = state._PCIE0; - - if (info.pinidx == 7) { - _DIDR0._ADC7D = state._ADCnD; - } - else if (info.pinidx == 6) { - _DIDR0._ADC6D = state._ADCnD; - } - else if (info.pinidx == 5) { - _DIDR0._ADC5D = state._ADCnD; - } - else if (info.pinidx == 4) { - _DIDR0._ADC4D = state._ADCnD; - } - else if (info.pinidx == 3) { - _DIDR0._ADC3D = state._ADCnD; - } - else if (info.pinidx == 2) { - _DIDR0._ADC2D = state._ADCnD; - } - else if (info.pinidx == 1) { - _DIDR0._ADC1D = state._ADCnD; - } - else if (info.pinidx == 0) { - _DIDR0._ADC0D = state._ADCnD; - } } - else if (info.port == eATmegaPort::PORT_B) { + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + _DIDR0._ADC7D = state._ADC7D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + _DIDR0._ADC6D = state._ADC6D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { _PCICR._PCIE1 = state._PCIE1; - - if (info.pinidx <= 7 && info.pinidx >= 4) { - _SPCR._SPE = state._SPE; - } - - if (info.pinidx == 4) { - TIMER0._TCCRnA._COMnA = state._COM0A; - } - else if (info.pinidx == 5) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } } - else if (info.port == eATmegaPort::PORT_C) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { _PCICR._PCIE2 = state._PCIE2; } - else if (info.port == eATmegaPort::PORT_D) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { _PCICR._PCIE3 = state._PCIE3; - - if (info.pinidx == 7) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - else if (info.pinidx == 6) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - else if (info.pinidx == 5) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - else if (info.pinidx == 4) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - else if (info.pinidx == 3) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - else if (info.pinidx == 2 || info.pinidx == 0) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - else if (info.pinidx == 1) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; } #elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { _PCICR._PCIE0 = state._PCIE0; - - if (info.pinidx <= 7 && info.pinidx <= 6) { - _ASSR._AS2 = state._AS2; - } - else if (info.pinidx <= 5 && info.pinidx >= 2) { - _SPCR._SPE = state._SPE; - } - - if (info.pinidx == 3) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - else if (info.pinidx == 2) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - else if (info.pinidx == 1) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } } - else if (info.port == eATmegaPort::PORT_C) { + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { _PCICR._PCIE1 = state._PCIE1; - - if (info.pinidx <= 5 && info.pinidx >= 4) { - _TWCR._TWEN = state._TWEN; - } - - if (info.pinidx == 5) { - _DIDR0._ADC5D = state._ADCnD; - } - else if (info.pinidx == 4) { - _DIDR0._ADC4D = state._ADCnD; - } - if (info.pinidx == 3) { - _DIDR0._ADC3D = state._ADCnD; - } - if (info.pinidx == 2) { - _DIDR0._ADC2D = state._ADCnD; - } - if (info.pinidx == 1) { - _DIDR0._ADC1D = state._ADCnD; - } - if (info.pinidx == 0) { - _DIDR0._ADC0D = state._ADCnD; - } } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 2) { - _PCICR._PCIE1 = state._PCIE1; - } - else { - _PCICR._PCIE2 = state._PCIE2; - } - - if (info.pinidx == 6) { - TIMER0._TCCRnA._COMnA = state._COM0A; - } - else if (info.pinidx == 5) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - else if (info.pinidx == 4) { - USART0._UCSRnC._UMSEL = state._UMSEL; - } - else if (info.pinidx == 3) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - else if (info.pinidx == 1) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } - else if (info.pinidx == 0) { - USART0._UCSRnB._RXEN = state._USART0_RXEN; - } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + USART0._UCSRnC._UMSEL = state._UMSEL; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; } #elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { _XMCRA._SRE = state._SRE; } - else if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - TIMER1._TCCRnA._COMnC = state._COM1C; - } - else if (info.pinidx == 6) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - else if (info.pinidx == 5) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - else if (info.pinidx == 4) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - else if (info.pinidx <= 3) { - _SPCR._SPE = state._SPE; - } - + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { _PCICR._PCIE0 = state._PCIE0; } - else if (info.port == eATmegaPort::PORT_C) { - _XMCRA._SRE = state._SRE; + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 5) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - else if (info.pinidx == 3) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - else if (info.pinidx == 2) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - else if (info.pinidx <= 1) { - _TWCR._TWEN = state._TWEN; - } - - if (info.pinidx == 1) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - else if (info.pinidx == 0) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - - if (info.pinidx == 3) { - _EIMSK._INT3 = state._INTn; - } - else if (info.pinidx == 2) { - _EIMSK._INT2 = state._INTn; - } - else if (info.pinidx == 1) { - _EIMSK._INT1 = state._INTn; - } - else if (info.pinidx == 0) { - _EIMSK._INT0 = state._INTn; - } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx == 7) { - _UHWCON._UVCONE = state._UVCONE; - } - else if (info.pinidx == 3) { - _UHWCON._UIDE = state._UIDE; - } - else if (info.pinidx <= 2) { - _XMCRA._SRE = state._SRE; - } - - if (info.pinidx == 7) { - _EIMSK._INT7 = state._INTn; - } - else if (info.pinidx == 6) { - _EIMSK._INT6 = state._INTn; - } - else if (info.pinidx == 5) { - _EIMSK._INT5 = state._INTn; - } - else if (info.pinidx == 4) { - _EIMSK._INT4 = state._INTn; - } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + _EIMSK._INT3 = state._INT3; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + _EIMSK._INT2 = state._INT2; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + _EIMSK._INT1 = state._INT1; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + _EIMSK._INT0 = state._INT0; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + _UHWCON._UVCONE = state._UVCONE; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + _UHWCON._UIDE = state._UIDE; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + _EIMSK._INT7 = state._INT7; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + _EIMSK._INT6 = state._INT6; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + _EIMSK._INT5 = state._INT5; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + _EIMSK._INT4 = state._INT4; } - // Ignore port F. #endif } -enum class eATmegaPinFunc { -#if defined(__AVR_TRM01__) - EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, - EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, - EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, - EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, - PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, PCI8, - PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, - PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, - SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, - TOSC1, TOSC2, - TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, - TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, - USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, - USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, - TWI_SDA, TWI_CLK, - CLK0, PDO, PDI, - AIN0, AIN1, - ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 -#elif defined(__AVR_TRM02__) - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, - SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, - PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, - PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, - PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, - EINT2, EINT1, EINT0, - TIMER3_ICP, - TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, - TIMER1_ICP, - TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, - AIN1, AIN0, - USART0_CLK, USART1_CLK, - USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, - CLK0, - TOSC2, TOSC1, - TWI_SDA, TWI_CLK -#elif defined(__AVR_TRM03__) - ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, - XTAL2, XTAL1, - TOSC2, TOSC1, - SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, - TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, - TIMER1_ICP, - TIMER1_ECI, TIMER0_ECI, - TWI_CLK, TWI_SDA, - PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, - PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, - PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, - CLK0, - AIN1, AIN0, - USART_CLK, - USART_TXD, USART_RXD, - EINT1, EINT0 -#elif defined(__AVR_TRM04__) - EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, - EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, - EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, - CLK0, PDO, PDI, - SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, - TIMER3_ICP, TIMER1_ICP, - TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, - USART1_CLK, USART1_TXD, USART1_RXD, - EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, - PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, - TWI_SDA, TWI_CLK, - AIN1, AIN0, - TOSC2, - UID, UVCON, - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 -#endif -}; - -struct ATmegaPinFunctions { - inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} - inline ATmegaPinFunctions() = default; - inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; - - const eATmegaPinFunc *funcs = nullptr; - uint8_t cnt = 0; - - inline bool hasFunc(eATmegaPinFunc query) const { - for (uint8_t n = 0; n < this->cnt; n++) { - eATmegaPinFunc func = this->funcs[n]; - - if (func == query) - return true; - } - return false; - } -}; +inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { + return _ATmega_savePinAlternates({pin}); +} -ATmegaPinFunctions _ATmega_getPinFunctions(int pin); +inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& state) { + _ATmega_restorePinAlternate({pin}, state); +} #ifndef LOW #define LOW 0 @@ -4166,7 +4456,7 @@ inline void _ATmega_digitalWrite(int pin, int state) { if (info.port == eATmegaPort::PORT_B) { _PORTB._PORT.setValue(info.pinidx, state == HIGH); } - else if (info.port == eATmegaPOrt::PORT_C) { + else if (info.port == eATmegaPort::PORT_C) { _PORTC._PORT.setValue(info.pinidx, state == HIGH); } else if (info.port == eATmegaPort::PORT_D) { @@ -4252,7 +4542,7 @@ inline int _ATmega_digitalRead(int pin) { if (info.port == eATmegaPort::PORT_B) { value = _PORTB._PIN.getValue(info.pinidx); } - else if (info.port == eATmegaPOrt::PORT_C) { + else if (info.port == eATmegaPort::PORT_C) { value = _PORTC._PIN.getValue(info.pinidx); } else if (info.port == eATmegaPort::PORT_D) { @@ -4345,7 +4635,7 @@ inline void _ATmega_pinMode(int pin, int mode) { if (info.port == eATmegaPort::PORT_B) { _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); } - else if (info.port == eATmegaPOrt::PORT_C) { + else if (info.port == eATmegaPort::PORT_C) { _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); } else if (info.port == eATmegaPort::PORT_D) { @@ -4429,7 +4719,7 @@ struct _ATmega_efuse { #define AVR_DEFAULT_EFUSE_VALUE 0xF9 #endif -#elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +#else //if defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) struct _ATmega_efuse { uint8_t _BODLEVEL : 3; uint8_t reserved1 : 5; @@ -4455,7 +4745,7 @@ struct _ATmega_hfuse { #define AVR_DEFAULT_HFUSE_VALUE 0xCF #endif -#elif defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +#else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) struct _ATmega_hfuse { uint8_t _BOOTRST : 1; uint8_t _BOOTSZ : 2; From a4098c7b95c0abb435e7c8bcb8d7f53252342ffb Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Sat, 10 Dec 2022 11:31:11 +0100 Subject: [PATCH 35/83] - added spiSetupChipSelect function which is used to initialize the usage of a pin as SPI-protocol chip-select (and no other purpose!) - searched for SPI CS initializations and converted them to use the new spiSetupChipSelect function --- Marlin/src/HAL/AVR/HAL_SPI_shared.cpp | 43 +++++++++++++++++++ Marlin/src/HAL/AVR/registers.h | 4 ++ Marlin/src/HAL/DUE/HAL_SPI.cpp | 16 +++++++ Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 4 ++ Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp | 4 ++ Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp | 9 ++-- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 4 ++ Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp | 4 ++ Marlin/src/HAL/LPC1768/main.cpp | 4 +- Marlin/src/HAL/SAMD51/HAL_SPI.cpp | 4 ++ Marlin/src/HAL/STM32/HAL_SPI_HW.cpp | 4 ++ Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp | 4 ++ Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp | 4 ++ Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp | 4 ++ Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp | 4 ++ Marlin/src/HAL/shared/HAL_SPI.h | 6 +++ Marlin/src/HAL/shared/tft/tft_spi.cpp | 2 +- Marlin/src/HAL/shared/tft/xpt2046.cpp | 27 +----------- Marlin/src/MarlinCore.cpp | 4 +- Marlin/src/feature/dac/dac_dac084s085.cpp | 8 ++-- Marlin/src/feature/tmc_util.cpp | 2 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 3 +- .../ftdi_eve_lib/basic/spi.cpp | 4 +- Marlin/src/libs/W25Qxx.cpp | 2 +- Marlin/src/module/temperature.cpp | 6 +-- Marlin/src/sd/Sd2Card.cpp | 3 +- .../sd/usb_flashdrive/lib-uhs2/usbhost.cpp | 3 +- 27 files changed, 134 insertions(+), 52 deletions(-) create mode 100644 Marlin/src/HAL/AVR/HAL_SPI_shared.cpp diff --git a/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp b/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp new file mode 100644 index 000000000000..7f126b2c7175 --- /dev/null +++ b/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp @@ -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 . + * + */ + +#ifdef __AVR__ + +#include "../../inc/MarlinConfig.h" + +#include "registers.h" + +inline bool _ATmega_isPinSPI(int pin) { + return _ATmega_getPinFunctions(pin).hasFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS); +} + +void spiSetupChipSelect(int pin) { + // If the pin is not hardware SPI, then we disable peripherals that may conflict with it due to badly written bootloaders + // or ArduinoCore. + if (_ATmega_isPinSPI(pin) == false) { + _ATmega_savePinAlternate(pin); + } + _ATmega_pinMode(pin, OUTPUT); + _ATmega_digitalWrite(pin, HIGH); +} + +#endif //__AVR__ \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index a4315d2bd428..55aaa86a434a 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -3222,6 +3222,10 @@ struct ATmegaPinFunctions { } return false; } + template + inline bool hasFunc(eATmegaPinFunc func, otherItemType&&... items) const { + return hasFunc(func) || hasFunc(((otherItemType&&)items)...); + } template inline void iterate(callbackType&& cb) const { diff --git a/Marlin/src/HAL/DUE/HAL_SPI.cpp b/Marlin/src/HAL/DUE/HAL_SPI.cpp index be38907325ad..d6d8a35535cc 100644 --- a/Marlin/src/HAL/DUE/HAL_SPI.cpp +++ b/Marlin/src/HAL/DUE/HAL_SPI.cpp @@ -480,6 +480,10 @@ SET_OUTPUT(SD_MOSI_PIN); } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + void spiSetBitOrder(int bitOrder) { _spi_bit_order = bitOrder; } @@ -688,6 +692,10 @@ // https://github.com/arduino/ArduinoCore-sam/blob/master/libraries/SPI/src/SPI.h // ------------------------ void spiBegin() {} + + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } void spiInitEx(uint32_t clock, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { _spi_clock = clock; @@ -974,6 +982,10 @@ spiInit(1); } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + void spiSetBitOrder(int bitOrder) { if (bitOrder == SPI_BITORDER_MSB) { SPI0->SPI_CR &= ~( 1 << 5 ); // 6th bit. @@ -1228,6 +1240,10 @@ void spiBegin() { spiInit(SPI_SPEED_DEFAULT); } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + void spiSetBitOrder(int bitOrder) { if (bitOrder == SPI_BITORDER_MSB) { SPI0->SPI_CR &= ~( 1 << 5 ); diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index 145f8396e058..fbccf6b20a8a 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -2106,6 +2106,10 @@ void spiBegin() { MarlinESP32::SPIResetBus(MarlinESP32::SPI3); } +void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); +} + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { #ifdef HALSPI_DEBUG if (_spi_core_id != xPortGetCoreID()) diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp index 9291d2952b45..cde750e4a643 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HWgen.cpp @@ -97,6 +97,10 @@ void spiBegin() { #endif } +void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); +} + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { if (hint_sck != -1) { SET_OUTPUT(hint_sck); diff --git a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp index 4cf9da005061..02d4c6e8052d 100644 --- a/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp +++ b/Marlin/src/HAL/ESP32/u8g_esp32_spi.cpp @@ -64,15 +64,13 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt switch (msg) { case U8G_COM_MSG_STOP: - spiClose(); break; case U8G_COM_MSG_INIT: - OUT_WRITE(DOGLCD_CS, HIGH); + spiSetupChipSelect(DOGLCD_CS); OUT_WRITE(DOGLCD_A0, HIGH); OUT_WRITE(LCD_RESET_PIN, HIGH); u8g_Delay(5); - spiInit(LCD_SPI_SPEED, DOGLCD_SCK, DOGLCD_MISO, DOGLCD_MOSI, DOGLCD_CS); break; case U8G_COM_MSG_ADDRESS: /* define cmd (arg_val = 0) or data mode (arg_val = 1) */ @@ -80,7 +78,10 @@ uint8_t u8g_eps_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_pt break; case U8G_COM_MSG_CHIP_SELECT: /* arg_val == 0 means HIGH level of U8G_PI_CS */ - WRITE(DOGLCD_CS, arg_val ? LOW : HIGH); + if (arg_val != 0) + spiInit(LCD_SPI_SPEED, DOGLCD_SCK, DOGLCD_MISO, DOGLCD_MOSI, DOGLCD_CS); + else + spiClose(); break; case U8G_COM_MSG_RESET: diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index a8d970d224e8..25cd2b366897 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -1476,6 +1476,10 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { MarlinLPC::PCONP.PCGPDMA = false; } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + static void _spiConfigClock(volatile MarlinLPC::ssp_dev_t& SSP, int clockMode) { if (clockMode == SPI_CLKMODE_0) { SSP.CR0.CPOL = false; diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp index 8ccd265f9ffb..0f37c022c060 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp @@ -63,6 +63,10 @@ void spiBegin() { //swSpiBegin(SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); } + + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { int use_sck = ( ( hint_sck >= 0 ) ? hint_sck : SD_SCK_PIN ); diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index d73f88e3f896..81d322a9fb47 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -97,11 +97,11 @@ void MarlinHAL::init() { //_DBG("\n\nDebug running\n"); // Initialize the SD card chip select pins as soon as possible #if PIN_EXISTS(SD_SS) - OUT_WRITE(SD_SS_PIN, HIGH); + spiSetupChipSelect(SD_SS_PIN); #endif #if PIN_EXISTS(ONBOARD_SD_CS) && ONBOARD_SD_CS_PIN != SD_SS_PIN - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); + spiSetupChipSelect(ONBOARD_SD_CS_PIN); #endif #ifdef LPC1768_ENABLE_CLKOUT_12M diff --git a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp index 69e499da50d4..9d040e9f477a 100644 --- a/Marlin/src/HAL/SAMD51/HAL_SPI.cpp +++ b/Marlin/src/HAL/SAMD51/HAL_SPI.cpp @@ -74,6 +74,10 @@ void spiBegin() { } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + void spiInitEx(uint32_t clock, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { _spi_clock = clock; _spi_bitOrder = MSBFIRST; diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp index b7d5f9c43395..8b7c21a2c2fc 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp @@ -561,6 +561,10 @@ extern "C" { #endif } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + static void _HAL_SPI_Prepare(void) { auto name_sck_pin = digitalPinToPinName(_spi_pin_sck); diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp index 0c9868a74d4d..f2729678f791 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp @@ -81,6 +81,10 @@ #endif } + void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); + } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { _spi_clock = maxClockFreq; spiConfig = SPISettings(maxClockFreq, MSBFIRST, SPI_MODE0); diff --git a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp index 3fdb72874f8c..b70211519bdf 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp @@ -48,6 +48,10 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } +void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); +} + // Configure SPI for specified SPI speed void spiInitEx(uint32_t clock, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the pin hints, there is nothing we can do (see arduino core). diff --git a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp index 2458a40ec3d1..8995bd75bb8c 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp @@ -47,6 +47,10 @@ void spiBegin() { SET_OUTPUT(SD_MOSI_PIN); } +void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); +} + void spiInitEx(uint32_t clock, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the SPI pin hints. _spi_clock = clock; diff --git a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp index 9c36696b3891..45fba212795b 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp @@ -63,6 +63,10 @@ void spiBegin() { //SET_OUTPUT(SD_MOSI_PIN); } +void spiSetupChipSelect(int pin) { + OUT_WRITE(pin, HIGH); +} + void spiInitEx(uint32_t clock, const int hint_sck/*=-1*/, const int hint_miso/*=-1*/, const int hint_mosi/*=-1*/, const int hint_cs/*=-1*/) { // Ignore the SPI pin hints. _spi_clock = clock; diff --git a/Marlin/src/HAL/shared/HAL_SPI.h b/Marlin/src/HAL/shared/HAL_SPI.h index db0cabe18b15..5d9641509298 100644 --- a/Marlin/src/HAL/shared/HAL_SPI.h +++ b/Marlin/src/HAL/shared/HAL_SPI.h @@ -74,6 +74,12 @@ // Initialize SPI bus (global). void spiBegin(); +// Configures the SPI chip-select pin for valid operation. +// It performs platform-dependant configurations for stability. +// Common feature is that the pin is set to HIGH while not being used. +// On the AVR, for example, it attempts to avoid the peripheral pin assignment conflict. +void spiSetupChipSelect(int pin); + // Configure SPI based on maximum clock frequency/rate. // Pass 0 for maxClockFreq to get a recommended default. void spiInitEx(uint32_t maxClockFreq, int hint_sck = -1, int hint_miso = -1, int hint_mosi = -1, int hint_cs = -1); diff --git a/Marlin/src/HAL/shared/tft/tft_spi.cpp b/Marlin/src/HAL/shared/tft/tft_spi.cpp index 9823e019a278..c950577082e4 100644 --- a/Marlin/src/HAL/shared/tft/tft_spi.cpp +++ b/Marlin/src/HAL/shared/tft/tft_spi.cpp @@ -41,7 +41,7 @@ void TFT_SPI::Init() { OUT_WRITE(TFT_A0_PIN, HIGH); - OUT_WRITE(TFT_CS_PIN, HIGH); + spiSetupChipSelect(TFT_CS_PIN); } void TFT_SPI::DataTransferBegin(eSPIMode spiMode) { diff --git a/Marlin/src/HAL/shared/tft/xpt2046.cpp b/Marlin/src/HAL/shared/tft/xpt2046.cpp index ebc671ae6e7a..ccc5c9306a29 100644 --- a/Marlin/src/HAL/shared/tft/xpt2046.cpp +++ b/Marlin/src/HAL/shared/tft/xpt2046.cpp @@ -34,32 +34,7 @@ #endif void XPT2046::Init() { - OUT_WRITE(TOUCH_CS_PIN, HIGH); - -#if 0 - // DEBUG PIN. - while (true) { - OUT_WRITE(EXP1_01_PIN, HIGH); - delay(1000); - OUT_WRITE(EXP1_01_PIN, LOW); - - // HIGH - OUT_WRITE(TOUCH_CS_PIN, HIGH); - delay(10000); - - OUT_WRITE(EXP1_01_PIN, HIGH); - delay(500); - OUT_WRITE(EXP1_01_PIN, LOW); - delay(500); - OUT_WRITE(EXP1_01_PIN, HIGH); - delay(500); - OUT_WRITE(EXP1_01_PIN, LOW); - - // LOW - OUT_WRITE(TOUCH_CS_PIN, LOW); - delay(10000); - } -#endif + spiSetupChipSelect(TOUCH_CS_PIN); #if PIN_EXISTS(TOUCH_INT) // Optional Pendrive interrupt pin diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 9e8ff62872bd..a68b80ba208e 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1230,10 +1230,10 @@ void setup() { // Init and disable SPI thermocouples; this is still needed #if TEMP_SENSOR_IS_MAX_TC(0) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0)) - OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable + spiSetupChipSelect(TEMP_0_CS_PIN); // Disable #endif #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) - OUT_WRITE(TEMP_1_CS_PIN, HIGH); + spiSetupChipSelect(TEMP_1_CS_PIN); #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index e5f3711623af..d3677ee727f7 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -90,10 +90,10 @@ void dac084s085::cshigh() { #if HAS_MULTI_EXTRUDER WRITE(DAC1_SYNC_PIN, HIGH); #endif - WRITE(SPI_EEPROM1_CS_PIN, HIGH); - WRITE(SPI_EEPROM2_CS_PIN, HIGH); - WRITE(SPI_FLASH_CS_PIN, HIGH); - WRITE(SD_SS_PIN, HIGH); + spiSetupChipSelect(SPI_EEPROM1_CS_PIN); + spiSetupChipSelect(SPI_EEPROM2_CS_PIN); + spiSetupChipSelect(SPI_FLASH_CS_PIN); + spiSetupChipSelect(SD_SS_PIN); } #endif // MB(ALLIGATOR) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 0867686363ca..308a63c8c44b 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -1321,7 +1321,7 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { #endif // HAS_TRINAMIC_CONFIG #if HAS_TMC_SPI - #define SET_CS_PIN(st) OUT_WRITE(st##_CS_PIN, HIGH) + #define SET_CS_PIN(st) spiSetupChipSelect(st##_CS_PIN) void tmc_init_cs_pins() { #if AXIS_HAS_SPI(X) SET_CS_PIN(X); diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index e388dbe2f1bf..3bc6f65804fb 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -344,8 +344,7 @@ void MarlinUI::init_lcd() { t = 0; #if ENABLED(TFTGLCD_PANEL_SPI) // SPI speed must be less 10MHz - SET_OUTPUT(TFTGLCD_CS); - WRITE(TFTGLCD_CS, HIGH); + spiSetupChipSelect(TFTGLCD_CS); _spi_prepare(); WRITE(TFTGLCD_CS, LOW); SPI_SEND_ONE(GET_LCD_ROW); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp index 5ba2901992fe..eea6b4559b54 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/spi.cpp @@ -42,11 +42,11 @@ namespace FTDI { WRITE(CLCD_MOD_RESET, 0); // start with module in power-down SET_OUTPUT(CLCD_SPI_CS); - WRITE(CLCD_SPI_CS, 1); + spiSetupChipSelect(CLCD_SPI_CS); #ifdef CLCD_SPI_EXTRA_CS SET_OUTPUT(CLCD_SPI_EXTRA_CS); - WRITE(CLCD_SPI_EXTRA_CS, 1); + spiSetupChipSelect(CLCD_SPI_EXTRA_CS); #endif #ifdef SPI_FLASH_SS diff --git a/Marlin/src/libs/W25Qxx.cpp b/Marlin/src/libs/W25Qxx.cpp index b14ffb68ca3e..88b1173f9f1f 100644 --- a/Marlin/src/libs/W25Qxx.cpp +++ b/Marlin/src/libs/W25Qxx.cpp @@ -39,7 +39,7 @@ bool flash_dma_mode = true; void W25QXXFlash::init(uint8_t spiRate) { - OUT_WRITE(SPI_FLASH_CS_PIN, HIGH); + spiSetupChipSelect(SPI_FLASH_CS_PIN); /** * STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 2fc8dae90f23..8acab22c2bd4 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2515,13 +2515,13 @@ void Temperature::init() { // Init (and disable) SPI thermocouples #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && PIN_EXISTS(TEMP_0_CS) - OUT_WRITE(TEMP_0_CS_PIN, HIGH); + spiSetupChipSelect(TEMP_0_CS_PIN); #endif #if TEMP_SENSOR_IS_ANY_MAX_TC(1) && PIN_EXISTS(TEMP_1_CS) - OUT_WRITE(TEMP_1_CS_PIN, HIGH); + spiSetupChipSelect(TEMP_1_CS_PIN); #endif #if TEMP_SENSOR_IS_ANY_MAX_TC(2) && PIN_EXISTS(TEMP_2_CS) - OUT_WRITE(TEMP_2_CS_PIN, HIGH); + spiSetupChipSelect(TEMP_2_CS_PIN); #endif // Setup objects for library-based polling of MAX TCs diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 796138a26b4a..1d29ae388dec 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -272,8 +272,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi // Set pin modes #if ENABLED(ZONESTAR_12864OLED) if (chipSelectPin_ != DOGLCD_CS) { - SET_OUTPUT(DOGLCD_CS); - WRITE(DOGLCD_CS, HIGH); + spiSetupChipSelect(DOGLCD_CS); } #else extDigitalWrite(chipSelectPin_, HIGH); // For some CPUs pinMode can write the wrong data so init desired data value first diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp index 76805b33d441..a242fc17461e 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/usbhost.cpp @@ -116,9 +116,8 @@ bool MAX3421e::reset() { bool MAX3421e::start() { // Initialize pins and SPI bus - SET_OUTPUT(USB_CS_PIN); + spiSetupChipSelect(USB_CS_PIN); SET_INPUT_PULLUP(USB_INTR_PIN); - ncs(); // MAX3421e - full-duplex, level interrupt, vbus off. regWr(rPINCTL, (bmFDUPSPI | bmINTLEVEL | GPX_VBDET)); From 393b8109305f7bef2c2eb420275e393c17893e8a Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Sat, 10 Dec 2022 13:54:17 +0100 Subject: [PATCH 36/83] - improved the error messages about missing HAL SPI fast HW chip oscillator frequency definitions - fixed pin definitions in AVR fastio which were used by external libraries, such as LiquidCrystal - added chip oscillator frequencies for RAMPS and MKS GEN L 1.0 --- Marlin/src/HAL/AVR/HAL_SPI_HW.cpp | 2 +- Marlin/src/HAL/AVR/HAL_SPI_SW.cpp | 6 +- Marlin/src/HAL/AVR/fastio/fastio_1280.h | 85 +++++++++++++++---------- Marlin/src/HAL/AVR/fastio/fastio_1281.h | 71 +++++++++++++-------- Marlin/src/HAL/AVR/fastio/fastio_168.h | 65 +++++++++++-------- Marlin/src/HAL/AVR/fastio/fastio_644.h | 83 +++++++++++++++--------- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 2 +- Marlin/src/pins/ramps/pins_MKS_GEN_L.h | 3 + Marlin/src/pins/ramps/pins_RAMPS.h | 3 + 9 files changed, 197 insertions(+), 123 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp index 774cc77f3152..2ba8a0ffafd4 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp @@ -44,7 +44,7 @@ #include #ifndef AVR_CHIPOSCILLATOR_FREQ -#error Missing AVR crystal oscillator frequency! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) +#error Missing AVR crystal oscillator frequency (AVR_CHIPOSCILLATOR_FREQ)! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) #endif // ------------------------ diff --git a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp index 716b3dff6e57..9dc1c2ea8b42 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp @@ -102,9 +102,9 @@ int use_pin_sck = (hint_sck >= 0) ? hint_sck : SD_SCK_PIN; int use_pin_miso = (hint_miso >= 0) ? hint_miso : SD_MISO_PIN; int use_pin_mosi = (hint_mosi >= 0) ? hint_mosi : SD_MOSI_PIN; - int use_pin_cs = (hint_cs >= 0) ? hint_cs : SD_SS_PIN; + int use_pin_cs = (hint_cs >= 0) ? hint_cs : SD_SS_PIN; // the chip-select should be initialized using spiSetupChipSelect! (much prior to usage) - _spi_pin_devstate = _ATmega_savePinAlternates({use_pin_sck, use_pin_miso, use_pin_mosi, use_pin_cs}); + _spi_pin_devstate = _ATmega_savePinAlternates({use_pin_sck, use_pin_miso, use_pin_mosi}); _spi_sck_pin = use_pin_sck; _spi_miso_pin = use_pin_miso; @@ -131,7 +131,7 @@ _ATmega_digitalWrite(_spi_cs_pin, HIGH); // Restore pin device states. - _ATmega_restorePinAlternates({_spi_cs_pin, _spi_mosi_pin, _spi_miso_pin, _spi_sck_pin}, _spi_pin_devstate); + _ATmega_restorePinAlternates({_spi_mosi_pin, _spi_miso_pin, _spi_sck_pin}, _spi_pin_devstate); _spi_is_running = false; } diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1280.h b/Marlin/src/HAL/AVR/fastio/fastio_1280.h index a8c241e5d080..a0aceef6f683 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1280.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1280.h @@ -31,40 +31,6 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO21 - -// UART -#define RXD DIO0 -#define TXD DIO1 - -// SPI -#define SCK DIO52 -#define MISO DIO50 -#define MOSI DIO51 -#define SS DIO53 - -// TWI (I2C) -#define SCL DIO21 -#define SDA DIO20 - -// Timers and PWM -#define OC0A DIO13 -#define OC0B DIO4 -#define OC1A DIO11 -#define OC1B DIO12 -#define OC2A DIO10 -#define OC2B DIO9 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 -#define OC4A DIO6 -#define OC4B DIO7 -#define OC4C DIO8 -#define OC5A DIO46 -#define OC5B DIO45 -#define OC5C DIO44 - // Digital I/O #define DIO0_PIN PINE0 @@ -669,4 +635,53 @@ #define DIO85_PWM nullptr #define PinH7 85 -#define DIO_NUM 86 \ No newline at end of file +#define DIO_NUM 86 + +// change for your board +// NOTE: these may actually be used by external libraries such as LiquidCrystal_AIP31068 +#ifndef DEBUG_LED + #define DEBUG_LED PinD0 +#endif + +// UART +#ifndef RXD + #define RXD PinE0 +#endif +#ifndef TXD + #define TXD PinE1 +#endif + +// SPI +#ifndef SCK + #define SCK PinB1 +#endif +#ifndef MISO + #define MISO PinB3 +#endif +#ifndef MOSI + #define MOSI PinB2 +#endif +#ifndef SS + #define SS PinB0 +#endif + +// TWI (I2C) +#define SCL PinD0 +#define SDA PinD1 + +// Timers and PWM +#define OC0A PinB7 +#define OC0B PinG5 +#define OC1A PinB5 +#define OC1B PinB6 +#define OC2A PinB4 +#define OC2B PinH6 +#define OC3A PinE3 +#define OC3B PinE4 +#define OC3C PinE5 +#define OC4A PinH3 +#define OC4B PinH4 +#define OC4C PinH5 +#define OC5A PinL3 +#define OC5B PinL4 +#define OC5C PinL5 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_1281.h b/Marlin/src/HAL/AVR/fastio/fastio_1281.h index 0a5bb350403b..0b30b600f265 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_1281.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_1281.h @@ -30,33 +30,6 @@ #include "../fastio.h" -// change for your board -#define DEBUG_LED DIO46 - -// UART -#define RXD DIO0 -#define TXD DIO1 - -// SPI -#define SCK DIO10 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO16 - -// TWI (I2C) -#define SCL DIO17 -#define SDA DIO18 - -// Timers and PWM -#define OC0A DIO9 -#define OC0B DIO4 -#define OC1A DIO7 -#define OC1B DIO8 -#define OC2A DIO6 -#define OC3A DIO5 -#define OC3B DIO2 -#define OC3C DIO3 - // Digital I/O #define DIO0_PIN PINE0 @@ -437,4 +410,46 @@ #define DIO53_PWM nullptr #define PinF7 53 -#define DIO_NUM 54 \ No newline at end of file +#define DIO_NUM 54 + +// change for your board +// NOTE: may be used by external libraries (LiquidCrystal) +#ifndef DEBUG_LED + #define DEBUG_LED PinF0 +#endif + +// UART +#ifndef RXD + #define RXD PinE0 +#endif +#ifndef TXD + #define TXD PinE1 +#endif + +// SPI +#ifndef SCK + #define SCK PinB1 +#endif +#ifndef MISO + #define MISO PinB3 +#endif +#ifndef MOSI + #define MOSI PinB2 +#endif +#ifndef SS + #define SS PinB0 +#endif + +// TWI (I2C) +#define SCL PinD0 +#define SDA PinD1 + +// Timers and PWM +#define OC0A PinB7 +#define OC0B PinG5 +#define OC1A PinB5 +#define OC1B PinB6 +#define OC2A PinB4 +#define OC3A PinE3 +#define OC3B PinE4 +#define OC3C PinE5 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_168.h b/Marlin/src/HAL/AVR/fastio/fastio_168.h index 8c6a343731ca..58b47b1c4dcd 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_168.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_168.h @@ -30,30 +30,6 @@ #include "../fastio.h" -#define DEBUG_LED AIO5 - -// UART -#define RXD DIO0 -#define TXD DIO1 - -// SPI -#define SCK DIO13 -#define MISO DIO12 -#define MOSI DIO11 -#define SS DIO10 - -// TWI (I2C) -#define SCL AIO5 -#define SDA AIO4 - -// Timers and PWM -#define OC0A DIO6 -#define OC0B DIO5 -#define OC1A DIO9 -#define OC1B DIO10 -#define OC2A DIO11 -#define OC2B DIO3 - // Digital I/O #define DIO0_PIN PIND0 @@ -210,4 +186,43 @@ #define DIO21_PWM nullptr #define PinC7 21 -#define DIO_NUM 22 \ No newline at end of file +#define DIO_NUM 22 + +// NOTE: may be used by external libraries (LiquidCrystal) +#ifndef DEBUG_LED + #define DEBUG_LED PinC5 +#endif + +// UART +#ifndef RXD + #define RXD PinD0 +#endif +#ifndef TXD + #define TXD PinD1 +#endif + +// SPI +#ifndef SCK + #define SCK PinB5 +#endif +#ifndef MISO + #define MISO PinB4 +#endif +#ifndef MOSI + #define MOSI PinB3 +#endif +#ifndef SS + #define SS PinB2 +#endif + +// TWI (I2C) +#define SCL PinC5 +#define SDA PinC4 + +// Timers and PWM +#define OC0A PinD6 +#define OC0B PinD5 +#define OC1A PinB1 +#define OC1B PinB2 +#define OC2A PinB3 +#define OC2B PinD3 \ No newline at end of file diff --git a/Marlin/src/HAL/AVR/fastio/fastio_644.h b/Marlin/src/HAL/AVR/fastio/fastio_644.h index 8755016c1dee..968263f4c1af 100644 --- a/Marlin/src/HAL/AVR/fastio/fastio_644.h +++ b/Marlin/src/HAL/AVR/fastio/fastio_644.h @@ -56,35 +56,6 @@ #include "../fastio.h" -#define DEBUG_LED DIO0 - -// UART -#define RXD DIO8 -#define TXD DIO9 -#define RXD0 DIO8 -#define TXD0 DIO9 - -#define RXD1 DIO10 -#define TXD1 DIO11 - -// SPI -#define SCK DIO7 -#define MISO DIO6 -#define MOSI DIO5 -#define SS DIO4 - -// TWI (I2C) -#define SCL DIO16 -#define SDA DIO17 - -// Timers and PWM -#define OC0A DIO3 -#define OC0B DIO4 -#define OC1A DIO13 -#define OC1B DIO12 -#define OC2A DIO15 -#define OC2B DIO14 - // Digital I/O #define DIO0_PIN PINB0 @@ -311,4 +282,56 @@ #define DIO31_PWM nullptr #define PinA0 31 -#define DIO_NUM 32 \ No newline at end of file +#define DIO_NUM 32 + +// NOTE: may be used by external libraries (LiquidCrystal) +#ifndef DEBUG_LED + #define DEBUG_LED PinB0 +#endif + +// UART +#ifndef RXD + #define RXD PinD0 +#endif +#ifndef TXD + #define TXD PinD1 +#endif +#ifndef RXD0 + #define RXD0 PinD0 +#endif +#ifndef TXD0 + #define TXD0 PinD1 +#endif + +#ifndef RXD1 + #define RXD1 PinD2 +#endif +#ifndef TXD1 + #define TXD1 PinD3 +#endif + +// SPI +#ifndef SCK + #define SCK PinB7 +#endif +#ifndef MISO + #define MISO PinB6 +#endif +#ifndef MOSI + #define MOSI PinB5 +#endif +#ifndef SS + #define SS PinB4 +#endif + +// TWI (I2C) +#define SCL PinC0 +#define SDA PinC1 + +// Timers and PWM +#define OC0A PinB3 +#define OC0B PinB4 +#define OC1A PinD5 +#define OC1B PinD4 +#define OC2A PinD7 +#define OC2B PinD6 \ No newline at end of file diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 25cd2b366897..0ceed7e7e4b7 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -64,7 +64,7 @@ #if !ENABLED(SOFTWARE_SPI) #ifndef LPC_MAINOSCILLATOR_FREQ -#error Missing LPC176X/LPC175X main oscillator frequency! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) +#error Missing LPC176X/LPC175X main oscillator frequency (LPC_MAINOSCILLATOR_FREQ)! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) #endif static void _spi_on_error(uint32_t code = 0) { diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index 28af5d6e7c43..d23f937e9702 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -24,6 +24,7 @@ /** * MKS GEN L – Arduino Mega2560 with RAMPS v1.4 pin assignments * ATmega2560, ATmega1280 + * https://github.com/makerbase-mks/MKS-GEN_L/blob/master/hardware/MKS%20Gen_L%20V1.0_008/MKS%20Gen_L%20V1.0_008%20SCH.pdf */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -32,6 +33,8 @@ #define BOARD_INFO_NAME "MKS GEN L" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Heaters / Fans // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 658fa0a8d415..218cee06baeb 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -50,6 +50,9 @@ #error "No pins defined for RAMPS with AZSMZ_12864." #endif +// https://www.arduino.cc/en/uploads/Main/arduino-mega2560-schematic.pdf +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #include "env_validate.h" // Custom flags and defines for the build From 65362ace2493fb78f80a95f9129843083201f58f Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Sat, 10 Dec 2022 15:39:10 +0100 Subject: [PATCH 37/83] - converted RAMBo board pin header files to pin names instead of internal numbering --- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 121 ++++++------ Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 132 ++++++------- Marlin/src/pins/rambo/pins_MINIRAMBO.h | 148 +++++++-------- Marlin/src/pins/rambo/pins_RAMBO.h | 190 +++++++++---------- Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h | 20 +- Marlin/src/pins/rambo/pins_SCOOVO_X9H.h | 134 ++++++------- Marlin/src/pins/sam/env_validate.h | 5 + 7 files changed, 378 insertions(+), 372 deletions(-) diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index c5d5fcef78f7..10623771b968 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -40,10 +40,10 @@ #endif // TMC2130 Diag Pins (currently just for reference) -#define X_DIAG_PIN 64 -#define Y_DIAG_PIN 69 -#define Z_DIAG_PIN 68 -#define E0_DIAG_PIN 65 +#define X_DIAG_PIN PinK2 +#define Y_DIAG_PIN PinK7 +#define Z_DIAG_PIN PinK6 +#define E0_DIAG_PIN PinK3 // // Limit Switches @@ -56,9 +56,9 @@ #if DISABLED(SENSORLESS_HOMING) - #define X_STOP_PIN 12 - #define Y_STOP_PIN 11 - #define Z_STOP_PIN 10 + #define X_STOP_PIN PinB6 + #define Y_STOP_PIN PinB5 + #define Z_STOP_PIN PinB4 #else @@ -66,10 +66,10 @@ #define Y_STOP_PIN Y_DIAG_PIN #if ENABLED(BLTOUCH) - #define Z_STOP_PIN 11 // Y-MIN - #define SERVO0_PIN 10 // Z-MIN + #define Z_STOP_PIN PinB5 // Y-MIN + #define SERVO0_PIN PinB4 // Z-MIN #else - #define Z_STOP_PIN 10 + #define Z_STOP_PIN PinB4 #endif #endif @@ -78,59 +78,60 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN PinB4 #endif // // Filament Runout Sensor // #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 62 + #define FIL_RUNOUT_PIN PinK0 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 49 -#define X_ENABLE_PIN 29 -#define X_CS_PIN 41 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinL0 +#define X_ENABLE_PIN PinA7 +#define X_CS_PIN PinG0 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 48 -#define Y_ENABLE_PIN 28 -#define Y_CS_PIN 39 +#define Y_STEP_PIN PinC1 +#define Y_DIR_PIN PinL1 +#define Y_ENABLE_PIN PinA6 +#define Y_CS_PIN PinG2 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 -#define Z_CS_PIN 67 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinL2 +#define Z_ENABLE_PIN PinA5 +#define Z_CS_PIN PinK5 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_CS_PIN 66 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinA4 +#define E0_CS_PIN PinK4 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input, Header J2 -#define TEMP_1_PIN 1 // Analog Input, Header J3 +#define TEMP_0_PIN PinE0 // Analog Input, Header J2 +#define TEMP_1_PIN PinE1 // Analog Input, Header J3 +// FATAL ERROR: TEMP_BOARD_PIN does not exist! #define TEMP_BOARD_PIN 91 // Onboard thermistor, 100k TDK NTCG104LH104JT1 -#define TEMP_BED_PIN 2 // Analog Input, Header J6 -#define TEMP_PROBE_PIN 3 // Analog Input, Header J15 +#define TEMP_BED_PIN PinE4 // Analog Input, Header J6 +#define TEMP_PROBE_PIN PinE5 // Analog Input, Header J15 // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN #ifdef MK3_FAN_PINS - #define FAN_PIN 6 + #define FAN_PIN PinH3 #else - #define FAN_PIN 8 + #define FAN_PIN PinH5 #endif #endif @@ -138,7 +139,7 @@ #ifdef MK3_FAN_PINS #define FAN1_PIN -1 #else - #define FAN1_PIN 6 + #define FAN1_PIN PinH3 #endif #endif @@ -153,29 +154,29 @@ * P1 P2 P3 */ -#define EXP1_01_PIN 84 -#define EXP1_02_PIN 9 -#define EXP1_03_PIN 61 -#define EXP1_04_PIN 82 -#define EXP1_05_PIN 59 -#define EXP1_06_PIN 70 -#define EXP1_07_PIN 85 -#define EXP1_08_PIN 71 - -#define EXP2_01_PIN 50 -#define EXP2_02_PIN 52 -#define EXP2_03_PIN 72 -#define EXP2_04_PIN 77 -#define EXP2_05_PIN 14 -#define EXP2_06_PIN 51 -#define EXP2_07_PIN 15 +#define EXP1_01_PIN PinH2 +#define EXP1_02_PIN PinH6 +#define EXP1_03_PIN PinF7 +#define EXP1_04_PIN PinD5 +#define EXP1_05_PIN PinF5 +#define EXP1_06_PIN PinG4 +#define EXP1_07_PIN PinH7 +#define EXP1_08_PIN PinG3 + +#define EXP2_01_PIN PinB3 +#define EXP2_02_PIN PinB1 +#define EXP2_03_PIN PinJ2 +#define EXP2_04_PIN PinJ6 +#define EXP2_05_PIN PinJ1 +#define EXP2_06_PIN PinB2 +#define EXP2_07_PIN PinJ0 #define EXP2_08_PIN -1 // // Misc. Functions // #define SDSS EXP2_04_PIN -#define LED_PIN 13 +#define LED_PIN PinB7 #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN EXP1_02_PIN @@ -186,16 +187,16 @@ // // use P1 connector for spindle pins #define SPINDLE_LASER_PWM_PIN EXP1_02_PIN // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_ENA_PIN PinD3 // Pullup! +#define SPINDLE_DIR_PIN PinD2 // // Průša i3 MK2 Multiplexer Support // #if HAS_PRUSA_MMU1 - #define E_MUX0_PIN 17 - #define E_MUX1_PIN 16 - #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + #define E_MUX0_PIN PinH0 + #define E_MUX1_PIN PinH1 + #define E_MUX2_PIN PinE2 // 84 in MK2 Firmware, with BEEPER as 78 #endif // @@ -203,7 +204,7 @@ // #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL - #define KILL_PIN 32 + #define KILL_PIN PinC5 #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 413eb8c98cc6..65af045f8c84 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -37,10 +37,10 @@ #endif // TMC2130 Diag Pins -#define X_DIAG_PIN 64 -#define Y_DIAG_PIN 69 -#define Z_DIAG_PIN 68 -#define E0_DIAG_PIN 65 +#define X_DIAG_PIN PinK2 +#define Y_DIAG_PIN PinK7 +#define Z_DIAG_PIN PinK6 +#define E0_DIAG_PIN PinK3 // // Limit Switches @@ -53,114 +53,114 @@ #if DISABLED(SENSORLESS_HOMING) - #define X_MIN_PIN 12 // X- - #define Y_MIN_PIN 11 // Y- - #define X_MAX_PIN 81 // X+ - #define Y_MAX_PIN 57 // Y+ + #define X_MIN_PIN PinB6 // X- + #define Y_MIN_PIN PinB5 // Y- + #define X_MAX_PIN PinD4 // X+ + #define Y_MAX_PIN PinF3 // Y+ #else #if X_HOME_TO_MIN #define X_MIN_PIN X_DIAG_PIN - #define X_MAX_PIN 81 // X+ + #define X_MAX_PIN PinD4 // X+ #else - #define X_MIN_PIN 12 // X- + #define X_MIN_PIN PinB6 // X- #define X_MAX_PIN X_DIAG_PIN #endif #if Y_HOME_TO_MIN #define Y_MIN_PIN Y_DIAG_PIN - #define Y_MAX_PIN 57 // Y+ + #define Y_MAX_PIN PinF3 // Y+ #else - #define Y_MIN_PIN 11 // Y- + #define Y_MIN_PIN PinB5 // Y- #define Y_MAX_PIN Y_DIAG_PIN #endif #if ENABLED(BLTOUCH) - #define Z_MIN_PIN 11 // Y- - #define SERVO0_PIN 10 // Z- + #define Z_MIN_PIN PinB5 // Y- + #define SERVO0_PIN PinB4 // Z- #endif #endif -#define Z_MAX_PIN 7 +#define Z_MAX_PIN PinH4 #ifndef Z_MIN_PIN - #define Z_MIN_PIN 10 // Z- + #define Z_MIN_PIN PinB4 // Z- #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN PinB4 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 49 -#define X_ENABLE_PIN 29 -#define X_CS_PIN 41 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinL0 +#define X_ENABLE_PIN PinA7 +#define X_CS_PIN PinG0 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 48 -#define Y_ENABLE_PIN 28 -#define Y_CS_PIN 39 +#define Y_STEP_PIN PinC1 +#define Y_DIR_PIN PinL1 +#define Y_ENABLE_PIN PinA6 +#define Y_CS_PIN PinG2 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 -#define Z_CS_PIN 67 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinL2 +#define Z_ENABLE_PIN PinA5 +#define Z_CS_PIN PinK5 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_CS_PIN 66 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinA4 +#define E0_CS_PIN PinK4 // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_1_PIN PinE1 // Analog Input +#define TEMP_BED_PIN PinE4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_BED_PIN 4 +#define HEATER_0_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN PinH5 #endif -#define FAN1_PIN 6 +#define FAN1_PIN PinH3 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 9 + #define CASE_LIGHT_PIN PinH6 #endif // // M3/M4/M5 - Spindle/Laser Control // // use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_PWM_PIN PinH6 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinD3 // Pullup! +#define SPINDLE_DIR_PIN PinD2 // // Průša i3 MK2 Multiplexer Support // #if HAS_PRUSA_MMU1 - #define E_MUX0_PIN 17 - #define E_MUX1_PIN 16 - #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + #define E_MUX0_PIN PinH0 + #define E_MUX1_PIN PinH1 + #define E_MUX2_PIN PinE2 // 84 in MK2 Firmware, with BEEPER as 78 #endif // @@ -168,31 +168,31 @@ // #if ANY(HAS_WIRED_LCD, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) - #define KILL_PIN 32 + #define KILL_PIN PinC5 #if ANY(IS_ULTIPANEL, TOUCH_UI_ULTIPANEL, TOUCH_UI_FTDI_EVE) #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS 85 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 70 - #define BTN_EN1 18 - #define BTN_EN2 19 + #define LCD_PINS_RS PinH7 + #define LCD_PINS_ENABLE PinG3 + #define LCD_PINS_D4 PinG4 + #define BTN_EN1 PinD3 + #define BTN_EN2 PinD2 #else - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 // On 0.6b, use 61 - #define LCD_PINS_D4 19 // On 0.6b, use 59 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 - #define BTN_EN1 14 - #define BTN_EN2 72 + #define LCD_PINS_RS PinD5 + #define LCD_PINS_ENABLE PinD3 // On 0.6b, use 61 + #define LCD_PINS_D4 PinD2 // On 0.6b, use 59 + #define LCD_PINS_D5 PinG4 + #define LCD_PINS_D6 PinH7 + #define LCD_PINS_D7 PinG3 + #define BTN_EN1 PinJ1 + #define BTN_EN2 PinJ2 #endif - #define BTN_ENC 9 // AUX-2 - #define BEEPER_PIN 84 // AUX-4 + #define BTN_ENC PinH6 // AUX-2 + #define BEEPER_PIN PinH2 // AUX-4 - #define SD_DETECT_PIN 15 + #define SD_DETECT_PIN PinJ0 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 31d44f2b34ba..6da9e97de92e 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -36,52 +36,52 @@ // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 30 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 24 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 23 +#define X_MIN_PIN PinB6 +#define X_MAX_PIN PinC7 +#define Y_MIN_PIN PinB5 +#define Y_MAX_PIN PinA2 +#define Z_MIN_PIN PinB4 +#define Z_MAX_PIN PinA1 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 23 + #define Z_MIN_PROBE_PIN PinA1 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinL1 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN PinC1 +#define Y_DIR_PIN PinL0 +#define Y_ENABLE_PIN PinA6 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinL2 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinA4 // Microstepping pins -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 - -#define MOTOR_CURRENT_PWM_XY_PIN 46 -#define MOTOR_CURRENT_PWM_Z_PIN 45 -#define MOTOR_CURRENT_PWM_E_PIN 44 +#define X_MS1_PIN PinG1 +#define X_MS2_PIN PinG0 +#define Y_MS1_PIN PinK7 +#define Y_MS2_PIN PinG2 +#define Z_MS1_PIN PinK6 +#define Z_MS2_PIN PinK5 +#define E0_MS1_PIN PinK3 +#define E0_MS2_PIN PinK4 + +#define MOTOR_CURRENT_PWM_XY_PIN PinL3 +#define MOTOR_CURRENT_PWM_Z_PIN PinL4 +#define MOTOR_CURRENT_PWM_E_PIN PinL5 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #ifndef MOTOR_CURRENT_PWM_RANGE #define MOTOR_CURRENT_PWM_RANGE 2000 @@ -91,50 +91,50 @@ // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_1_PIN PinE1 // Analog Input +#define TEMP_BED_PIN PinE4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 3 -#define HEATER_1_PIN 7 +#define HEATER_0_PIN PinE5 +#define HEATER_1_PIN PinH4 #if !MB(MINIRAMBO_10A) - #define HEATER_2_PIN 6 + #define HEATER_2_PIN PinH3 #endif -#define HEATER_BED_PIN 4 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN PinH5 #endif -#define FAN1_PIN 6 +#define FAN1_PIN PinH3 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 +#define SDSS PinB0 +#define LED_PIN PinB7 #if !MB(MINIRAMBO_10A) - #define CASE_LIGHT_PIN 9 + #define CASE_LIGHT_PIN PinH6 #endif // // M3/M4/M5 - Spindle/Laser Control // // use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 18 // Pullup! -#define SPINDLE_DIR_PIN 19 +#define SPINDLE_LASER_PWM_PIN PinH6 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinD3 // Pullup! +#define SPINDLE_DIR_PIN PinD2 // // Průša i3 MK2 Multiplexer Support // #if HAS_PRUSA_MMU1 - #define E_MUX0_PIN 17 - #define E_MUX1_PIN 16 + #define E_MUX0_PIN PinH0 + #define E_MUX1_PIN PinH1 #if !MB(MINIRAMBO_10A) - #define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + #define E_MUX2_PIN PinE2 // 84 in MK2 Firmware, with BEEPER as 78 #endif #endif @@ -144,46 +144,46 @@ #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL #if !MB(MINIRAMBO_10A) - #define KILL_PIN 32 + #define KILL_PIN PinC5 #endif #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL #if MB(MINIRAMBO_10A) - #define BEEPER_PIN 78 + #define BEEPER_PIN PinE2 - #define BTN_EN1 80 - #define BTN_EN2 73 - #define BTN_ENC 21 + #define BTN_EN1 PinE7 + #define BTN_EN2 PinJ3 + #define BTN_ENC PinD0 - #define LCD_PINS_RS 38 - #define LCD_PINS_ENABLE 5 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 15 - #define LCD_PINS_D6 32 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS PinD7 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinJ1 + #define LCD_PINS_D5 PinJ0 + #define LCD_PINS_D6 PinC5 + #define LCD_PINS_D7 PinC6 - #define SD_DETECT_PIN 72 + #define SD_DETECT_PIN PinJ2 #else // !MINIRAMBO_10A // AUX-4 - #define BEEPER_PIN 84 + #define BEEPER_PIN PinH2 // AUX-2 - #define BTN_EN1 14 - #define BTN_EN2 72 - #define BTN_ENC 9 - - #define LCD_PINS_RS 82 - #define LCD_PINS_ENABLE 18 - #define LCD_PINS_D4 19 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 - - #define SD_DETECT_PIN 15 + #define BTN_EN1 PinJ1 + #define BTN_EN2 PinJ2 + #define BTN_ENC PinH6 + + #define LCD_PINS_RS PinD5 + #define LCD_PINS_ENABLE PinD3 + #define LCD_PINS_D4 PinD2 + #define LCD_PINS_D5 PinG4 + #define LCD_PINS_D6 PinH7 + #define LCD_PINS_D7 PinG3 + + #define SD_DETECT_PIN PinJ0 #endif // !MINIRAMBO_10A diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index cb7a05913414..8b96f883fb89 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -51,73 +51,73 @@ // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN 22 // Motor header MX1 + #define SERVO0_PIN PinA0 // Motor header MX1 #endif -#define SERVO1_PIN 23 // Motor header MX2 +#define SERVO1_PIN PinA1 // Motor header MX2 #ifndef SERVO2_PIN - #define SERVO2_PIN 24 // Motor header MX3 + #define SERVO2_PIN PinA2 // Motor header MX3 #endif -#define SERVO3_PIN 5 // PWM header pin 5 +#define SERVO3_PIN PinE3 // PWM header pin 5 // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 +#define X_MIN_PIN PinB6 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinB5 +#define Y_MAX_PIN PinA1 #ifndef Z_MIN_PIN - #define Z_MIN_PIN 10 + #define Z_MIN_PIN PinB4 #endif -#define Z_MAX_PIN 30 +#define Z_MAX_PIN PinC7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN PinC7 #endif #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 5 + #define FIL_RUNOUT_PIN PinE3 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinL1 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN PinC1 +#define Y_DIR_PIN PinL0 +#define Y_ENABLE_PIN PinA6 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinL2 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinA4 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN PinC4 +#define E1_DIR_PIN PinL7 +#define E1_ENABLE_PIN PinA3 // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 - -#define DIGIPOTSS_PIN 38 +#define X_MS1_PIN PinG1 +#define X_MS2_PIN PinG0 +#define Y_MS1_PIN PinK7 +#define Y_MS2_PIN PinG2 +#define Z_MS1_PIN PinK6 +#define Z_MS2_PIN PinK5 +#define E0_MS1_PIN PinK3 +#define E0_MS2_PIN PinK4 +#define E1_MS1_PIN PinK1 +#define E1_MS2_PIN PinK2 + +#define DIGIPOTSS_PIN PinD7 #define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // X Y Z E0 E1 digipot channels to stepper driver mapping #ifndef DIGIPOT_MOTOR_CURRENT #define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) @@ -126,70 +126,70 @@ // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 2 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_1_PIN PinE1 // Analog Input +#define TEMP_BED_PIN PinE4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 7 -#define HEATER_2_PIN 6 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN PinH6 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinH3 +#define HEATER_BED_PIN PinE5 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN PinH5 #endif #ifndef FAN1_PIN - #define FAN1_PIN 6 + #define FAN1_PIN PinH3 #endif #ifndef FAN2_PIN - #define FAN2_PIN 2 + #define FAN2_PIN PinE4 #endif // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 4 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinG5 #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN 46 + #define CASE_LIGHT_PIN PinL3 #endif #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 3 // Analog Input + #define FILWIDTH_PIN PinE5 // Analog Input #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 45 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN 31 // Pullup! -#define SPINDLE_DIR_PIN 32 +#define SPINDLE_LASER_PWM_PIN PinL4 // Hardware PWM +#define SPINDLE_LASER_ENA_PIN PinC6 // Pullup! +#define SPINDLE_DIR_PIN PinC5 // // SPI for MAX Thermocouple // #ifndef TEMP_0_CS_PIN - #define TEMP_0_CS_PIN 32 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN + #define TEMP_0_CS_PIN PinC5 // SPINDLE_DIR_PIN / STAT_LED_BLUE_PIN #endif // // M7/M8/M9 - Coolant Control // -#define COOLANT_MIST_PIN 22 -#define COOLANT_FLOOD_PIN 44 +#define COOLANT_MIST_PIN PinA0 +#define COOLANT_FLOOD_PIN PinL5 // // Průša i3 MK2 Multiplexer Support // #if HAS_PRUSA_MMU1 - #define E_MUX0_PIN 17 - #define E_MUX1_PIN 16 - #define E_MUX2_PIN 84 // 84 in MK2 Firmware + #define E_MUX0_PIN PinH0 + #define E_MUX1_PIN PinH1 + #define E_MUX2_PIN PinH2 // 84 in MK2 Firmware #endif // @@ -197,51 +197,51 @@ // #if HAS_WIRED_LCD || TOUCH_UI_ULTIPANEL - #define KILL_PIN 80 + #define KILL_PIN PinE7 #if IS_ULTIPANEL || TOUCH_UI_ULTIPANEL - #define LCD_PINS_RS 70 - #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 72 - #define LCD_PINS_D5 73 - #define LCD_PINS_D6 74 - #define LCD_PINS_D7 75 + #define LCD_PINS_RS PinG4 + #define LCD_PINS_ENABLE PinG3 + #define LCD_PINS_D4 PinJ2 + #define LCD_PINS_D5 PinJ3 + #define LCD_PINS_D6 PinJ7 + #define LCD_PINS_D7 PinJ4 #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN 44 + #define BEEPER_PIN PinL5 // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the // beeper/buzzer is connected to pin 33; however, the pin used in the // diagram is actually pin 44, so this is correct. - #define DOGLCD_A0 70 - #define DOGLCD_CS 71 + #define DOGLCD_A0 PinG4 + #define DOGLCD_CS PinG3 - #define BTN_EN1 85 - #define BTN_EN2 84 - #define BTN_ENC 83 + #define BTN_EN1 PinH7 + #define BTN_EN2 PinH2 + #define BTN_ENC PinD6 #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - #define STAT_LED_RED_PIN 22 - #define STAT_LED_BLUE_PIN 32 + #define STAT_LED_RED_PIN PinA0 + #define STAT_LED_BLUE_PIN PinC5 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #else // !VIKI2 && !miniVIKI - #define BEEPER_PIN 79 // AUX-4 + #define BEEPER_PIN PinE6 // AUX-4 // AUX-2 #ifndef BTN_EN1 - #define BTN_EN1 76 + #define BTN_EN1 PinJ5 #endif #ifndef BTN_EN2 - #define BTN_EN2 77 + #define BTN_EN2 PinJ6 #endif - #define BTN_ENC 78 + #define BTN_ENC PinE2 - #define SD_DETECT_PIN 81 + #define SD_DETECT_PIN PinD4 #endif // !VIKI2 && !miniVIKI @@ -252,21 +252,21 @@ #else // !IS_NEWPANEL - old style panel with shift register // No Beeper added - #define BEEPER_PIN 33 + #define BEEPER_PIN PinC4 // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK_PIN 38 - //#define SHIFT_LD_PIN 42 - //#define SHIFT_OUT_PIN 40 - //#define SHIFT_EN_PIN 17 - - #define LCD_PINS_RS 75 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + //#define SHIFT_CLK_PIN PinD7 + //#define SHIFT_LD_PIN PinL7 + //#define SHIFT_OUT_PIN PinG1 + //#define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinJ4 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #endif // !IS_NEWPANEL diff --git a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h index 278a5bf0b45a..8d85fe4524ed 100755 --- a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h +++ b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h @@ -27,34 +27,34 @@ #define BOARD_INFO_NAME "Rambo ThinkerV2" -#define SERVO0_PIN 4 // Motor header MX1 +#define SERVO0_PIN PinG5 // Motor header MX1 #define SERVO2_PIN -1 // Motor header MX3 #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN 10 + #define FIL_RUNOUT_PIN PinB4 #endif // Support BLTouch and fixed probes #if ENABLED(BLTOUCH) #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define Z_MIN_PIN 22 + #define Z_MIN_PIN PinA0 #elif !defined(Z_MIN_PROBE_PIN) - #define Z_MIN_PROBE_PIN 22 + #define Z_MIN_PROBE_PIN PinA0 #endif #elif ENABLED(FIX_MOUNTED_PROBE) #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define Z_MIN_PIN 4 + #define Z_MIN_PIN PinG5 #elif !defined(Z_MIN_PROBE_PIN) - #define Z_MIN_PROBE_PIN 4 + #define Z_MIN_PROBE_PIN PinG5 #endif #endif // Eryone has the fan pins reversed -#define FAN1_PIN 2 -#define FAN2_PIN 6 +#define FAN1_PIN PinE4 +#define FAN2_PIN PinH3 // Encoder -#define BTN_EN1 64 -#define BTN_EN2 63 +#define BTN_EN1 PinK2 +#define BTN_EN2 PinK1 #include "pins_RAMBO.h" diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index 533284a4bf5e..ae7a32ad95b2 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -32,127 +32,127 @@ // // Servos // -#define SERVO0_PIN 22 // Motor header MX1 -#define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 -#define SERVO3_PIN 5 // PWM header pin 5 +#define SERVO0_PIN PinA0 // Motor header MX1 +#define SERVO1_PIN PinA1 // Motor header MX2 +#define SERVO2_PIN PinA2 // Motor header MX3 +#define SERVO3_PIN PinE3 // PWM header pin 5 // // Limit Switches // -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 30 +#define X_MIN_PIN PinB6 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinB5 +#define Y_MAX_PIN PinA1 +#define Z_MIN_PIN PinB4 +#define Z_MAX_PIN PinC7 // // Z Probe (when not Z_MIN_IN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 30 + #define Z_MIN_PROBE_PIN PinC7 #endif // // Steppers // -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 +#define X_STEP_PIN PinC0 +#define X_DIR_PIN PinL1 +#define X_ENABLE_PIN PinA7 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 +#define Y_STEP_PIN PinC1 +#define Y_DIR_PIN PinL0 +#define Y_ENABLE_PIN PinA6 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 +#define Z_STEP_PIN PinC2 +#define Z_DIR_PIN PinL2 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 +#define E0_STEP_PIN PinC3 +#define E0_DIR_PIN PinL6 +#define E0_ENABLE_PIN PinA4 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 +#define E1_STEP_PIN PinC4 +#define E1_DIR_PIN PinL7 +#define E1_ENABLE_PIN PinA3 // Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 - -#define DIGIPOTSS_PIN 38 +#define X_MS1_PIN PinG1 +#define X_MS2_PIN PinG0 +#define Y_MS1_PIN PinK7 +#define Y_MS2_PIN PinG2 +#define Z_MS1_PIN PinK6 +#define Z_MS2_PIN PinK5 +#define E0_MS1_PIN PinK3 +#define E0_MS2_PIN PinK4 +#define E1_MS1_PIN PinK1 +#define E1_MS2_PIN PinK2 + +#define DIGIPOTSS_PIN PinD7 #define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } // X Y Z E0 E1 digipot channels to stepper driver mapping // // Temperature Sensors // -#define TEMP_0_PIN 0 // Analog Input -#define TEMP_BED_PIN 7 // Analog Input +#define TEMP_0_PIN PinE0 // Analog Input +#define TEMP_BED_PIN PinH4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 7 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN PinH6 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinE5 #ifndef FAN_PIN - #define FAN_PIN 8 + #define FAN_PIN PinH5 #endif -#define FAN1_PIN 6 -#define FAN2_PIN 2 +#define FAN1_PIN PinH3 +#define FAN2_PIN PinE4 // // Misc. Functions // -#define SDSS 53 -#define LED_PIN 13 -#define PS_ON_PIN 4 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinG5 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 3 // Analog Input + #define FILWIDTH_PIN PinE5 // Analog Input #endif // // LCD / Controller // -#define LCD_PINS_RS 70 // Ext2_5 -#define LCD_PINS_ENABLE 71 // Ext2_7 -#define LCD_PINS_D4 72 // Ext2_9 ? -#define LCD_PINS_D5 73 // Ext2_11 ? -#define LCD_PINS_D6 74 // Ext2_13 -#define LCD_PINS_D7 75 // Ext2_15 ? +#define LCD_PINS_RS PinG4 // Ext2_5 +#define LCD_PINS_ENABLE PinG3 // Ext2_7 +#define LCD_PINS_D4 PinJ2 // Ext2_9 ? +#define LCD_PINS_D5 PinJ3 // Ext2_11 ? +#define LCD_PINS_D6 PinJ7 // Ext2_13 +#define LCD_PINS_D7 PinJ4 // Ext2_15 ? #define BEEPER_PIN -1 -#define BTN_HOME 80 // Ext_16 -#define BTN_CENTER 81 // Ext_14 +#define BTN_HOME PinE7 // Ext_16 +#define BTN_CENTER PinD4 // Ext_14 #define BTN_ENC BTN_CENTER -#define BTN_RIGHT 82 // Ext_12 -#define BTN_LEFT 83 // Ext_10 -#define BTN_UP 84 // Ext2_8 -#define BTN_DOWN 85 // Ext2_6 +#define BTN_RIGHT PinD5 // Ext_12 +#define BTN_LEFT PinD6 // Ext_10 +#define BTN_UP PinH2 // Ext2_8 +#define BTN_DOWN PinH7 // Ext2_6 #define HOME_PIN BTN_HOME #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN 44 + #define BEEPER_PIN PinL5 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 70 - #define DOGLCD_CS 71 + #define DOGLCD_A0 PinG4 + #define DOGLCD_CS PinG3 #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - #define STAT_LED_RED_PIN 22 - #define STAT_LED_BLUE_PIN 32 + #define STAT_LED_RED_PIN PinA0 + #define STAT_LED_BLUE_PIN PinC5 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #endif diff --git a/Marlin/src/pins/sam/env_validate.h b/Marlin/src/pins/sam/env_validate.h index 09bcd1364921..8bfa88b0bd3a 100644 --- a/Marlin/src/pins/sam/env_validate.h +++ b/Marlin/src/pins/sam/env_validate.h @@ -21,6 +21,11 @@ */ #pragma once +// Why ATmega2560? The ATsam board are based on ARM Cortex microprocessors which is +// an entirely different architecture than 8bit AVR MCUs. This file is in practice only +// allowing SAM MCU boards anyway. So the ATmega MCU support can be cut out of here, in favor +// of own board pin header definitions in the ramps folder! + #if BOTH(ALLOW_MEGA1280, ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega1280__, __AVR_ATmega2560__) #error "Oops! Select 'Arduino Due or Mega' in 'Tools > Board.'" #elif ENABLED(ALLOW_MEGA2560) && NOT_TARGET(__SAM3X8E__, __AVR_ATmega2560__) From a823366073906f024a64d691f4afcac042473ada Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Dec 2022 10:25:00 -0600 Subject: [PATCH 38/83] misc. cleanup --- Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp | 4 +- Marlin/src/HAL/AVR/HAL_SPI_SW.cpp | 66 ++++---- Marlin/src/HAL/AVR/registers.h | 18 +-- Marlin/src/HAL/DUE/HAL_SPI.cpp | 10 +- Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 141 +++++++----------- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 89 +++++------ Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp | 8 +- .../u8g/u8g_com_HAL_LPC1768_st7920_hw_spi.cpp | 2 +- Marlin/src/HAL/STM32/HAL_SPI_HW.cpp | 4 +- Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp | 2 +- Marlin/src/HAL/STM32/HAL_SPI_SW.cpp | 4 +- Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp | 6 +- Marlin/src/pins/mega/pins_MEGATRONICS.h | 2 +- Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 2 +- 14 files changed, 154 insertions(+), 204 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp index d521f88c8b0d..101e711dc3b1 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_HWgen.cpp @@ -223,7 +223,7 @@ (void)SPI.transfer(val); } } - + void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { _maybe_start_transaction(); for (uint16_t n = 0; n < repcnt; n++) { @@ -233,4 +233,4 @@ #endif -#endif //__AVR__ \ No newline at end of file +#endif //__AVR__ diff --git a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp index 9dc1c2ea8b42..817dfda75571 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_SW.cpp @@ -46,32 +46,22 @@ static void _spi_on_error(int code) { for (;;) { -#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); - delay(400); - OUT_WRITE(BEEPER_PIN, LOW); - delay(400); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(400); - OUT_WRITE(BEEPER_PIN, LOW); - delay(400); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); - delay(1000); - for (int n = 0; n < code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - if (n < code-1) - delay(500); - } - delay(1000); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(800); - OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); -#endif + #if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); delay(400); + OUT_WRITE(BEEPER_PIN, LOW); delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); delay(400); + OUT_WRITE(BEEPER_PIN, LOW); delay(400); + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + for (int n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code - 1) delay(500); + } + delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); delay(800); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + #endif } } @@ -120,9 +110,11 @@ _spi_is_running = true; } + void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { spiInit(0, hint_sck, hint_miso, hint_mosi, hint_cs); } + void spiClose() { if (_spi_is_running == false) _spi_on_error(2); @@ -149,9 +141,8 @@ // Soft SPI receive byte uint8_t spiRec(uint8_t txval) { - if (txval != 0xFF) { - _spi_on_error(4); - } + if (txval != 0xFF) _spi_on_error(4); + uint8_t data = 0; // no interrupts during byte receive - about 8µs cli(); @@ -166,8 +157,7 @@ nop; // adjust so SCK is nice nop; - if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) - { + if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) { int bitidx = ( msb ? 7-i : i ); data |= ( 1 << bitidx ); } @@ -180,9 +170,8 @@ } uint16_t spiRec16(uint16_t txval) { - if (txval != 0xFFFF) { - _spi_on_error(4); - } + if (txval != 0xFFFF) _spi_on_error(4); + uint16_t data = 0; bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); // no interrupts during byte receive - about 8µs @@ -196,8 +185,7 @@ nop; // adjust so SCK is nice nop; - if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) - { + if (_ATmega_digitalRead(_spi_miso_pin) == HIGH) { int bitidx = ( msb ? 15-i : i ); data |= ( 1 << bitidx ); } @@ -238,11 +226,11 @@ } void spiSend16(uint16_t v) { - bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); + const bool msb = ( _spi_bit_order == SPI_BITORDER_MSB ); // no interrupts during byte send - about 8µs cli(); LOOP_L_N(i, 16) { - int bitidx = ( msb ? 15-i : i ); + const int bitidx = msb ? 15 - i : i; _ATmega_digitalWrite(_spi_sck_pin, LOW); _ATmega_digitalWrite(_spi_mosi_pin, ( v & ( 1 << bitidx )) != 0); _ATmega_digitalWrite(_spi_sck_pin, HIGH); @@ -269,7 +257,7 @@ for (uint16_t n = 0; n < cnt; n++) spiSend(buf[n]); } - + void spiWrite16(const uint16_t *buf, uint16_t cnt) { for (uint16_t n = 0; n < cnt; n++) spiSend16(buf[n]); diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 55aaa86a434a..b13809e178d1 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -114,7 +114,7 @@ static_assert(sizeof(PORT_dev_t) == 3, "invalid size of ATmega2560 GPIO_dev_t"); struct _bitG_reg_t { uint8_t val : 6; uint8_t reserved1 : 2; - + bool getValue(uint8_t idx) const volatile { return ( val & (1<> 8); spiSend(data & 0xFF); - + } else { spiSend(data & 0xFF); diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index fbccf6b20a8a..8215c8346722 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -53,38 +53,26 @@ // tested using MKS TinyBee V1.0 (ESP32-WROOM-32U) // ------------------------ -static void _spi_on_error(uint32_t code = 0) { +static void _spi_on_error(const uint32_t code=0) { for (;;) { -#if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - delay(500); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - delay(500); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(150); - OUT_WRITE(BEEPER_PIN, LOW); - delay(150); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(150); - OUT_WRITE(BEEPER_PIN, LOW); - delay(150); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(150); - OUT_WRITE(BEEPER_PIN, LOW); - delay((code > 0) ? 800 : 150); - for (uint32_t n = 0; n < code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(250); - OUT_WRITE(BEEPER_PIN, LOW); - if (n < code - 1) - delay(250); - } - delay(3000); -#endif + #if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); delay(150); + OUT_WRITE(BEEPER_PIN, LOW); delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); delay(150); + OUT_WRITE(BEEPER_PIN, LOW); delay(150); + OUT_WRITE(BEEPER_PIN, HIGH); delay(150); + OUT_WRITE(BEEPER_PIN, LOW); delay(code ? 800 : 150); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(250); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code - 1) delay(250); + } + delay(3000); + #endif } } @@ -92,65 +80,48 @@ static void _spi_on_error(uint32_t code = 0) { #define HALSPI_LOOPBEEP_TIMEOUT 3000 #endif -struct spi_monitored_loop -{ +struct spi_monitored_loop { private: -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - uint32_t _start_millis; -#endif + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; + #endif public: inline spi_monitored_loop() { -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - _start_millis = millis(); -#endif + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); + #endif } inline void update(unsigned int beep_code) { -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(1000); - for (unsigned int n = 0; n < beep_code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); - } - delay(800); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); -#endif + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + #endif } }; static void __attribute__((unused)) _spi_infobeep(uint32_t code) { #if PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); delay(500); for (uint32_t n = 0; n < code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); } delay(300); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(400); - OUT_WRITE(BEEPER_PIN, LOW); - delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); delay(400); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); #endif } @@ -244,7 +215,7 @@ struct spi_user1_reg_t { static_assert(sizeof(spi_user1_reg_t) == 4, "invalid size for ESP32 spi_user1_reg_t"); struct spi_user2_reg_t { - uint32_t SPI_USR_COMMAND_VALUE : 16; + uint32_t SPI_USR_COMMAND_VALUE : 16; uint32_t reserved1 : 12; uint32_t SPI_USR_COMMAND_BITLEN : 4; }; @@ -1217,7 +1188,7 @@ inline void SPIWriteDataToTransferEx( byteval, true ); - + total_bytes_written++; } @@ -1267,7 +1238,7 @@ inline void SPIReadDataFromTransfer( total_bytes_read++; } - + cntReadBytes_out = total_bytes_read; } @@ -1969,7 +1940,7 @@ static dma_descriptor_t* DMAGenerateAcquireChain(dma_process_t& proc) { // Advance the process. proc.curoff += txcount; - + // Give ownership of the descriptor to the DMA controller. // (this decision turns valid as soon as the DMAC is kicked-off!) freedesc->owner = SPIDMA_OWNER_DMAC; @@ -2281,7 +2252,7 @@ void spiSend(uint8_t txval) { MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; - + _spiAsyncBarrier(); _maybe_start_transaction(); @@ -2499,7 +2470,7 @@ void spiWrite(const uint8_t *buf, uint16_t cnt) { void spiWrite16(const uint16_t *buf, uint16_t cnt) { if (cnt == 0) return; - + MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2596,7 +2567,7 @@ void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { while (txprog < repcnt_bytes) { uint16_t actualWriteCount; _spiWriteRepeatToBufferEx(SPI, val, repcnt_bytes - txprog, actualWriteCount, spi_writebuf_size, notrevbits, start_num_idx); - + MarlinESP32::SPITransaction(SPI, actualWriteCount); txprog += actualWriteCount; @@ -2656,4 +2627,4 @@ bool spiAsyncIsRunning() { #endif -#endif \ No newline at end of file +#endif diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 0ceed7e7e4b7..43096a33e03f 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -38,20 +38,20 @@ * active. If any of these pins are shared then the software SPI must be used. */ -/* - HAL SPI implementation by Martin Turski, company owner of EirDev - Inclusion date: 24th of November, 2022 - Contact mail: turningtides@outlook.de - --- - - Contact Martin if there is any grave SPI design or functionality issue. - Include a link to the Marlin FW GitHub issue post. Otherwise the mail - may be ignored. This implementation has been created specifically for the - Marlin FW. It was made with performance and simplicity-of-maintenance in - mind, while keeping all the SPI requirements in check. - - Original pull request: https://github.com/MarlinFirmware/Marlin/pull/24911 -*/ +/** + * HAL SPI implementation by Martin Turski, company owner of EirDev + * Inclusion date: 24th of November, 2022 + * Contact mail: turningtides@outlook.de + * --- + * + * Contact Martin if there is any grave SPI design or functionality issue. + * Include a link to the Marlin FW GitHub issue post. Otherwise the mail + * may be ignored. This implementation has been created specifically for the + * Marlin FW. It was made with performance and simplicity-of-maintenance in + * mind, while keeping all the SPI requirements in check. + * + * Original pull request: https://github.com/MarlinFirmware/Marlin/pull/24911 + */ // Actually: LPC176x/LPC175x #ifdef TARGET_LPC1768 @@ -61,38 +61,29 @@ #include "../shared/HAL_SPI.h" #include "../shared/ARM/HAL_NVIC.h" -#if !ENABLED(SOFTWARE_SPI) +#if DISABLED(SOFTWARE_SPI) -#ifndef LPC_MAINOSCILLATOR_FREQ -#error Missing LPC176X/LPC175X main oscillator frequency (LPC_MAINOSCILLATOR_FREQ)! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance) -#endif + #ifndef LPC_MAINOSCILLATOR_FREQ + #error "Missing LPC176X/LPC175X main oscillator frequency (LPC_MAINOSCILLATOR_FREQ)! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance)" + #endif -static void _spi_on_error(uint32_t code = 0) { +static void _spi_on_error(const uint32_t code=0) { for (;;) { -#if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); - delay(1000); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - if (code > 0) - delay(500); - for (uint32_t n = 0; n < code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(250); - OUT_WRITE(BEEPER_PIN, LOW); - if (n < code-1) + #if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); if (code > 0) delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(250); - } - if (code > 0) - delay(800); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); -#endif + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code - 1) delay(250); + } + if (code > 0) delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + #endif } } @@ -387,7 +378,7 @@ static pinmode9_reg_t& PINMODE9 = *(pinmode9_reg_t*)0x4002C064; struct fioXdir_reg_t { uint32_t val; - + inline void set(uint8_t reg, uint8_t val) { if (val == LPC_GPIODIR_INPUT) val &= ~(1<pin_list[U8G_PI_A0_STATE] = 0; // initial RS state: command mode break; diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp index 8b7c21a2c2fc..f123ab86ccba 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HW.cpp @@ -932,7 +932,7 @@ extern "C" { if (SPIhx.Init.FirstBit == SPI_FIRSTBIT_LSB) return; SPIhx.Init.FirstBit = SPI_FIRSTBIT_LSB; } - + // If the SPI is already enabled, then update it. // When the SPI is initialized, the chip-select must be high aswell. if (_spi_is_initialized) @@ -1349,4 +1349,4 @@ extern "C" { #endif -#endif // HAL_STM32 \ No newline at end of file +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp index f2729678f791..26d19a02fe12 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_HWgen.cpp @@ -100,7 +100,7 @@ // Configure SPI for specified SPI speed void spiInit(uint8_t spiRate, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { // Ignore chip-select because the software manages it already. - + // Use datarates Marlin uses uint32_t clock; switch (spiRate) { diff --git a/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp index fac73cc98f20..60f689202e1c 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI_SW.cpp @@ -133,7 +133,7 @@ } else spiRate = SPI_SPEED_6; - + spiInit(spiRate, hint_sck, hint_miso, hint_mosi, hint_cs); } @@ -249,4 +249,4 @@ #endif -#endif \ No newline at end of file +#endif diff --git a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp index a431fa768446..6dc0eb164fc1 100644 --- a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp +++ b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp @@ -137,7 +137,7 @@ void nvicUpdateVector() { void nvicSetHandler(uint32_t idx, void (*callback)()) { if (idx >= VECTOR_TABLE_SIZE) _NVIC_OnError(); - + _isrv_redirect[idx] = callback; __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) } @@ -149,7 +149,7 @@ void nvicSetIRQHandler(IRQn_Type irqn, void (*callback)()) { void (*nvicGetHandler(uint32_t idx))() { if (idx >= VECTOR_TABLE_SIZE) _NVIC_OnError(); - + return _isrv_redirect[idx]; } @@ -184,4 +184,4 @@ void nvicUninstallRedirect() { __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) } _vtor_refcount--; -} \ No newline at end of file +} diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index bf7dfe143f48..5f2ed5bea6d9 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -55,7 +55,7 @@ #define Y_STEP_PIN PinF6 // A6 (TODO: wtf? pin assignment? ff.) #define Y_DIR_PIN PinF7 // A7 -#define Y_ENABLE_PIN +#define Y_ENABLE_PIN #define Z_STEP_PIN PinF0 // A0 #define Z_DIR_PIN PinF1 // A1 diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index bb5d2112f3eb..b6c5c0bbeca8 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -68,7 +68,7 @@ #define E1_STEP_PIN PinA7 #define E1_DIR_PIN PinG2 #define E1_ENABLE_PIN PinA6 - + #define E2_STEP_PIN PinA1 // ? schematic says 24 (this comment is a sign of confusion by maintainers about the internal schematic numbering VS the internal numbering of AVR Marlin FW which should not matter!) #define E2_DIR_PIN PinA2 // ? schematic says 23 #define E2_ENABLE_PIN PinA0 From fde3ce8240230f99d34ac64330786cf42841426a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Dec 2022 10:45:08 -0600 Subject: [PATCH 39/83] also --- Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h index ec7621e28f3e..505f289964ca 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h @@ -38,16 +38,16 @@ #define BOARD_INFO_NAME "Sanguinololu 1.2" #endif -#define HEATER_BED_PIN 12 // (bed) -#define X_ENABLE_PIN 14 -#define Y_ENABLE_PIN 14 +#define HEATER_BED_PIN PinD4 // (bed) +#define X_ENABLE_PIN PinD6 +#define Y_ENABLE_PIN PinD6 #ifndef Z_ENABLE_PIN - #define Z_ENABLE_PIN 26 + #define Z_ENABLE_PIN PinA5 #endif -#define E0_ENABLE_PIN 14 +#define E0_ENABLE_PIN PinD6 #if !defined(FAN_PIN) && ENABLED(LCD_I2C_PANELOLU2) - #define FAN_PIN 4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan + #define FAN_PIN PinB4 // Uses Transistor1 (PWM) on Panelolu2's Sanguino Adapter Board to drive the fan #endif #define SANGUINOLOLU_V_1_2 From 8765a9279f0ace3edc2ad96f083902c4c79a455f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Dec 2022 11:19:02 -0600 Subject: [PATCH 40/83] apply pins formatting --- Marlin/src/pins/mega/pins_ELEFU_3.h | 94 ++--- Marlin/src/pins/mega/pins_GT2560_REV_A.h | 134 +++---- Marlin/src/pins/mega/pins_MINITRONICS.h | 84 ++-- Marlin/src/pins/ramps/pins_3DRAG.h | 58 +-- Marlin/src/pins/ramps/pins_DAGOMA_F5.h | 10 +- .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 118 +++--- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 126 +++--- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 184 ++++----- Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h | 28 +- Marlin/src/pins/ramps/pins_MKS_BASE_16.h | 2 +- Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h | 18 +- Marlin/src/pins/ramps/pins_RAMPS.h | 206 +++++----- Marlin/src/pins/ramps/pins_RAMPS_PLUS.h | 48 +-- Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h | 12 +- Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h | 120 +++--- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 370 +++++++++--------- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 194 ++++----- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 130 +++--- Marlin/src/pins/sanguino/pins_ANET_10.h | 94 ++--- Marlin/src/pins/sanguino/pins_OMCA.h | 58 +-- .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 162 ++++---- .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 154 ++++---- Marlin/src/pins/teensy2/pins_SAV_MKI.h | 64 +-- 23 files changed, 1234 insertions(+), 1234 deletions(-) diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index 223f2a9520c3..4bfb729f7f3f 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -33,96 +33,96 @@ // // Limit Switches // -#define X_MIN_PIN PinC2 -#define X_MAX_PIN PinC3 -#define Y_MIN_PIN PinC4 -#define Y_MAX_PIN PinC5 -#define Z_MIN_PIN PinC6 -#define Z_MAX_PIN PinC7 +#define X_MIN_PIN PinC2 +#define X_MAX_PIN PinC3 +#define Y_MIN_PIN PinC4 +#define Y_MAX_PIN PinC5 +#define Z_MIN_PIN PinC6 +#define Z_MAX_PIN PinC7 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinC7 + #define Z_MIN_PROBE_PIN PinC7 #endif // // Steppers // -#define X_STEP_PIN PinL0 -#define X_DIR_PIN PinB7 -#define X_ENABLE_PIN PinL1 +#define X_STEP_PIN PinL0 +#define X_DIR_PIN PinB7 +#define X_ENABLE_PIN PinL1 -#define Y_STEP_PIN PinB5 -#define Y_DIR_PIN PinH6 -#define Y_ENABLE_PIN PinB6 +#define Y_STEP_PIN PinB5 +#define Y_DIR_PIN PinH6 +#define Y_ENABLE_PIN PinB6 -#define Z_STEP_PIN PinH4 -#define Z_DIR_PIN PinH3 -#define Z_ENABLE_PIN PinH5 +#define Z_STEP_PIN PinH4 +#define Z_DIR_PIN PinH3 +#define Z_ENABLE_PIN PinH5 -#define E0_STEP_PIN PinG1 -#define E0_DIR_PIN PinG0 -#define E0_ENABLE_PIN PinC0 +#define E0_STEP_PIN PinG1 +#define E0_DIR_PIN PinG0 +#define E0_ENABLE_PIN PinC0 -#define E1_STEP_PIN PinD3 -#define E1_DIR_PIN PinD2 -#define E1_ENABLE_PIN PinD7 +#define E1_STEP_PIN PinD3 +#define E1_DIR_PIN PinD2 +#define E1_ENABLE_PIN PinD7 -#define E2_STEP_PIN PinL6 -#define E2_DIR_PIN PinL2 -#define E2_ENABLE_PIN PinL7 +#define E2_STEP_PIN PinL6 +#define E2_DIR_PIN PinL2 +#define E2_ENABLE_PIN PinL7 // // Temperature Sensors // -#define TEMP_0_PIN PinE5 // Analog Input -#define TEMP_1_PIN PinE4 // Analog Input -#define TEMP_2_PIN PinE1 // Analog Input -#define TEMP_BED_PIN PinE0 // Analog Input +#define TEMP_0_PIN PinE5 // Analog Input +#define TEMP_1_PIN PinE4 // Analog Input +#define TEMP_2_PIN PinE1 // Analog Input +#define TEMP_BED_PIN PinE0 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PinL4 // 12V PWM1 -#define HEATER_1_PIN PinL3 // 12V PWM2 -#define HEATER_2_PIN PinH0 // 12V PWM3 -#define HEATER_BED_PIN PinL5 // DOUBLE 12V PWM +#define HEATER_0_PIN PinL4 // 12V PWM1 +#define HEATER_1_PIN PinL3 // 12V PWM2 +#define HEATER_2_PIN PinH0 // 12V PWM3 +#define HEATER_BED_PIN PinL5 // DOUBLE 12V PWM #ifndef FAN_PIN - #define FAN_PIN PinH1 // 5V PWM + #define FAN_PIN PinH1 // 5V PWM #endif // // Misc. Functions // -#define PS_ON_PIN PinB4 // Set to -1 if using a manual switch on the PWRSW Connector -#define SLEEP_WAKE_PIN PinA4 // This feature still needs work -#define PHOTOGRAPH_PIN PinA7 +#define PS_ON_PIN PinB4 // Set to -1 if using a manual switch on the PWRSW Connector +#define SLEEP_WAKE_PIN PinA4 // This feature still needs work +#define PHOTOGRAPH_PIN PinA7 // // LCD / Controller // -#define BEEPER_PIN PinC1 +#define BEEPER_PIN PinC1 #if ENABLED(RA_CONTROL_PANEL) - #define SDSS PinB0 - #define SD_DETECT_PIN PinA6 + #define SDSS PinB0 + #define SD_DETECT_PIN PinA6 - #define BTN_EN1 PinJ1 - #define BTN_EN2 PinG2 - #define BTN_ENC PinJ0 + #define BTN_EN1 PinJ1 + #define BTN_EN2 PinG2 + #define BTN_ENC PinJ0 #endif // RA_CONTROL_PANEL #if ENABLED(RA_DISCO) // variables for which pins the TLC5947 is using - #define TLC_CLOCK_PIN PinA3 - #define TLC_BLANK_PIN PinA1 - #define TLC_XLAT_PIN PinA0 - #define TLC_DATA_PIN PinA2 + #define TLC_CLOCK_PIN PinA3 + #define TLC_BLANK_PIN PinA1 + #define TLC_XLAT_PIN PinA0 + #define TLC_DATA_PIN PinA2 // We also need to define pin to port number mapping for the 2560 to match the pins listed above. // If you change the TLC pins, update this as well per the 2560 datasheet! This currently only works with the RA Board. diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index eb7191e70c5a..ab4da737b5b5 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -48,125 +48,125 @@ // // Limit Switches // -#define X_MIN_PIN PinA0 -#define X_MAX_PIN PinA2 -#define Y_MIN_PIN PinA4 -#define Y_MAX_PIN PinA6 -#define Z_MIN_PIN PinC7 +#define X_MIN_PIN PinA0 +#define X_MAX_PIN PinA2 +#define Y_MIN_PIN PinA4 +#define Y_MAX_PIN PinA6 +#define Z_MIN_PIN PinC7 #if ENABLED(BLTOUCH) #if MB(GT2560_REV_A_PLUS) - #define SERVO0_PIN PinB5 - #define Z_MAX_PIN PinC5 + #define SERVO0_PIN PinB5 + #define Z_MAX_PIN PinC5 #else - #define SERVO0_PIN PinC5 + #define SERVO0_PIN PinC5 #define Z_MAX_PIN -1 #endif #else - #define Z_MAX_PIN PinC5 + #define Z_MAX_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN PinA3 -#define X_DIR_PIN PinA1 -#define X_ENABLE_PIN PinA5 +#define X_STEP_PIN PinA3 +#define X_DIR_PIN PinA1 +#define X_ENABLE_PIN PinA5 -#define Y_STEP_PIN PinC6 -#define Y_DIR_PIN PinC4 -#define Y_ENABLE_PIN PinA7 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC4 +#define Y_ENABLE_PIN PinA7 -#define Z_STEP_PIN PinC0 -#define Z_DIR_PIN PinG2 -#define Z_ENABLE_PIN PinC2 +#define Z_STEP_PIN PinC0 +#define Z_DIR_PIN PinG2 +#define Z_ENABLE_PIN PinC2 -#define E0_STEP_PIN PinL6 -#define E0_DIR_PIN PinL4 -#define E0_ENABLE_PIN PinG0 +#define E0_STEP_PIN PinL6 +#define E0_DIR_PIN PinL4 +#define E0_ENABLE_PIN PinG0 -#define E1_STEP_PIN PinL0 -#define E1_DIR_PIN PinL2 -#define E1_ENABLE_PIN PinL1 +#define E1_STEP_PIN PinL0 +#define E1_DIR_PIN PinL2 +#define E1_ENABLE_PIN PinL1 // // Temperature Sensors // -#define TEMP_0_PIN PinH5 -#define TEMP_1_PIN PinH6 -#define TEMP_BED_PIN PinB4 +#define TEMP_0_PIN PinH5 +#define TEMP_1_PIN PinH6 +#define TEMP_BED_PIN PinB4 // // Heaters / Fans // -#define HEATER_0_PIN PinE4 -#define HEATER_1_PIN PinE5 -#define HEATER_BED_PIN PinG5 +#define HEATER_0_PIN PinE4 +#define HEATER_1_PIN PinE5 +#define HEATER_BED_PIN PinG5 #ifndef FAN_PIN - #define FAN_PIN PinH4 + #define FAN_PIN PinH4 #endif // // Misc. Functions // -#define SDSS PinB0 -#define LED_PIN PinB7 -#define PS_ON_PIN PinB6 -#define SUICIDE_PIN PinF0 // Must be enabled at startup to keep power flowing +#define SDSS PinB0 +#define LED_PIN PinB7 +#define PS_ON_PIN PinB6 +#define SUICIDE_PIN PinF0 // Must be enabled at startup to keep power flowing #define KILL_PIN -1 #if HAS_WIRED_LCD - #define BEEPER_PIN PinD3 + #define BEEPER_PIN PinD3 #if IS_NEWPANEL #if ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 PinE3 - #define DOGLCD_CS PinD0 - #define BTN_EN1 PinG1 - #define BTN_EN2 PinL7 + #define DOGLCD_A0 PinE3 + #define DOGLCD_CS PinD0 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinL7 #elif ENABLED(FYSETC_MINI_12864) // Disconnect EXP2-1 and EXP2-2, otherwise future firmware upload won't work. - #define DOGLCD_A0 PinD1 - #define DOGLCD_CS PinH0 + #define DOGLCD_A0 PinD1 + #define DOGLCD_CS PinH0 - #define NEOPIXEL_PIN PinD0 - #define BTN_EN1 PinL7 - #define BTN_EN2 PinG1 + #define NEOPIXEL_PIN PinD0 + #define BTN_EN1 PinL7 + #define BTN_EN2 PinG1 - #define LCD_RESET_PIN PinH1 + #define LCD_RESET_PIN PinH1 #define LCD_CONTRAST_INIT 220 #define LCD_BACKLIGHT_PIN -1 #else - #define LCD_PINS_RS PinD1 - #define LCD_PINS_ENABLE PinH0 - #define LCD_PINS_D4 PinH1 - #define LCD_PINS_D5 PinD0 - #define LCD_PINS_D6 PinE3 - #define LCD_PINS_D7 PinH3 - #define BTN_EN1 PinL7 - #define BTN_EN2 PinG1 + #define LCD_PINS_RS PinD1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinH1 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinE3 + #define LCD_PINS_D7 PinH3 + #define BTN_EN1 PinL7 + #define BTN_EN2 PinG1 #endif - #define BTN_ENC PinD2 - #define SD_DETECT_PIN PinD7 + #define BTN_ENC PinD2 + #define SD_DETECT_PIN PinD7 #else // !IS_NEWPANEL - #define SHIFT_CLK_PIN PinD7 - #define SHIFT_LD_PIN PinL7 - #define SHIFT_OUT_PIN PinG1 - #define SHIFT_EN_PIN PinH0 - - #define LCD_PINS_RS PinH1 - #define LCD_PINS_ENABLE PinE3 - #define LCD_PINS_D4 PinH3 - #define LCD_PINS_D5 PinD0 - #define LCD_PINS_D6 PinD1 - #define LCD_PINS_D7 PinD2 + #define SHIFT_CLK_PIN PinD7 + #define SHIFT_LD_PIN PinL7 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_EN_PIN PinH0 + + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinE3 + #define LCD_PINS_D4 PinH3 + #define LCD_PINS_D5 PinD0 + #define LCD_PINS_D6 PinD1 + #define LCD_PINS_D7 PinD2 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index 5fd6ebbcb0d9..5e7b150c3bd5 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -42,59 +42,59 @@ // // Limit Switches // -#define X_MIN_PIN PinE3 -#define X_MAX_PIN PinE4 -#define Y_MIN_PIN PinE4 -#define Y_MAX_PIN PinE7 -#define Z_MIN_PIN PinB4 +#define X_MIN_PIN PinE3 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinE4 +#define Y_MAX_PIN PinE7 +#define Z_MIN_PIN PinB4 #define Z_MAX_PIN -1 // // Steppers // -#define X_STEP_PIN PinF2 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinF3 +#define X_STEP_PIN PinF2 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinF3 -#define Y_STEP_PIN PinA1 // A6 -#define Y_DIR_PIN PinA2 // A0 -#define Y_ENABLE_PIN PinA0 +#define Y_STEP_PIN PinA1 // A6 +#define Y_DIR_PIN PinA2 // A0 +#define Y_ENABLE_PIN PinA0 -#define Z_STEP_PIN PinA4 // A2 -#define Z_DIR_PIN PinA5 // A6 -#define Z_ENABLE_PIN PinA3 // A1 +#define Z_STEP_PIN PinA4 // A2 +#define Z_DIR_PIN PinA5 // A6 +#define Z_ENABLE_PIN PinA3 // A1 -#define E0_STEP_PIN PinA7 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinG2 +#define E0_STEP_PIN PinA7 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinG2 -#define E1_STEP_PIN PinC6 -#define E1_DIR_PIN PinC5 -#define E1_ENABLE_PIN PinC7 +#define E1_STEP_PIN PinC6 +#define E1_DIR_PIN PinC5 +#define E1_ENABLE_PIN PinC7 // // Temperature Sensors // -#define TEMP_0_PIN PinB5 // Analog Input -#define TEMP_1_PIN PinB4 // Analog Input -#define TEMP_BED_PIN PinB4 // Analog Input +#define TEMP_0_PIN PinB5 // Analog Input +#define TEMP_1_PIN PinB4 // Analog Input +#define TEMP_BED_PIN PinB4 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PinB5 // EXTRUDER 1 -#define HEATER_1_PIN PinB6 // EXTRUDER 2 -#define HEATER_BED_PIN PinE5 // BED +#define HEATER_0_PIN PinB5 // EXTRUDER 1 +#define HEATER_1_PIN PinB6 // EXTRUDER 2 +#define HEATER_BED_PIN PinE5 // BED #ifndef FAN_PIN - #define FAN_PIN PinB7 + #define FAN_PIN PinB7 #endif // // Misc. Functions // -#define SDSS PinB0 -#define LED_PIN PinF0 +#define SDSS PinB0 +#define LED_PIN PinF0 // // LCD / Controller @@ -103,15 +103,15 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS PinE7 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PinB2 // SID (MOSI) - #define LCD_PINS_D4 PinB1 // SCK (CLK) clock + #define LCD_PINS_RS PinE7 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinB2 // SID (MOSI) + #define LCD_PINS_D4 PinB1 // SCK (CLK) clock - #define BTN_EN1 PinD1 - #define BTN_EN2 PinD0 - #define BTN_ENC PinG0 + #define BTN_EN1 PinD1 + #define BTN_EN2 PinD0 + #define BTN_ENC PinG0 - #define SD_DETECT_PIN PinC0 + #define SD_DETECT_PIN PinC0 #else @@ -134,10 +134,10 @@ #undef TEMP_BED_PIN // need to free up some pins but also need to #undef TEMP_0_PIN // re-assign them (to unused pins) because Marlin #undef TEMP_1_PIN // requires the presence of certain pins or else it - #define HEATER_BED_PIN PinG5 // won't compile - #define TEMP_BED_PIN PinF4 - #define TEMP_0_PIN PinF5 - #define SPINDLE_LASER_ENA_PIN PinF6 // using A6 because it already has a pullup - #define SPINDLE_LASER_PWM_PIN PinE5 // WARNING - LED & resistor pull up to +12/+24V stepper voltage - #define SPINDLE_DIR_PIN PinF7 + #define HEATER_BED_PIN PinG5 // won't compile + #define TEMP_BED_PIN PinF4 + #define TEMP_0_PIN PinF5 + #define SPINDLE_LASER_ENA_PIN PinF6 // using A6 because it already has a pullup + #define SPINDLE_LASER_PWM_PIN PinE5 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_DIR_PIN PinF7 #endif diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 02ee173d35af..95c755af71c5 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -41,17 +41,17 @@ // // Limit Switches // -#define Z_STOP_PIN PinD3 +#define Z_STOP_PIN PinD3 // // Steppers // #if HAS_CUTTER - #define Z_DIR_PIN PinA6 - #define Z_ENABLE_PIN PinA2 - #define Z_STEP_PIN PinA4 + #define Z_DIR_PIN PinA6 + #define Z_ENABLE_PIN PinA2 + #define Z_STEP_PIN PinA4 #else - #define Z_ENABLE_PIN PinK1 + #define Z_ENABLE_PIN PinK1 #endif #if HAS_CUTTER && !HAS_EXTRUDERS @@ -63,16 +63,16 @@ // // Heaters / Fans // -#define MOSFET_B_PIN PinH5 -#define MOSFET_C_PIN PinH6 -#define MOSFET_D_PIN PinB6 +#define MOSFET_B_PIN PinH5 +#define MOSFET_C_PIN PinH6 +#define MOSFET_D_PIN PinB6 -#define HEATER_2_PIN PinH3 +#define HEATER_2_PIN PinH3 // // Misc. Functions // -#define SDSS PinA3 +#define SDSS PinA3 #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header @@ -111,16 +111,16 @@ */ #if HAS_CUTTER #if !HAS_EXTRUDERS - #define SPINDLE_LASER_PWM_PIN PinL3 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN PinK0 // Pullup! - #define SPINDLE_DIR_PIN PinL1 - #elif !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use - #define SPINDLE_LASER_ENA_PIN PinH1 // Pullup or pulldown! - #define SPINDLE_DIR_PIN PinH0 + #define SPINDLE_LASER_PWM_PIN PinL3 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinK0 // Pullup! + #define SPINDLE_DIR_PIN PinL1 + #elif !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // Use expansion header if no LCD in use + #define SPINDLE_LASER_ENA_PIN PinH1 // Pullup or pulldown! + #define SPINDLE_DIR_PIN PinH0 #if !NUM_SERVOS // Use servo connector if possible - #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM #endif #endif #endif @@ -132,23 +132,23 @@ #undef BEEPER_PIN // TODO: Remap EXP1/2 based on adapter - #define LCD_PINS_RS PinA5 - #define LCD_PINS_ENABLE PinA7 - #define LCD_PINS_D4 PinC0 - #define LCD_PINS_D5 PinC2 - #define LCD_PINS_D6 PinC4 - #define LCD_PINS_D7 PinC6 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinC0 + #define LCD_PINS_D5 PinC2 + #define LCD_PINS_D6 PinC4 + #define LCD_PINS_D7 PinC6 // Buttons - #define BTN_EN1 PinH1 - #define BTN_EN2 PinH0 - #define BTN_ENC PinA1 + #define BTN_EN1 PinH1 + #define BTN_EN2 PinH0 + #define BTN_ENC PinA1 #define LCD_PINS_DEFINED #else - #define BEEPER_PIN PinC4 + #define BEEPER_PIN PinC4 #endif // HAS_WIRED_LCD && IS_NEWPANEL @@ -158,6 +158,6 @@ #define BOARD_ST7920_DELAY_3 0 #endif -#define SD_DETECT_PIN PinB0 +#define SD_DETECT_PIN PinB0 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h index 2dc7f77fa2ee..39054b299861 100644 --- a/Marlin/src/pins/ramps/pins_DAGOMA_F5.h +++ b/Marlin/src/pins/ramps/pins_DAGOMA_F5.h @@ -32,13 +32,13 @@ // // Endstops // -#define X_STOP_PIN PinE4 -#define Y_STOP_PIN PinE5 -#define Z_STOP_PIN PinJ0 +#define X_STOP_PIN PinE4 +#define Y_STOP_PIN PinE5 +#define Z_STOP_PIN PinJ0 -#define FIL_RUNOUT_PIN PinG2 +#define FIL_RUNOUT_PIN PinG2 #if EXTRUDERS > 1 - #define FIL_RUNOUT2_PIN PinJ1 + #define FIL_RUNOUT2_PIN PinJ1 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 2a3f04195967..6d5f7a218d25 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -39,7 +39,7 @@ // // Servos // -#define SERVO0_PIN PinB5 +#define SERVO0_PIN PinB5 #define SERVO1_PIN -1 // was 6 #define SERVO2_PIN -1 // was 5 #define SERVO3_PIN -1 @@ -47,112 +47,112 @@ // // Limit Switches // -#define X_MIN_PIN PinE5 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN PinE4 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN PinJ1 -#define Y_MAX_PIN PinJ0 -#define Z_MIN_PIN PinD3 -#define Z_MAX_PIN PinD2 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinC5 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN PinB0 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN PinL0 + #define Y_CS_PIN PinL0 #endif -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN - #define Z_CS_PIN PinG1 + #define Z_CS_PIN PinG1 #endif -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN PinL7 + #define E0_CS_PIN PinL7 #endif -#define E1_STEP_PIN PinC1 -#define E1_DIR_PIN PinC3 -#define E1_ENABLE_PIN PinC7 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN PinL5 + #define E1_CS_PIN PinL5 #endif -#define E2_STEP_PIN PinL7 -#define E2_DIR_PIN PinL6 -#define E2_ENABLE_PIN PinL5 +#define E2_STEP_PIN PinL7 +#define E2_DIR_PIN PinL6 +#define E2_ENABLE_PIN PinL5 // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input -#define TEMP_1_PIN PinJ0 // Analog Input -#define TEMP_BED_PIN PinE5 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinE5 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinH4 -#define HEATER_BED_PIN PinF4 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinF4 -#define FAN_PIN PinH6 +#define FAN_PIN PinH6 #if HAS_FILAMENT_SENSOR - #define FIL_RUNOUT_PIN PinG5 + #define FIL_RUNOUT_PIN PinG5 //#define FIL_RUNOUT2_PIN -1 #else // Though defined as a fan pin, it is utilized as a dedicated laser pin by Formbot. - #define FAN1_PIN PinG5 + #define FAN1_PIN PinG5 #endif // // Misc. Functions // -#define SDSS PinB0 +#define SDSS PinB0 #ifndef LED_PIN - #define LED_PIN PinB7 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED + #define LED_PIN PinB7 // The Formbot v 1 board has almost no unassigned pins on it. The Board's LED #endif // is a good place to get a signal to control the Max7219 LED Matrix. // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN PinE3 // Analog Input +#define FILWIDTH_PIN PinE3 // Analog Input #ifndef PS_ON_PIN - #define PS_ON_PIN PinB6 + #define PS_ON_PIN PinB6 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN PinH5 + #define CASE_LIGHT_PIN PinH5 #endif // @@ -162,24 +162,24 @@ // #if IS_RRD_SC #ifndef BEEPER_PIN - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 #endif - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 - #define BTN_ENC PinC2 - #define SD_DETECT_PIN PinL0 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 // Allow MAX7219 to steal the KILL pin #if !defined(KILL_PIN) && MAX7219_CLK_PIN != 41 && MAX7219_DIN_PIN != 41 && MAX7219_LOAD_PIN != 41 - #define KILL_PIN PinG0 + #define KILL_PIN PinG0 #endif - #define LCD_PINS_RS PinH1 - #define LCD_PINS_ENABLE PinH0 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA3 - #define LCD_PINS_D6 PinA5 - #define LCD_PINS_D7 PinA7 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 5936b50d6f24..58e9b6fee939 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -39,7 +39,7 @@ // // Servos // -#define SERVO0_PIN PinB5 +#define SERVO0_PIN PinB5 #define SERVO1_PIN -1 // was 6 #define SERVO2_PIN -1 #define SERVO3_PIN -1 @@ -47,115 +47,115 @@ // // Limit Switches // -#define X_MIN_PIN PinE5 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN PinE4 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN PinJ1 -#define Y_MAX_PIN PinJ0 -#define Z_MIN_PIN PinD3 -#define Z_MAX_PIN PinD2 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinC5 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN PinB0 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN PinL0 + #define Y_CS_PIN PinL0 #endif -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN - #define Z_CS_PIN PinG1 + #define Z_CS_PIN PinG1 #endif -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN PinL7 + #define E0_CS_PIN PinL7 #endif -#define E1_STEP_PIN PinC1 -#define E1_DIR_PIN PinC3 -#define E1_ENABLE_PIN PinC7 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN PinL5 + #define E1_CS_PIN PinL5 #endif #if HAS_X2_STEPPER - #define X2_STEP_PIN PinL7 - #define X2_DIR_PIN PinL6 - #define X2_ENABLE_PIN PinL5 + #define X2_STEP_PIN PinL7 + #define X2_DIR_PIN PinL6 + #define X2_ENABLE_PIN PinL5 #else - #define E2_STEP_PIN PinL7 - #define E2_DIR_PIN PinL6 - #define E2_ENABLE_PIN PinL5 + #define E2_STEP_PIN PinL7 + #define E2_DIR_PIN PinL6 + #define E2_ENABLE_PIN PinL5 #endif // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input -#define TEMP_1_PIN PinJ0 // Analog Input -#define TEMP_BED_PIN PinJ1 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) - #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card #else - #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinH4 -#define HEATER_BED_PIN PinH5 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN PinH6 -#define FAN1_PIN PinB6 +#define FAN_PIN PinH6 +#define FAN1_PIN PinB6 -#define FIL_RUNOUT_PIN PinA0 -#define FIL_RUNOUT2_PIN PinD0 +#define FIL_RUNOUT_PIN PinA0 +#define FIL_RUNOUT2_PIN PinD0 // // Misc. Functions // -#define SDSS PinB0 +#define SDSS PinB0 #ifndef LED_PIN - #define LED_PIN PinB7 + #define LED_PIN PinB7 #endif #ifndef CASE_LIGHT_PIN - #define CASE_LIGHT_PIN PinE3 + #define CASE_LIGHT_PIN PinE3 #endif #define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM -#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! +#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN PinE3 // Analog Input +#define FILWIDTH_PIN PinE3 // Analog Input // // LCD / Controller @@ -163,21 +163,21 @@ // Formbot only supports REPRAP_DISCOUNT_SMART_CONTROLLER // #if IS_RRD_SC - #define LCD_PINS_RS PinH1 - #define LCD_PINS_ENABLE PinH0 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA3 - #define LCD_PINS_D6 PinA5 - #define LCD_PINS_D7 PinA7 - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 - #define BTN_ENC PinC2 - #define SD_DETECT_PIN PinL0 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 #ifndef KILL_PIN - #define KILL_PIN PinG0 + #define KILL_PIN PinG0 #endif #ifndef BEEPER_PIN - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 0f8bb4fa7cdc..d994297fc73d 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -34,27 +34,27 @@ #define BOARD_INFO_NAME "FYSETC F6 1.3" #endif -#define RESET_PIN PinC7 -#define SPI_FLASH_CS_PIN PinD6 +#define RESET_PIN PinC7 +#define SPI_FLASH_CS_PIN PinD6 // // Servos // -#define SERVO0_PIN PinB7 -#define SERVO1_PIN PinB5 // (PS_ON_PIN) -#define SERVO2_PIN PinB4 // (FIL_RUNOUT_PIN) -#define SERVO3_PIN PinG5 // (RGB_LED_G_PIN) +#define SERVO0_PIN PinB7 +#define SERVO1_PIN PinB5 // (PS_ON_PIN) +#define SERVO2_PIN PinB4 // (FIL_RUNOUT_PIN) +#define SERVO3_PIN PinG5 // (RGB_LED_G_PIN) // // Limit Switches // -#define X_MIN_PIN PinK1 -#define X_MAX_PIN PinK2 -#define Y_MIN_PIN PinJ1 -#define Y_MAX_PIN PinJ0 -#define Z_MIN_PIN PinB6 +#define X_MIN_PIN PinK1 +#define X_MAX_PIN PinK2 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinB6 #ifndef Z_MAX_PIN - #define Z_MAX_PIN PinH6 + #define Z_MAX_PIN PinH6 #endif #ifndef FIL_RUNOUT_PIN @@ -65,52 +65,52 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinH6 // Servos pin + #define Z_MIN_PROBE_PIN PinH6 // Servos pin #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN PinG4 + #define X_CS_PIN PinG4 #endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN PinG2 + #define Y_CS_PIN PinG2 #endif -#define Z_STEP_PIN PinL6 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinF4 +#define Z_STEP_PIN PinL6 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinF4 #ifndef Z_CS_PIN - #define Z_CS_PIN PinJ7 + #define Z_CS_PIN PinJ7 #endif -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN - #define E0_CS_PIN PinL2 + #define E0_CS_PIN PinL2 #endif -#define E1_STEP_PIN PinC1 -#define E1_DIR_PIN PinC3 -#define E1_ENABLE_PIN PinC7 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN - #define E1_CS_PIN PinC5 + #define E1_CS_PIN PinC5 #endif -#define E2_STEP_PIN PinF5 -#define E2_DIR_PIN PinF3 -#define E2_ENABLE_PIN PinG1 +#define E2_STEP_PIN PinF5 +#define E2_DIR_PIN PinF3 +#define E2_ENABLE_PIN PinG1 #ifndef E2_CS_PIN - #define E2_CS_PIN PinL7 + #define E2_CS_PIN PinL7 #endif // @@ -126,37 +126,37 @@ * At the moment, F6 rx pins are not pc interrupt pins */ #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN PinJ2 + #define X_SERIAL_TX_PIN PinJ2 #endif #ifndef X_SERIAL_RX_PIN #define X_SERIAL_RX_PIN -1 // 71 #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PinJ4 + #define Y_SERIAL_TX_PIN PinJ4 #endif #ifndef Y_SERIAL_RX_PIN #define Y_SERIAL_RX_PIN -1 // 73 #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PinE6 + #define Z_SERIAL_TX_PIN PinE6 #endif #ifndef Z_SERIAL_RX_PIN #define Z_SERIAL_RX_PIN -1 // 78 #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PinJ6 + #define E0_SERIAL_TX_PIN PinJ6 #endif #ifndef E0_SERIAL_RX_PIN #define E0_SERIAL_RX_PIN -1 // 76 #endif #ifndef E1_SERIAL_TX_PIN - #define E1_SERIAL_TX_PIN PinD4 + #define E1_SERIAL_TX_PIN PinD4 #endif #ifndef E1_SERIAL_RX_PIN #define E1_SERIAL_RX_PIN -1 // 80 #endif #ifndef E2_SERIAL_TX_PIN - #define E2_SERIAL_TX_PIN PinD5 + #define E2_SERIAL_TX_PIN PinD5 #endif #ifndef E2_SERIAL_RX_PIN #define E2_SERIAL_RX_PIN -1 // 22 @@ -166,33 +166,33 @@ // // Temperature Sensors // -#define TEMP_0_PIN PinB6 // Analog Input -#define TEMP_1_PIN PinB7 // Analog Input -#define TEMP_2_PIN PinJ1 // Analog Input -#define TEMP_BED_PIN PinJ0 // Analog Input +#define TEMP_0_PIN PinB6 // Analog Input +#define TEMP_1_PIN PinB7 // Analog Input +#define TEMP_2_PIN PinJ1 // Analog Input +#define TEMP_BED_PIN PinJ0 // Analog Input #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN PinH6 // Analog Input on X+ endstop + #define FILWIDTH_PIN PinH6 // Analog Input on X+ endstop #endif // // Heaters / Fans // -#define HEATER_0_PIN PinE3 -#define HEATER_1_PIN PinH3 -#define HEATER_2_PIN PinH4 -#define HEATER_BED_PIN PinH5 +#define HEATER_0_PIN PinE3 +#define HEATER_1_PIN PinH3 +#define HEATER_2_PIN PinH4 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN PinL5 -#define FAN1_PIN PinL4 -#define FAN2_PIN PinL3 +#define FAN_PIN PinL5 +#define FAN1_PIN PinL4 +#define FAN2_PIN PinL3 // // Misc. Functions // -#define SDSS PinB0 -#define LED_PIN PinB7 -#define KILL_PIN PinG0 +#define SDSS PinB0 +#define LED_PIN PinB7 +#define KILL_PIN PinG0 #ifndef PS_ON_PIN #define PS_ON_PIN SERVO1_PIN @@ -212,36 +212,36 @@ // // LCDs and Controllers // -#define SD_DETECT_PIN PinL0 +#define SD_DETECT_PIN PinL0 #if ENABLED(FYSETC_242_OLED_12864) - #define BTN_EN1 PinC0 - #define BTN_EN2 PinA7 - #define BTN_ENC PinC2 - #define BEEPER_PIN PinC6 - - #define LCD_PINS_DC PinA3 - #define LCD_PINS_RS PinC4 - #define DOGLCD_CS PinH1 - #define DOGLCD_MOSI PinA1 - #define DOGLCD_SCK PinH0 + #define BTN_EN1 PinC0 + #define BTN_EN2 PinA7 + #define BTN_ENC PinC2 + #define BEEPER_PIN PinC6 + + #define LCD_PINS_DC PinA3 + #define LCD_PINS_RS PinC4 + #define DOGLCD_CS PinH1 + #define DOGLCD_MOSI PinA1 + #define DOGLCD_SCK PinH0 #define DOGLCD_A0 LCD_PINS_DC #undef KILL_PIN - #define NEOPIXEL_PIN PinA5 + #define NEOPIXEL_PIN PinA5 #else - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 #if ENABLED(FYSETC_MINI_12864) // // See https://wiki.fysetc.com/Mini12864_Panel/ // - #define DOGLCD_A0 PinH1 - #define DOGLCD_CS PinH0 + #define DOGLCD_A0 PinH1 + #define DOGLCD_CS PinH0 #if ENABLED(FYSETC_GENERIC_12864_1_1) - #define LCD_BACKLIGHT_PIN PinA5 + #define LCD_BACKLIGHT_PIN PinA5 #endif #define LCD_RESET_PIN 23 // Must be high or open for LCD to operate normally. @@ -249,30 +249,30 @@ #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PinA3 + #define RGB_LED_R_PIN PinA3 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PinA5 + #define RGB_LED_G_PIN PinA5 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PinA7 + #define RGB_LED_B_PIN PinA7 #endif #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN PinA3 + #define NEOPIXEL_PIN PinA3 #endif #elif HAS_MARLINUI_U8GLIB || HAS_MARLINUI_HD44780 - #define LCD_PINS_RS PinH1 - #define LCD_PINS_ENABLE PinH0 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA3 - #define LCD_PINS_D6 PinA5 - #define LCD_PINS_D7 PinA7 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 + #define LCD_PINS_D7 PinA7 #if ENABLED(MKS_MINI_12864) - #define DOGLCD_CS PinA3 - #define DOGLCD_A0 PinA5 + #define DOGLCD_CS PinA3 + #define DOGLCD_A0 PinA5 #endif #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) @@ -282,20 +282,20 @@ #endif #if IS_NEWPANEL - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 - #define BTN_ENC PinC2 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 #endif #endif #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN PinE5 + #define RGB_LED_R_PIN PinE5 #endif #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN PinG5 + #define RGB_LED_G_PIN PinG5 #endif #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN PinH6 + #define RGB_LED_B_PIN PinH6 #endif #ifndef RGB_LED_W_PIN #define RGB_LED_W_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h index c10c7f49696a..d92b3323dc39 100644 --- a/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h +++ b/Marlin/src/pins/ramps/pins_LONGER3D_LKx_PRO.h @@ -41,9 +41,9 @@ #endif #if SERIAL_PORT == 3 || SERIAL_PORT_2 == 3 || SERIAL_PORT_3 == 3 || LCD_SERIAL_PORT == 3 #warning "Serial 3 is originally reserved for Y limit switches. Hardware changes are required to use it." - #define Y_STOP_PIN PinC0 + #define Y_STOP_PIN PinC0 #if MB(LONGER3D_LKx_PRO) - #define Z_STOP_PIN PinC2 + #define Z_STOP_PIN PinC2 #endif #endif @@ -58,7 +58,7 @@ // Servos // #if MB(LONGER3D_LKx_PRO) - #define SERVO0_PIN PinH4 + #define SERVO0_PIN PinH4 #endif #define SERVO1_PIN -1 #define SERVO2_PIN -1 @@ -68,28 +68,28 @@ // Limit Switches // #if ENABLED(LONGER_LK5) - #define X_MIN_PIN PinE5 - #define X_MAX_PIN PinE4 + #define X_MIN_PIN PinE5 + #define X_MAX_PIN PinE4 #else - #define X_STOP_PIN PinE5 + #define X_STOP_PIN PinE5 #endif #if !ANY_PIN(Y_MIN, Y_MAX, Y_STOP) #if ENABLED(LONGER_LK5) - #define Y_STOP_PIN PinJ1 + #define Y_STOP_PIN PinJ1 #else - #define Y_MIN_PIN PinJ1 - #define Y_MAX_PIN PinJ0 + #define Y_MIN_PIN PinJ1 + #define Y_MAX_PIN PinJ0 #endif #endif #if !ANY_PIN(Z_MIN, Z_MAX, Z_STOP) #if MB(LONGER3D_LKx_PRO) - #define Z_MIN_PIN PinC2 + #define Z_MIN_PIN PinC2 #else - #define Z_MIN_PIN PinB5 + #define Z_MIN_PIN PinB5 #endif - #define Z_MAX_PIN PinC0 + #define Z_MAX_PIN PinC0 #endif // @@ -120,8 +120,8 @@ // // Misc. Functions // -#define SD_DETECT_PIN PinL0 -#define FIL_RUNOUT_PIN PinE4 +#define SD_DETECT_PIN PinL0 +#define FIL_RUNOUT_PIN PinE4 // ------------------ ---------------- --------------- ------------- // Aux-1 | D19 D18 GND 5V | J21 | D4 D5 D6 GND | J17 | D11 GND 24V | J18 | D7 GND 5V | diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 5f81c564d3d8..0e683d005ab5 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -36,7 +36,7 @@ // // Servos // -#define SERVO1_PIN PinB6 // Digital 12 / Pin 25 +#define SERVO1_PIN PinB6 // Digital 12 / Pin 25 // // Omitted RAMPS pins diff --git a/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h index 86ecf5196caf..a8860d8ccef1 100644 --- a/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h +++ b/Marlin/src/pins/ramps/pins_PXMALION_CORE_I3.h @@ -34,7 +34,7 @@ // // Servos // -#define SERVO0_PIN PinB2 +#define SERVO0_PIN PinB2 #define SERVO1_PIN -1 #define SERVO2_PIN -1 #define SERVO3_PIN -1 @@ -42,10 +42,10 @@ // // Limit Switches // -#define X_STOP_PIN PinE5 -#define Y_STOP_PIN PinE4 -#define Z_MIN_PIN PinD2 -#define Z_MAX_PIN PinD3 +#define X_STOP_PIN PinE5 +#define Y_STOP_PIN PinE4 +#define Z_MIN_PIN PinD2 +#define Z_MAX_PIN PinD3 // TODO: Filament Runout Sensor #ifndef FIL_RUNOUT_PIN @@ -66,13 +66,13 @@ // #define FET_ORDER_EFB #ifndef MOSFET_A_PIN - #define MOSFET_A_PIN PinH5 + #define MOSFET_A_PIN PinH5 #endif #ifndef MOSFET_B_PIN - #define MOSFET_B_PIN PinH4 + #define MOSFET_B_PIN PinH4 #endif #ifndef MOSFET_C_PIN - #define MOSFET_C_PIN PinH6 + #define MOSFET_C_PIN PinH6 #endif // @@ -82,6 +82,6 @@ #define FILWIDTH_PIN -1 // Analog Input #endif -#define PS_ON_PIN PinB5 +#define PS_ON_PIN PinB5 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 0fdd4a334672..d69ab218886a 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -67,19 +67,19 @@ // #ifndef SERVO0_PIN #ifdef IS_RAMPS_13 - #define SERVO0_PIN PinH4 + #define SERVO0_PIN PinH4 #else - #define SERVO0_PIN PinB5 + #define SERVO0_PIN PinB5 #endif #endif #ifndef SERVO1_PIN - #define SERVO1_PIN PinH3 + #define SERVO1_PIN PinH3 #endif #ifndef SERVO2_PIN - #define SERVO2_PIN PinE3 + #define SERVO2_PIN PinE3 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN PinG5 + #define SERVO3_PIN PinG5 #endif // @@ -91,7 +91,7 @@ #define MOSFET_C_PIN -1 #endif #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) && NUM_SERVOS < 2 - #define SPINDLE_LASER_PWM_PIN PinH5 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH5 // Hardware PWM #endif #ifndef Z_MIN_PIN #define Z_MIN_PIN -1 @@ -100,10 +100,10 @@ #define Z_MAX_PIN -1 #endif #ifndef I_STOP_PIN - #define I_STOP_PIN PinD3 + #define I_STOP_PIN PinD3 #endif #ifndef J_STOP_PIN - #define J_STOP_PIN PinD2 + #define J_STOP_PIN PinD2 #endif #endif @@ -112,26 +112,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN PinE5 + #define X_MIN_PIN PinE5 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN PinE4 + #define X_MAX_PIN PinE4 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN PinJ1 + #define Y_MIN_PIN PinJ1 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN PinJ0 + #define Y_MAX_PIN PinJ0 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN PinD3 + #define Z_MIN_PIN PinD3 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN PinD2 + #define Z_MAX_PIN PinD2 #endif #endif @@ -139,96 +139,96 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinC5 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN - #define X_CS_PIN PinB0 + #define X_CS_PIN PinB0 #endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN - #define Y_CS_PIN PinL0 + #define Y_CS_PIN PinL0 #endif #ifndef Z_STEP_PIN - #define Z_STEP_PIN PinL3 + #define Z_STEP_PIN PinL3 #endif #ifndef Z_DIR_PIN - #define Z_DIR_PIN PinL1 + #define Z_DIR_PIN PinL1 #endif #ifndef Z_ENABLE_PIN - #define Z_ENABLE_PIN PinK0 + #define Z_ENABLE_PIN PinK0 #endif #ifndef Z_CS_PIN - #define Z_CS_PIN PinG1 + #define Z_CS_PIN PinG1 #endif #ifndef E0_STEP_PIN - #define E0_STEP_PIN PinA4 + #define E0_STEP_PIN PinA4 #endif #ifndef E0_DIR_PIN - #define E0_DIR_PIN PinA6 + #define E0_DIR_PIN PinA6 #endif #ifndef E0_ENABLE_PIN - #define E0_ENABLE_PIN PinA2 + #define E0_ENABLE_PIN PinA2 #endif #ifndef E0_CS_PIN - #define E0_CS_PIN PinL7 + #define E0_CS_PIN PinL7 #endif #ifndef E1_STEP_PIN - #define E1_STEP_PIN PinC1 + #define E1_STEP_PIN PinC1 #endif #ifndef E1_DIR_PIN - #define E1_DIR_PIN PinC3 + #define E1_DIR_PIN PinC3 #endif #ifndef E1_ENABLE_PIN - #define E1_ENABLE_PIN PinC7 + #define E1_ENABLE_PIN PinC7 #endif #ifndef E1_CS_PIN - #define E1_CS_PIN PinL5 + #define E1_CS_PIN PinL5 #endif // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN PinB7 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN PinJ0 // Analog Input + #define TEMP_1_PIN PinJ0 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN PinJ1 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // SPI for MAX Thermocouple // #ifndef TEMP_0_CS_PIN - #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) + #define TEMP_0_CS_PIN PinK4 // Don't use 53 if using Display/SD card (SDSS) or 49 (SD_DETECT_PIN) #endif // // Heaters / Fans // #ifndef MOSFET_A_PIN - #define MOSFET_A_PIN PinB4 + #define MOSFET_A_PIN PinB4 #endif #ifndef MOSFET_B_PIN - #define MOSFET_B_PIN PinH6 + #define MOSFET_B_PIN PinH6 #endif #ifndef MOSFET_C_PIN - #define MOSFET_C_PIN PinH5 + #define MOSFET_C_PIN PinH5 #endif #ifndef MOSFET_D_PIN #define MOSFET_D_PIN -1 @@ -266,7 +266,7 @@ #elif EITHER(FET_ORDER_EEF, FET_ORDER_SF) // Hotend, Hotend, Fan or Spindle, Fan #define FAN_PIN MOSFET_C_PIN #elif FET_ORDER_EEB // Hotend, Hotend, Bed - #define FAN_PIN PinG5 // IO pin. Buffer needed + #define FAN_PIN PinG5 // IO pin. Buffer needed #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") #define FAN_PIN MOSFET_B_PIN #endif @@ -278,26 +278,26 @@ #ifndef SDSS #define SDSS AUX3_06_PIN #endif -#define LED_PIN PinB7 +#define LED_PIN PinB7 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 + #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 #endif // RAMPS 1.4 DIO 4 on the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PinG5 + #define FIL_RUNOUT_PIN PinG5 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN PinB6 + #define PS_ON_PIN PinB6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN PinH3 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN PinL5 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -306,15 +306,15 @@ // #if HAS_CUTTER && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS < 2 // Use servo connector if possible - #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! #ifndef SPINDLE_LASER_PWM_PIN - #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM #endif - #define SPINDLE_DIR_PIN PinE3 + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM - #define SPINDLE_DIR_PIN PinK3 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #else #error "No auto-assignable Spindle/Laser pins available." #endif @@ -324,13 +324,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PinK4 + #define TMC_SPI_MOSI PinK4 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PinL5 + #define TMC_SPI_MISO PinL5 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PinK2 + #define TMC_SPI_SCK PinK2 #endif #if HAS_TMC_UART @@ -356,10 +356,10 @@ //#define E4_HARDWARE_SERIAL Serial1 #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN PinG1 + #define X_SERIAL_TX_PIN PinG1 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN PinK1 + #define X_SERIAL_RX_PIN PinK1 #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 @@ -369,10 +369,10 @@ #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PinF5 + #define Y_SERIAL_TX_PIN PinF5 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN PinK2 + #define Y_SERIAL_RX_PIN PinK2 #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 @@ -382,10 +382,10 @@ #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PinL7 + #define Z_SERIAL_TX_PIN PinL7 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN PinK3 + #define Z_SERIAL_RX_PIN PinK3 #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN -1 @@ -395,10 +395,10 @@ #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PinL5 + #define E0_SERIAL_TX_PIN PinL5 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN PinK4 + #define E0_SERIAL_RX_PIN PinK4 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 @@ -449,13 +449,13 @@ // #if HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN PinG1 // Z_CS_PIN + #define E_MUX0_PIN PinG1 // Z_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN PinL7 // E0_CS_PIN + #define E_MUX1_PIN PinL7 // E0_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN PinL5 // E1_CS_PIN + #define E_MUX2_PIN PinL5 // E1_CS_PIN #endif #endif @@ -465,10 +465,10 @@ // 1 3 5 7 // 5V GND A3 A4 // -#define AUX1_05_PIN PinF3 // (A3) -#define AUX1_06_PIN PinE4 -#define AUX1_07_PIN PinF4 // (A4) -#define AUX1_08_PIN PinE1 +#define AUX1_05_PIN PinF3 // (A3) +#define AUX1_06_PIN PinE4 +#define AUX1_07_PIN PinF4 // (A4) +#define AUX1_08_PIN PinE1 // // AUX2 GND A9 D40 D42 A11 @@ -476,14 +476,14 @@ // 1 3 5 7 9 // VCC A5 A10 D44 A12 // -#define AUX2_03_PIN PinF5 // (A5) -#define AUX2_04_PIN PinK1 // (A9) -#define AUX2_05_PIN PinK2 // (A10) -#define AUX2_06_PIN PinG1 -#define AUX2_07_PIN PinL5 -#define AUX2_08_PIN PinL7 -#define AUX2_09_PIN PinK4 // (A12) -#define AUX2_10_PIN PinK3 // (A11) +#define AUX2_03_PIN PinF5 // (A5) +#define AUX2_04_PIN PinK1 // (A9) +#define AUX2_05_PIN PinK2 // (A10) +#define AUX2_06_PIN PinG1 +#define AUX2_07_PIN PinL5 +#define AUX2_08_PIN PinL7 +#define AUX2_09_PIN PinK4 // (A12) +#define AUX2_10_PIN PinK3 // (A11) // // AUX3 GND D52 D50 5V @@ -491,31 +491,31 @@ // 8 6 4 2 // NC D53 D51 D49 // -#define AUX3_02_PIN PinL0 -#define AUX3_03_PIN PinB3 -#define AUX3_04_PIN PinB2 -#define AUX3_05_PIN PinB1 -#define AUX3_06_PIN PinB0 +#define AUX3_02_PIN PinL0 +#define AUX3_03_PIN PinB3 +#define AUX3_04_PIN PinB2 +#define AUX3_05_PIN PinB1 +#define AUX3_06_PIN PinB0 // // AUX4 5V GND D32 D47 D45 D43 D41 D39 D37 D35 D33 D31 D29 D27 D25 D23 D17 D16 // -#define AUX4_03_PIN PinC5 -#define AUX4_04_PIN PinL2 -#define AUX4_05_PIN PinL4 -#define AUX4_06_PIN PinL6 -#define AUX4_07_PIN PinG0 -#define AUX4_08_PIN PinG2 -#define AUX4_09_PIN PinC0 -#define AUX4_10_PIN PinC2 -#define AUX4_11_PIN PinC4 -#define AUX4_12_PIN PinC6 -#define AUX4_13_PIN PinA7 -#define AUX4_14_PIN PinA5 -#define AUX4_15_PIN PinA3 -#define AUX4_16_PIN PinA1 -#define AUX4_17_PIN PinH0 -#define AUX4_18_PIN PinH1 +#define AUX4_03_PIN PinC5 +#define AUX4_04_PIN PinL2 +#define AUX4_05_PIN PinL4 +#define AUX4_06_PIN PinL6 +#define AUX4_07_PIN PinG0 +#define AUX4_08_PIN PinG2 +#define AUX4_09_PIN PinC0 +#define AUX4_10_PIN PinC2 +#define AUX4_11_PIN PinC4 +#define AUX4_12_PIN PinC6 +#define AUX4_13_PIN PinA7 +#define AUX4_14_PIN PinA5 +#define AUX4_15_PIN PinA3 +#define AUX4_16_PIN PinA1 +#define AUX4_17_PIN PinH0 +#define AUX4_18_PIN PinH1 /** * LCD adapters come in different variants. The socket keys can be @@ -879,7 +879,7 @@ #define BEEPER_PIN EXP2_05_PIN - #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 + #if ENABLED(PANEL_ONE) // Buttons connect directly to AUX-2 #define BTN_EN1 AUX2_03_PIN #define BTN_EN2 AUX2_04_PIN #define BTN_ENC AUX3_02_PIN diff --git a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h index 43f04bb218a1..018abd0dd8ee 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_PLUS.h @@ -43,8 +43,8 @@ #define BOARD_INFO_NAME "RAMPS 1.4 Plus" -#define MOSFET_A_PIN PinH5 -#define MOSFET_C_PIN PinB4 +#define MOSFET_A_PIN PinH5 +#define MOSFET_C_PIN PinB4 // // Steppers @@ -54,14 +54,14 @@ #define Z_CS_PIN -1 // Swap E0 / E1 on 3DYMY -#define E0_STEP_PIN PinC1 -#define E0_DIR_PIN PinC3 -#define E0_ENABLE_PIN PinC7 +#define E0_STEP_PIN PinC1 +#define E0_DIR_PIN PinC3 +#define E0_ENABLE_PIN PinC7 #define E0_CS_PIN -1 -#define E1_STEP_PIN PinA4 -#define E1_DIR_PIN PinA6 -#define E1_ENABLE_PIN PinA2 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA2 #define E1_CS_PIN -1 /** 3DYMY Expansion Headers @@ -74,22 +74,22 @@ * ------ ------ * EXP1 EXP2 */ -#define EXP1_01_PIN PinC0 -#define EXP1_02_PIN PinC2 -#define EXP1_03_PIN PinC6 -#define EXP1_04_PIN PinG0 -#define EXP1_05_PIN PinC4 -#define EXP1_06_PIN PinA1 -#define EXP1_07_PIN PinL7 -#define EXP1_08_PIN PinL5 +#define EXP1_01_PIN PinC0 +#define EXP1_02_PIN PinC2 +#define EXP1_03_PIN PinC6 +#define EXP1_04_PIN PinG0 +#define EXP1_05_PIN PinC4 +#define EXP1_06_PIN PinA1 +#define EXP1_07_PIN PinL7 +#define EXP1_08_PIN PinL5 -#define EXP2_01_PIN PinB3 -#define EXP2_02_PIN PinB1 -#define EXP2_03_PIN PinA7 -#define EXP2_04_PIN PinB0 -#define EXP2_05_PIN PinA3 -#define EXP2_06_PIN PinB2 -#define EXP2_07_PIN PinL0 -#define EXP2_08_PIN PinA5 +#define EXP2_01_PIN PinB3 +#define EXP2_02_PIN PinB1 +#define EXP2_03_PIN PinA7 +#define EXP2_04_PIN PinB0 +#define EXP2_05_PIN PinA3 +#define EXP2_06_PIN PinB2 +#define EXP2_07_PIN PinL0 +#define EXP2_08_PIN PinA5 #include "pins_RAMPS.h" diff --git a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h index 58eb9f659e2f..bd077b918928 100644 --- a/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h +++ b/Marlin/src/pins/ramps/pins_RIGIDBOARD_V2.h @@ -41,12 +41,12 @@ #define DAC_STEPPER_ORDER { 0, 1, 2, 3 } #define DAC_STEPPER_SENSE 0.05 // sense resistors on rigidboard stepper chips are .05 value -#define DAC_STEPPER_ADDRESS 0 -#define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 -#define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V -#define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 -#define DAC_DISABLE_PIN PinL7 // set low to enable DAC -#define DAC_OR_ADDRESS 0x01 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 +#define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V +#define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 +#define DAC_DISABLE_PIN PinL7 // set low to enable DAC +#define DAC_OR_ADDRESS 0x01 #ifndef DAC_MOTOR_CURRENT_DEFAULT #define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index d608348f1c33..f63ea3642943 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -39,90 +39,90 @@ // // Servos // -#define SERVO0_PIN PinB5 -#define SERVO1_PIN PinH3 +#define SERVO0_PIN PinB5 +#define SERVO1_PIN PinH3 #define SERVO2_PIN -1 // Original pin 5 used for hotend fans -#define SERVO3_PIN PinG5 +#define SERVO3_PIN PinG5 // // Limit Switches // -#define X_MIN_PIN PinE5 -#define X_MAX_PIN PinE4 -#define Y_MIN_PIN PinJ1 -//#define Y_MAX_PIN PinJ0 // Connected to "DJ" plug on extruder heads -#define Z_MIN_PIN PinD3 -#define Z_MAX_PIN PinD2 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinJ1 +//#define Y_MAX_PIN PinJ0 // Connected to "DJ" plug on extruder heads +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinJ0 // Ramps is normally 32 + #define Z_MIN_PROBE_PIN PinJ0 // Ramps is normally 32 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 //#ifndef X_CS_PIN - //#define X_CS_PIN PinB0 + //#define X_CS_PIN PinB0 //#endif -#define X2_STEP_PIN PinC1 -#define X2_DIR_PIN PinC3 -#define X2_ENABLE_PIN PinC7 +#define X2_STEP_PIN PinC1 +#define X2_DIR_PIN PinC3 +#define X2_ENABLE_PIN PinC7 //#ifndef X2_CS_PIN - //#define X2_CS_PIN PinB0 + //#define X2_CS_PIN PinB0 //#endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 //#ifndef Y_CS_PIN - //#define Y_CS_PIN PinL0 + //#define Y_CS_PIN PinL0 //#endif -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 //#ifndef Z_CS_PIN - //#define Z_CS_PIN PinG1 + //#define Z_CS_PIN PinG1 //#endif -#define Z2_STEP_PIN PinK3 -#define Z2_DIR_PIN PinK4 -#define Z2_ENABLE_PIN PinK2 +#define Z2_STEP_PIN PinK3 +#define Z2_DIR_PIN PinK4 +#define Z2_ENABLE_PIN PinK2 //#ifndef Z2_CS_PIN - //#define Z2_CS_PIN PinG1 + //#define Z2_CS_PIN PinG1 //#endif -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 //#ifndef E0_CS_PIN //define E0_CS_PIN PinL7 //#endif -#define E1_STEP_PIN PinF3 -#define E1_DIR_PIN PinF4 -#define E1_ENABLE_PIN PinF5 +#define E1_STEP_PIN PinF3 +#define E1_DIR_PIN PinF4 +#define E1_ENABLE_PIN PinF5 //#ifndef E1_CS_PIN //define E1_CS_PIN PinL5 //#endif -//#define E2_STEP_PIN PinL7 -//#define E2_DIR_PIN PinL6 -//#define E2_ENABLE_PIN PinL5 +//#define E2_STEP_PIN PinL7 +//#define E2_DIR_PIN PinL6 +//#define E2_ENABLE_PIN PinL5 // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input -#define TEMP_1_PIN PinJ0 // Analog Input -#define TEMP_BED_PIN PinJ1 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // SPI for MAX Thermocouple #if DISABLED(SDSUPPORT) @@ -134,33 +134,33 @@ // // Heaters / Fans // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinB5 -#define HEATER_BED_PIN PinH5 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinB5 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN PinH6 -#define FAN1_PIN PinE3 // Normally this would be a servo pin +#define FAN_PIN PinH6 +#define FAN1_PIN PinE3 // Normally this would be a servo pin // XXX Runout support unknown? //#define NUM_RUNOUT_SENSORS 0 -//#define FIL_RUNOUT_PIN PinA0 -//#define FIL_RUNOUT2_PIN PinD0 +//#define FIL_RUNOUT_PIN PinA0 +//#define FIL_RUNOUT2_PIN PinD0 // // Misc. Functions // -//#define PS_ON_PIN PinG1 // The M80/M81 PSU pin for boards v2.1-2.3 -//#define CASE_LIGHT_PIN PinE3 -#define SDSS PinB0 +//#define PS_ON_PIN PinG1 // The M80/M81 PSU pin for boards v2.1-2.3 +//#define CASE_LIGHT_PIN PinE3 +#define SDSS PinB0 //#ifndef LED_PIN - //#define LED_PIN PinB7 + //#define LED_PIN PinB7 //#endif //#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM -//#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! +//#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -//#define FILWIDTH_PIN PinE3 // Analog Input +//#define FILWIDTH_PIN PinE3 // Analog Input // // LCD / Controller @@ -174,12 +174,12 @@ #define LCD_PINS_D5 -1 #define LCD_PINS_D6 -1 #define LCD_PINS_D7 -1 -//#define BTN_EN1 PinC6 -//#define BTN_EN2 PinC4 -//#define BTN_ENC PinC2 -#define SD_DETECT_PIN PinL0 +//#define BTN_EN1 PinC6 +//#define BTN_EN2 PinC4 +//#define BTN_ENC PinC2 +#define SD_DETECT_PIN PinL0 //#ifndef KILL_PIN - //#define KILL_PIN PinG0 + //#define KILL_PIN PinG0 //#endif //#ifndef BEEPER_PIN #define BEEPER_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 9a0bf5ee7e92..36b49216774c 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -35,20 +35,20 @@ // // Servos // -#define SERVO0_PIN PinB5 -#define SERVO1_PIN PinB6 -#define SERVO2_PIN PinE3 -#define SERVO3_PIN PinG5 +#define SERVO0_PIN PinB5 +#define SERVO1_PIN PinB6 +#define SERVO2_PIN PinE3 +#define SERVO3_PIN PinG5 // // Limit Switches // -#define X_MIN_PIN PinE5 -#define X_MAX_PIN PinE4 -#define Y_MIN_PIN PinJ1 -#define Y_MAX_PIN PinJ0 -#define Z_MIN_PIN PinD3 -#define Z_MAX_PIN PinD2 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) @@ -60,44 +60,44 @@ // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 -#define X_CS_PIN PinF3 - -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 -#define Y_CS_PIN PinF4 - -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 -#define Z_CS_PIN PinB0 - -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 -#define E0_CS_PIN PinL0 - -#define E1_STEP_PIN PinC1 -#define E1_DIR_PIN PinC3 -#define E1_ENABLE_PIN PinC7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 +#define X_CS_PIN PinF3 + +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 +#define Y_CS_PIN PinF4 + +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 +#define Z_CS_PIN PinB0 + +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 +#define E0_CS_PIN PinL0 + +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #define E1_CS_PIN E0_CS_PIN -#define E2_STEP_PIN PinK1 -#define E2_DIR_PIN PinA0 -#define E2_ENABLE_PIN PinF5 +#define E2_STEP_PIN PinK1 +#define E2_DIR_PIN PinA0 +#define E2_ENABLE_PIN PinF5 #define E2_CS_PIN E0_CS_PIN -#define E3_STEP_PIN PinC5 -#define E3_DIR_PIN PinG1 -#define E3_ENABLE_PIN PinG2 +#define E3_STEP_PIN PinC5 +#define E3_DIR_PIN PinG1 +#define E3_ENABLE_PIN PinG2 #define E3_CS_PIN E0_CS_PIN -#define E4_STEP_PIN PinL6 -#define E4_DIR_PIN PinL7 -#define E4_ENABLE_PIN PinL2 +#define E4_STEP_PIN PinL6 +#define E4_DIR_PIN PinL7 +#define E4_ENABLE_PIN PinL2 #define E4_CS_PIN E0_CS_PIN #if HAS_TMC_UART @@ -165,16 +165,16 @@ // // Temperature Sensors // -#define TEMP_0_PIN PinB7 -#define TEMP_1_PIN PinJ0 -#define TEMP_2_PIN PinB4 -#define TEMP_3_PIN PinB5 -#define TEMP_BED_PIN PinJ1 +#define TEMP_0_PIN PinB7 +#define TEMP_1_PIN PinJ0 +#define TEMP_2_PIN PinB4 +#define TEMP_3_PIN PinB5 +#define TEMP_BED_PIN PinJ1 #if TEMP_SENSOR_CHAMBER > 0 - #define TEMP_CHAMBER_PIN PinB6 + #define TEMP_CHAMBER_PIN PinB6 #else - #define TEMP_4_PIN PinB6 + #define TEMP_4_PIN PinB6 #endif // SPI for MAX Thermocouple @@ -187,30 +187,30 @@ // // Heaters / Fans // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinH4 -#define HEATER_2_PIN PinL5 -#define HEATER_BED_PIN PinH5 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinL5 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN PinH6 +#define FAN_PIN PinH6 #if EXTRUDERS >= 5 - #define HEATER_4_PIN PinH3 + #define HEATER_4_PIN PinH3 #else - #define FAN1_PIN PinH3 + #define FAN1_PIN PinH3 #endif #if EXTRUDERS >= 4 - #define HEATER_3_PIN PinL4 + #define HEATER_3_PIN PinL4 #else - #define FAN2_PIN PinL4 + #define FAN2_PIN PinL4 #endif // // Misc. Functions // -#define SDSS PinB0 -#define LED_PIN PinB7 +#define SDSS PinB0 +#define LED_PIN PinB7 //#ifndef FILWIDTH_PIN // #define FILWIDTH_PIN 5 // Analog Input @@ -220,7 +220,7 @@ //#define FIL_RUNOUT_PIN SERVO3_PIN #ifndef PS_ON_PIN - #define PS_ON_PIN PinB6 + #define PS_ON_PIN PinB6 #endif // @@ -228,13 +228,13 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !NUM_SERVOS // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM - #define SPINDLE_DIR_PIN PinE3 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM - #define SPINDLE_DIR_PIN PinK3 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #endif #endif @@ -243,9 +243,9 @@ // #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENA_PIN) #if !NUM_SERVOS // Prefer the servo connector - #define CASE_LIGHT_PIN PinH3 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS // Try to use AUX 2 - #define CASE_LIGHT_PIN PinL5 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -254,13 +254,13 @@ // #if 0 && HAS_PRUSA_MMU1 #ifndef E_MUX0_PIN - #define E_MUX0_PIN PinF4 // Y_CS_PIN + #define E_MUX0_PIN PinF4 // Y_CS_PIN #endif #ifndef E_MUX1_PIN - #define E_MUX1_PIN PinB0 // Z_CS_PIN + #define E_MUX1_PIN PinB0 // Z_CS_PIN #endif #ifndef E_MUX2_PIN - #define E_MUX2_PIN PinL0 // En_CS_PIN + #define E_MUX2_PIN PinL0 // En_CS_PIN #endif #endif @@ -275,63 +275,63 @@ // #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS PinL0 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PinB2 // SID (MOSI) - #define LCD_PINS_D4 PinB1 // SCK (CLK) clock + #define LCD_PINS_RS PinL0 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinB2 // SID (MOSI) + #define LCD_PINS_D4 PinB1 // SCK (CLK) clock #elif BOTH(IS_NEWPANEL, PANEL_ONE) - #define LCD_PINS_RS PinG1 - #define LCD_PINS_ENABLE PinL7 - #define LCD_PINS_D4 PinK3 - #define LCD_PINS_D5 PinK4 - #define LCD_PINS_D6 PinL5 - #define LCD_PINS_D7 PinK2 + #define LCD_PINS_RS PinG1 + #define LCD_PINS_ENABLE PinL7 + #define LCD_PINS_D4 PinK3 + #define LCD_PINS_D5 PinK4 + #define LCD_PINS_D6 PinL5 + #define LCD_PINS_D7 PinK2 #elif ENABLED(ZONESTAR_LCD) - #define LCD_PINS_RS PinK2 - #define LCD_PINS_ENABLE PinL5 - #define LCD_PINS_D4 PinK1 - #define LCD_PINS_D5 PinG1 - #define LCD_PINS_D6 PinL7 - #define LCD_PINS_D7 PinK3 - #define ADC_KEYPAD_PIN PinB6 + #define LCD_PINS_RS PinK2 + #define LCD_PINS_ENABLE PinL5 + #define LCD_PINS_D4 PinK1 + #define LCD_PINS_D5 PinG1 + #define LCD_PINS_D6 PinL7 + #define LCD_PINS_D7 PinK3 + #define ADC_KEYPAD_PIN PinB6 #else #if ENABLED(CR10_STOCKDISPLAY) - #define LCD_PINS_RS PinA5 - #define LCD_PINS_ENABLE PinA7 - #define LCD_PINS_D4 PinA3 + #define LCD_PINS_RS PinA5 + #define LCD_PINS_ENABLE PinA7 + #define LCD_PINS_D4 PinA3 #if !IS_NEWPANEL - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 #endif #else #if EITHER(MKS_12864OLED, MKS_12864OLED_SSD1306) - #define LCD_PINS_DC PinA3 // Set as output on init - #define LCD_PINS_RS PinA5 // Pull low for 1s to init + #define LCD_PINS_DC PinA3 // Set as output on init + #define LCD_PINS_RS PinA5 // Pull low for 1s to init // DOGM SPI LCD Support - #define DOGLCD_CS PinH1 - #define DOGLCD_MOSI PinH0 - #define DOGLCD_SCK PinA1 + #define DOGLCD_CS PinH1 + #define DOGLCD_MOSI PinH0 + #define DOGLCD_SCK PinA1 #define DOGLCD_A0 LCD_PINS_DC #else - #define LCD_PINS_RS PinH1 - #define LCD_PINS_ENABLE PinH0 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA3 - #define LCD_PINS_D6 PinA5 + #define LCD_PINS_RS PinH1 + #define LCD_PINS_ENABLE PinH0 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA3 + #define LCD_PINS_D6 PinA5 #endif - #define LCD_PINS_D7 PinA7 + #define LCD_PINS_D7 PinA7 #if !IS_NEWPANEL - #define BEEPER_PIN PinC4 + #define BEEPER_PIN PinC4 #endif #endif @@ -339,10 +339,10 @@ #if !IS_NEWPANEL // Buttons attached to a shift register // Not wired yet - //#define SHIFT_CLK_PIN PinD7 - //#define SHIFT_LD_PIN PinL7 - //#define SHIFT_OUT_PIN PinG1 - //#define SHIFT_EN_PIN PinH0 + //#define SHIFT_CLK_PIN PinD7 + //#define SHIFT_LD_PIN PinL7 + //#define SHIFT_OUT_PIN PinG1 + //#define SHIFT_EN_PIN PinH0 #endif #endif @@ -358,118 +358,118 @@ #if IS_RRD_SC - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 #if ENABLED(CR10_STOCKDISPLAY) - #define BTN_EN1 PinH0 - #define BTN_EN2 PinA1 + #define BTN_EN1 PinH0 + #define BTN_EN2 PinA1 #else - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 #endif - #define BTN_ENC PinC2 - #define SD_DETECT_PIN PinL0 - //#define KILL_PIN PinG0 + #define BTN_ENC PinC2 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_BACKLIGHT_PIN PinG2 + #define LCD_BACKLIGHT_PIN PinG2 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 PinK2 - #define BTN_EN2 PinF5 - #define BTN_ENC PinK1 - #define SD_DETECT_PIN PinL7 + #define BTN_EN1 PinK2 + #define BTN_EN2 PinF5 + #define BTN_ENC PinK1 + #define SD_DETECT_PIN PinL7 #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 PinL2 - #define BTN_EN2 PinL6 - #define BTN_ENC PinC5 - #define LCD_SDSS PinB0 - //#define KILL_PIN PinG0 + #define BTN_EN1 PinL2 + #define BTN_EN2 PinL6 + #define BTN_ENC PinC5 + #define LCD_SDSS PinB0 + //#define KILL_PIN PinG0 #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 PinA0 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. - #define BTN_EN2 PinH4 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + #define BTN_EN1 PinA0 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 PinH4 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. #define BTN_ENC -1 - #define LCD_SDSS PinB0 - #define SD_DETECT_PIN PinL0 + #define LCD_SDSS PinB0 + #define SD_DETECT_PIN PinL0 #elif EITHER(VIKI2, miniVIKI) - #define DOGLCD_CS PinL4 - #define DOGLCD_A0 PinL5 + #define DOGLCD_CS PinL4 + #define DOGLCD_A0 PinL5 - #define BEEPER_PIN PinC4 - #define STAT_LED_RED_PIN PinC5 - #define STAT_LED_BLUE_PIN PinC2 + #define BEEPER_PIN PinC4 + #define STAT_LED_RED_PIN PinC5 + #define STAT_LED_BLUE_PIN PinC2 - #define BTN_EN1 PinA0 - #define BTN_EN2 PinH4 - #define BTN_ENC PinG2 + #define BTN_EN1 PinA0 + #define BTN_EN2 PinH4 + #define BTN_ENC PinG2 - #define SDSS PinB0 + #define SDSS PinB0 #define SD_DETECT_PIN -1 // Pin 49 for display SD interface, 72 for easy adapter board - //#define KILL_PIN PinC6 + //#define KILL_PIN PinC6 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define DOGLCD_CS PinA7 - #define DOGLCD_A0 PinA5 + #define DOGLCD_CS PinA7 + #define DOGLCD_A0 PinA5 - #define BEEPER_PIN PinA1 - #define LCD_BACKLIGHT_PIN PinC4 + #define BEEPER_PIN PinA1 + #define LCD_BACKLIGHT_PIN PinC4 - #define BTN_EN1 PinC2 - #define BTN_EN2 PinC0 - #define BTN_ENC PinC6 + #define BTN_EN1 PinC2 + #define BTN_EN2 PinC0 + #define BTN_ENC PinC6 - #define LCD_SDSS PinB0 - #define SD_DETECT_PIN PinL0 - //#define KILL_PIN PinG0 + #define LCD_SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #elif ENABLED(MKS_MINI_12864) - #define DOGLCD_A0 PinA5 - #define DOGLCD_CS PinA3 + #define DOGLCD_A0 PinA5 + #define DOGLCD_CS PinA3 - #define BEEPER_PIN PinC0 + #define BEEPER_PIN PinC0 - #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 - #define BTN_ENC PinC2 - //#define SDSS PinB0 - #define SD_DETECT_PIN PinL0 - //#define KILL_PIN PinK2 + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + //#define SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinK2 //#define LCD_CONTRAST_INIT 190 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN PinL7 + #define BEEPER_PIN PinL7 // not connected to a pin - #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN PinK3 // backlight LED on A11/D65 - #define DOGLCD_A0 PinL5 - #define DOGLCD_CS PinK4 + #define DOGLCD_A0 PinL5 + #define DOGLCD_CS PinK4 - #define BTN_EN1 PinG1 - #define BTN_EN2 PinK1 - #define BTN_ENC PinF5 + #define BTN_EN1 PinG1 + #define BTN_EN2 PinK1 + #define BTN_ENC PinF5 - #define SDSS PinB0 - #define SD_DETECT_PIN PinL0 - //#define KILL_PIN PinK2 + #define SDSS PinB0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinK2 //#define LCD_CONTRAST_INIT 190 //#define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -477,29 +477,29 @@ #else // Beeper on AUX-4 - #define BEEPER_PIN PinC4 + #define BEEPER_PIN PinC4 // Buttons are directly attached to AUX-2 #if IS_RRW_KEYPAD - #define SHIFT_OUT_PIN PinG1 - #define SHIFT_CLK_PIN PinL5 - #define SHIFT_LD_PIN PinL7 - #define BTN_EN1 PinK2 - #define BTN_EN2 PinF5 - #define BTN_ENC PinK1 + #define SHIFT_OUT_PIN PinG1 + #define SHIFT_CLK_PIN PinL5 + #define SHIFT_LD_PIN PinL7 + #define BTN_EN1 PinK2 + #define BTN_EN2 PinF5 + #define BTN_ENC PinK1 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 PinF5 // AUX2 PIN 3 - #define BTN_EN2 PinK1 // AUX2 PIN 4 - #define BTN_ENC PinL0 // AUX3 PIN 7 + #define BTN_EN1 PinF5 // AUX2 PIN 3 + #define BTN_EN2 PinK1 // AUX2 PIN 4 + #define BTN_ENC PinL0 // AUX3 PIN 7 #else - #define BTN_EN1 PinC0 - #define BTN_EN2 PinC2 - #define BTN_ENC PinC6 + #define BTN_EN1 PinC0 + #define BTN_EN2 PinC2 + #define BTN_ENC PinC6 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN PinL0 - //#define KILL_PIN PinG0 + #define SD_DETECT_PIN PinL0 + //#define KILL_PIN PinG0 #endif #endif diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 2c1cc9fd885c..6761d46dba19 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -39,34 +39,34 @@ // // PIN 12 Connector // -#define PIN_12_PIN PinB6 +#define PIN_12_PIN PinB6 // // XS1 Connector // -#define XS1_01_PIN PinL7 -#define XS1_03_PIN PinL6 -#define XS1_05_PIN PinL5 -#define XS1_07_PIN PinL4 -#define XS1_08_PIN PinL2 +#define XS1_01_PIN PinL7 +#define XS1_03_PIN PinL6 +#define XS1_05_PIN PinL5 +#define XS1_07_PIN PinL4 +#define XS1_08_PIN PinL2 // // XS6 Connector // -#define XS6_01_PIN PinD1 -#define XS6_03_PIN PinB1 -#define XS6_05_PIN PinB2 -#define XS6_07_PIN PinB3 -#define XS6_08_PIN PinD0 +#define XS6_01_PIN PinD1 +#define XS6_03_PIN PinB1 +#define XS6_05_PIN PinB2 +#define XS6_07_PIN PinB3 +#define XS6_08_PIN PinD0 // // Servos / XS3 Connector // #ifndef SERVO0_PIN - #define SERVO0_PIN PinK3 // PWM + #define SERVO0_PIN PinK3 // PWM #endif #ifndef SERVO1_PIN - #define SERVO1_PIN PinK4 // PWM + #define SERVO1_PIN PinK4 // PWM #endif // @@ -74,26 +74,26 @@ // #ifndef X_STOP_PIN #ifndef X_MIN_PIN - #define X_MIN_PIN PinE5 + #define X_MIN_PIN PinE5 #endif #ifndef X_MAX_PIN - #define X_MAX_PIN PinE4 + #define X_MAX_PIN PinE4 #endif #endif #ifndef Y_STOP_PIN #ifndef Y_MIN_PIN - #define Y_MIN_PIN PinJ1 + #define Y_MIN_PIN PinJ1 #endif #ifndef Y_MAX_PIN - #define Y_MAX_PIN PinJ0 + #define Y_MAX_PIN PinJ0 #endif #endif #ifndef Z_STOP_PIN #ifndef Z_MIN_PIN - #define Z_MIN_PIN PinD3 + #define Z_MIN_PIN PinD3 #endif #ifndef Z_MAX_PIN - #define Z_MAX_PIN PinD2 + #define Z_MAX_PIN PinD2 #endif #endif @@ -101,81 +101,81 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinD2 + #define Z_MIN_PROBE_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #if NUM_Z_STEPPERS == 2 - #define Z2_STEP_PIN PinA4 // E0 connector - #define Z2_DIR_PIN PinA6 - #define Z2_ENABLE_PIN PinA2 + #define Z2_STEP_PIN PinA4 // E0 connector + #define Z2_DIR_PIN PinA6 + #define Z2_ENABLE_PIN PinA2 - #define E0_STEP_PIN PinC1 // E1 connector - #define E0_DIR_PIN PinC3 - #define E0_ENABLE_PIN PinC7 + #define E0_STEP_PIN PinC1 // E1 connector + #define E0_DIR_PIN PinC3 + #define E0_ENABLE_PIN PinC7 - #define E1_STEP_PIN PinG5 // E2 connector - #define E1_DIR_PIN PinE3 - #define E1_ENABLE_PIN PinA0 + #define E1_STEP_PIN PinG5 // E2 connector + #define E1_DIR_PIN PinE3 + #define E1_ENABLE_PIN PinA0 #else - #define E0_STEP_PIN PinA4 - #define E0_DIR_PIN PinA6 - #define E0_ENABLE_PIN PinA2 + #define E0_STEP_PIN PinA4 + #define E0_DIR_PIN PinA6 + #define E0_ENABLE_PIN PinA2 - #define E1_STEP_PIN PinC1 - #define E1_DIR_PIN PinC3 - #define E1_ENABLE_PIN PinC7 + #define E1_STEP_PIN PinC1 + #define E1_DIR_PIN PinC3 + #define E1_ENABLE_PIN PinC7 - #define E2_STEP_PIN PinG5 - #define E2_DIR_PIN PinE3 - #define E2_ENABLE_PIN PinA0 + #define E2_STEP_PIN PinG5 + #define E2_DIR_PIN PinE3 + #define E2_ENABLE_PIN PinA0 #endif // // Temperature Sensors // #ifndef TEMP_0_PIN - #define TEMP_0_PIN PinB7 // Analog Input + #define TEMP_0_PIN PinB7 // Analog Input #endif #ifndef TEMP_1_PIN - #define TEMP_1_PIN PinJ0 // Analog Input + #define TEMP_1_PIN PinJ0 // Analog Input #endif #ifndef TEMP_BED_PIN - #define TEMP_BED_PIN PinJ1 // Analog Input + #define TEMP_BED_PIN PinJ1 // Analog Input #endif // // Heaters / Fans Connectors // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinH4 -#define FAN_PIN PinH6 -#define HEATER_BED_PIN PinH5 -#define FAN1_PIN PinH3 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define FAN_PIN PinH6 +#define HEATER_BED_PIN PinH5 +#define FAN1_PIN PinH3 // // Misc. Functions // #ifndef SDSS - #define SDSS PinB0 + #define SDSS PinB0 #endif -#define LED_PIN PinB7 +#define LED_PIN PinB7 #ifndef FIL_RUNOUT_PIN #define FIL_RUNOUT_PIN XS1_01_PIN @@ -310,23 +310,23 @@ */ #ifndef EXP1_08_PIN - #define EXP1_01_PIN PinC0 - #define EXP1_02_PIN PinC2 - #define EXP1_03_PIN PinH0 - #define EXP1_04_PIN PinH1 - #define EXP1_05_PIN PinA1 - #define EXP1_06_PIN PinA3 - #define EXP1_07_PIN PinA5 - #define EXP1_08_PIN PinA7 + #define EXP1_01_PIN PinC0 + #define EXP1_02_PIN PinC2 + #define EXP1_03_PIN PinH0 + #define EXP1_04_PIN PinH1 + #define EXP1_05_PIN PinA1 + #define EXP1_06_PIN PinA3 + #define EXP1_07_PIN PinA5 + #define EXP1_08_PIN PinA7 #define EXP2_01_PIN XS6_07_PIN #define EXP2_02_PIN XS6_03_PIN - #define EXP2_03_PIN PinC6 - #define EXP2_04_PIN PinB0 - #define EXP2_05_PIN PinC4 + #define EXP2_03_PIN PinC6 + #define EXP2_04_PIN PinB0 + #define EXP2_05_PIN PinC4 #define EXP2_06_PIN XS6_05_PIN - #define EXP2_07_PIN PinL0 - #define EXP2_08_PIN PinG0 + #define EXP2_07_PIN PinL0 + #define EXP2_08_PIN PinG0 #endif ////////////////////////// @@ -335,26 +335,26 @@ #if ENABLED(ZONESTAR_12864LCD) #define LCDSCREEN_NAME "ZONESTAR LCD12864" - #define LCD_SDSS PinH1 - #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS (PIN4 of LCD module) - #define LCD_PINS_ENABLE PinA1 // ST7920_DAT_PIN LCD_PIN_R/W (PIN5 of LCD module) - #define LCD_PINS_D4 PinH0 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) - #define BTN_EN2 PinA3 - #define BTN_EN1 PinA5 - #define BTN_ENC PinA7 - #define BEEPER_PIN PinC0 - #define KILL_PIN PinC2 + #define LCD_SDSS PinH1 + #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS (PIN4 of LCD module) + #define LCD_PINS_ENABLE PinA1 // ST7920_DAT_PIN LCD_PIN_R/W (PIN5 of LCD module) + #define LCD_PINS_D4 PinH0 // ST7920_CLK_PIN LCD_PIN_ENABLE (PIN6 of LCD module) + #define BTN_EN2 PinA3 + #define BTN_EN1 PinA5 + #define BTN_ENC PinA7 + #define BEEPER_PIN PinC0 + #define KILL_PIN PinC2 #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define LCDSCREEN_NAME "Reprap LCD12864" // Use EXP1 & EXP2 connector - #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS - #define LCD_PINS_ENABLE PinH0 // ST7920_DAT_PIN LCD_PIN_ENABLE - #define LCD_PINS_D4 PinA1 // ST7920_CLK_PIN LCD_PIN_R/W - #define BTN_EN1 PinC6 - #define BTN_EN2 PinC4 - #define BTN_ENC PinC2 - #define BEEPER_PIN PinC0 - #define KILL_PIN PinG0 + #define LCD_PINS_RS PinH1 // ST7920_CS_PIN LCD_PIN_RS + #define LCD_PINS_ENABLE PinH0 // ST7920_DAT_PIN LCD_PIN_ENABLE + #define LCD_PINS_D4 PinA1 // ST7920_CLK_PIN LCD_PIN_R/W + #define BTN_EN1 PinC6 + #define BTN_EN2 PinC4 + #define BTN_ENC PinC2 + #define BEEPER_PIN PinC0 + #define KILL_PIN PinG0 #endif //================================================================================ @@ -363,21 +363,21 @@ #if EITHER(ZONESTAR_12864OLED, ZONESTAR_12864OLED_SSD1306) #define LCDSCREEN_NAME "ZONESTAR 12864OLED" - #define LCD_SDSS PinH1 - #define LCD_PINS_RS PinA1 // RESET Pull low for 1s to init - #define LCD_PINS_DC PinH0 - #define DOGLCD_CS PinH1 // CS - #define BTN_EN2 PinA3 - #define BTN_EN1 PinA5 - #define BTN_ENC PinA7 + #define LCD_SDSS PinH1 + #define LCD_PINS_RS PinA1 // RESET Pull low for 1s to init + #define LCD_PINS_DC PinH0 + #define DOGLCD_CS PinH1 // CS + #define BTN_EN2 PinA3 + #define BTN_EN1 PinA5 + #define BTN_ENC PinA7 #define BEEPER_PIN -1 #define KILL_PIN -1 #if EITHER(OLED_HW_IIC, OLED_HW_SPI) #error "Oops! You must choose SW SPI for ZRIB V53 board and connect the OLED screen to EXP1 connector." #else // SW_SPI #define DOGLCD_A0 LCD_PINS_DC - #define DOGLCD_MOSI PinC2 // SDA - #define DOGLCD_SCK PinC0 // SCK + #define DOGLCD_MOSI PinC2 // SDA + #define DOGLCD_SCK PinC0 // SCK #endif #endif // OLED 128x64 @@ -393,7 +393,7 @@ #define LCD_PINS_D5 EXP1_06_PIN #define LCD_PINS_D6 EXP1_07_PIN #define LCD_PINS_D7 EXP1_08_PIN - #define ADC_KEYPAD_PIN PinB4 // A10 for ADCKEY + #define ADC_KEYPAD_PIN PinB4 // A10 for ADCKEY #define BEEPER_PIN EXP1_01_PIN #endif diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 02e2c2a4c23a..611125025b2a 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -39,81 +39,81 @@ // Servos // #ifndef SERVO0_PIN - #define SERVO0_PIN PinB5 + #define SERVO0_PIN PinB5 #endif #ifndef SERVO3_PIN - #define SERVO3_PIN PinG5 + #define SERVO3_PIN PinG5 #endif // // Limit Switches // -#define X_MIN_PIN PinE5 +#define X_MIN_PIN PinE5 #ifndef X_MAX_PIN - #define X_MAX_PIN PinE4 + #define X_MAX_PIN PinE4 #endif -#define Y_MIN_PIN PinJ1 -#define Y_MAX_PIN PinJ0 -#define Z_MIN_PIN PinD3 -#define Z_MAX_PIN PinD2 +#define Y_MIN_PIN PinJ1 +#define Y_MAX_PIN PinJ0 +#define Z_MIN_PIN PinD3 +#define Z_MAX_PIN PinD2 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PinC5 + #define Z_MIN_PROBE_PIN PinC5 #endif // // Steppers // -#define X_STEP_PIN PinF0 -#define X_DIR_PIN PinF1 -#define X_ENABLE_PIN PinD7 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 #ifndef X_CS_PIN #define X_CS_PIN -1 #endif -#define Y_STEP_PIN PinF6 -#define Y_DIR_PIN PinF7 -#define Y_ENABLE_PIN PinF2 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 #ifndef Y_CS_PIN #define Y_CS_PIN -1 #endif -#define Z_STEP_PIN PinL3 -#define Z_DIR_PIN PinL1 -#define Z_ENABLE_PIN PinK0 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 #ifndef Z_CS_PIN #define Z_CS_PIN -1 #endif -#define E0_STEP_PIN PinA4 -#define E0_DIR_PIN PinA6 -#define E0_ENABLE_PIN PinA2 +#define E0_STEP_PIN PinA4 +#define E0_DIR_PIN PinA6 +#define E0_ENABLE_PIN PinA2 #ifndef E0_CS_PIN #define E0_CS_PIN -1 #endif -#define E1_STEP_PIN PinC1 -#define E1_DIR_PIN PinC3 -#define E1_ENABLE_PIN PinC7 +#define E1_STEP_PIN PinC1 +#define E1_DIR_PIN PinC3 +#define E1_ENABLE_PIN PinC7 #ifndef E1_CS_PIN #define E1_CS_PIN -1 #endif // Red -#define E2_STEP_PIN PinL7 -#define E2_DIR_PIN PinG1 -#define E2_ENABLE_PIN PinK3 +#define E2_STEP_PIN PinL7 +#define E2_DIR_PIN PinG1 +#define E2_ENABLE_PIN PinK3 #ifndef E2_CS_PIN #define E2_CS_PIN -1 #endif // Black -#define E3_STEP_PIN PinL5 -#define E3_DIR_PIN PinK2 -#define E3_ENABLE_PIN PinK4 +#define E3_STEP_PIN PinL5 +#define E3_DIR_PIN PinK2 +#define E3_ENABLE_PIN PinK4 #ifndef E3_CS_PIN #define E3_CS_PIN -1 #endif @@ -121,47 +121,47 @@ // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input -#define TEMP_1_PIN PinJ0 // Analog Input -#define TEMP_2_PIN PinE3 // Analog Input (BLACK) -#define TEMP_3_PIN PinH6 // Analog Input (RED) -#define TEMP_BED_PIN PinJ1 // Analog Input +#define TEMP_0_PIN PinB7 // Analog Input +#define TEMP_1_PIN PinJ0 // Analog Input +#define TEMP_2_PIN PinE3 // Analog Input (BLACK) +#define TEMP_3_PIN PinH6 // Analog Input (RED) +#define TEMP_BED_PIN PinJ1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN PinB4 -#define HEATER_1_PIN PinH4 -#define HEATER_2_PIN PinH3 -#define HEATER_3_PIN PinE3 -#define HEATER_BED_PIN PinH5 +#define HEATER_0_PIN PinB4 +#define HEATER_1_PIN PinH4 +#define HEATER_2_PIN PinH3 +#define HEATER_3_PIN PinE3 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN PinH6 +#define FAN_PIN PinH6 // // Misc. Functions // -#define SDSS PinB0 -#define LED_PIN PinB7 +#define SDSS PinB0 +#define LED_PIN PinB7 #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 + #define FILWIDTH_PIN PinE3 // Analog Input on AUX2 #endif // Оn the servos connector #ifndef FIL_RUNOUT_PIN - #define FIL_RUNOUT_PIN PinG5 + #define FIL_RUNOUT_PIN PinG5 #endif #ifndef PS_ON_PIN - #define PS_ON_PIN PinB6 + #define PS_ON_PIN PinB6 #endif #if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN) #if NUM_SERVOS <= 1 // Prefer the servo connector - #define CASE_LIGHT_PIN PinH3 // Hardware PWM + #define CASE_LIGHT_PIN PinH3 // Hardware PWM #elif HAS_FREE_AUX2_PINS - #define CASE_LIGHT_PIN PinL5 // Hardware PWM + #define CASE_LIGHT_PIN PinL5 // Hardware PWM #endif #endif @@ -170,13 +170,13 @@ // #if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector - #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM - #define SPINDLE_DIR_PIN PinE3 + #define SPINDLE_LASER_ENA_PIN PinG5 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinH3 // Hardware PWM + #define SPINDLE_DIR_PIN PinE3 #elif HAS_FREE_AUX2_PINS - #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM - #define SPINDLE_DIR_PIN PinK3 + #define SPINDLE_LASER_ENA_PIN PinG1 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinL5 // Hardware PWM + #define SPINDLE_DIR_PIN PinK3 #endif #endif @@ -184,13 +184,13 @@ // TMC SPI // #ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PinK4 + #define TMC_SPI_MOSI PinK4 #endif #ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PinL5 + #define TMC_SPI_MISO PinL5 #endif #ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PinK2 + #define TMC_SPI_SCK PinK2 #endif #if HAS_TMC_UART @@ -213,10 +213,10 @@ //#define E4_HARDWARE_SERIAL Serial1 #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN PinG1 + #define X_SERIAL_TX_PIN PinG1 #endif #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN PinK1 + #define X_SERIAL_RX_PIN PinK1 #endif #ifndef X2_SERIAL_TX_PIN #define X2_SERIAL_TX_PIN -1 @@ -226,10 +226,10 @@ #endif #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN PinF5 + #define Y_SERIAL_TX_PIN PinF5 #endif #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN PinK2 + #define Y_SERIAL_RX_PIN PinK2 #endif #ifndef Y2_SERIAL_TX_PIN #define Y2_SERIAL_TX_PIN -1 @@ -239,10 +239,10 @@ #endif #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN PinL7 + #define Z_SERIAL_TX_PIN PinL7 #endif #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN PinK3 + #define Z_SERIAL_RX_PIN PinK3 #endif #ifndef Z2_SERIAL_TX_PIN #define Z2_SERIAL_TX_PIN -1 @@ -252,10 +252,10 @@ #endif #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN PinL5 + #define E0_SERIAL_TX_PIN PinL5 #endif #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN PinK4 + #define E0_SERIAL_RX_PIN PinK4 #endif #ifndef E1_SERIAL_TX_PIN #define E1_SERIAL_TX_PIN -1 diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index fc2dc1e57510..f068ad8384dd 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -111,49 +111,49 @@ // // Limit Switches // -#define X_STOP_PIN PinC2 -#define Y_STOP_PIN PinC3 -#define Z_STOP_PIN PinC4 +#define X_STOP_PIN PinC2 +#define Y_STOP_PIN PinC3 +#define Z_STOP_PIN PinC4 // // Steppers // -#define X_STEP_PIN PinD7 -#define X_DIR_PIN PinC5 -#define X_ENABLE_PIN PinD6 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC5 +#define X_ENABLE_PIN PinD6 -#define Y_STEP_PIN PinC6 -#define Y_DIR_PIN PinC7 -#define Y_ENABLE_PIN PinD6 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC7 +#define Y_ENABLE_PIN PinD6 -#define Z_STEP_PIN PinB3 -#define Z_DIR_PIN PinB2 -#define Z_ENABLE_PIN PinA5 +#define Z_STEP_PIN PinB3 +#define Z_DIR_PIN PinB2 +#define Z_ENABLE_PIN PinA5 -#define E0_STEP_PIN PinB1 -#define E0_DIR_PIN PinB0 -#define E0_ENABLE_PIN PinD6 +#define E0_STEP_PIN PinB1 +#define E0_DIR_PIN PinB0 +#define E0_ENABLE_PIN PinD6 // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN PinD5 // (extruder) -#define HEATER_BED_PIN PinD4 // (bed) +#define HEATER_0_PIN PinD5 // (extruder) +#define HEATER_BED_PIN PinD4 // (bed) #ifndef FAN_PIN - #define FAN_PIN PinB4 + #define FAN_PIN PinB4 #endif // // Misc. Functions // -#define SDSS PinA0 +#define SDSS PinA0 #define LED_PIN -1 /** @@ -167,18 +167,18 @@ #if HAS_WIRED_LCD - #define LCD_SDSS PinA3 + #define LCD_SDSS PinA3 #if HAS_ADC_BUTTONS - #define SERVO0_PIN PinA4 // free for BLTouch/3D-Touch - #define LCD_PINS_RS PinA3 - #define LCD_PINS_ENABLE PinA2 - #define LCD_PINS_D4 PinD2 - #define LCD_PINS_D5 PinD3 - #define LCD_PINS_D6 PinC0 - #define LCD_PINS_D7 PinC1 - #define ADC_KEYPAD_PIN PinB1 + #define SERVO0_PIN PinA4 // free for BLTouch/3D-Touch + #define LCD_PINS_RS PinA3 + #define LCD_PINS_ENABLE PinA2 + #define LCD_PINS_D4 PinD2 + #define LCD_PINS_D5 PinD3 + #define LCD_PINS_D6 PinC0 + #define LCD_PINS_D7 PinC1 + #define ADC_KEYPAD_PIN PinB1 #elif IS_RRD_FG_SC @@ -187,26 +187,26 @@ // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 #if ENABLED(ANET_FULL_GRAPHICS_LCD_ALT_WIRING) - #define SERVO0_PIN PinA1 - #define BEEPER_PIN PinA4 - #define LCD_PINS_RS PinA2 - #define LCD_PINS_ENABLE PinC0 - #define LCD_PINS_D4 PinD3 - #define BTN_EN1 PinA3 - #define BTN_EN2 PinD2 - #define BTN_ENC PinC1 + #define SERVO0_PIN PinA1 + #define BEEPER_PIN PinA4 + #define LCD_PINS_RS PinA2 + #define LCD_PINS_ENABLE PinC0 + #define LCD_PINS_D4 PinD3 + #define BTN_EN1 PinA3 + #define BTN_EN2 PinD2 + #define BTN_ENC PinC1 #define BOARD_ST7920_DELAY_1 250 #define BOARD_ST7920_DELAY_2 250 #define BOARD_ST7920_DELAY_3 250 #else - #define SERVO0_PIN PinA2 // free for BLTouch/3D-Touch - #define BEEPER_PIN PinC1 - #define LCD_PINS_RS PinA4 - #define LCD_PINS_ENABLE PinA3 - #define LCD_PINS_D4 PinA1 - #define BTN_EN1 PinD3 - #define BTN_EN2 PinD2 - #define BTN_ENC PinC0 + #define SERVO0_PIN PinA2 // free for BLTouch/3D-Touch + #define BEEPER_PIN PinC1 + #define LCD_PINS_RS PinA4 + #define LCD_PINS_ENABLE PinA3 + #define LCD_PINS_D4 PinA1 + #define BTN_EN1 PinD3 + #define BTN_EN2 PinD2 + #define BTN_ENC PinC0 #define BOARD_ST7920_DELAY_1 125 #define BOARD_ST7920_DELAY_2 63 #define BOARD_ST7920_DELAY_3 125 @@ -215,7 +215,7 @@ #endif #else - #define SERVO0_PIN PinA4 + #define SERVO0_PIN PinA4 #endif #ifndef FIL_RUNOUT_PIN diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index d57d000334f9..9d8fe015a489 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -84,28 +84,28 @@ // // Limit Switches // -#define X_STOP_PIN PinB0 -#define Y_STOP_PIN PinB1 -#define Z_STOP_PIN PinB2 +#define X_STOP_PIN PinB0 +#define Y_STOP_PIN PinB1 +#define Z_STOP_PIN PinB2 // // Steppers // -#define X_STEP_PIN PinA5 -#define X_DIR_PIN PinA6 -#define X_ENABLE_PIN PinD2 +#define X_STEP_PIN PinA5 +#define X_DIR_PIN PinA6 +#define X_ENABLE_PIN PinD2 -#define Y_STEP_PIN PinA3 -#define Y_DIR_PIN PinA4 -#define Y_ENABLE_PIN PinD2 +#define Y_STEP_PIN PinA3 +#define Y_DIR_PIN PinA4 +#define Y_ENABLE_PIN PinD2 -#define Z_STEP_PIN PinC7 -#define Z_DIR_PIN PinC6 -#define Z_ENABLE_PIN PinD2 +#define Z_STEP_PIN PinC7 +#define Z_DIR_PIN PinC6 +#define Z_ENABLE_PIN PinD2 -#define E0_STEP_PIN PinA7 -#define E0_DIR_PIN PinC5 -#define E0_ENABLE_PIN PinD2 +#define E0_STEP_PIN PinA7 +#define E0_DIR_PIN PinC5 +#define E0_ENABLE_PIN PinD2 #define E1_STEP_PIN -1 // 21 #define E1_DIR_PIN -1 // 20 @@ -118,32 +118,32 @@ // // Temperature Sensors // -#define TEMP_0_PIN PinB0 // Analog Input -#define TEMP_1_PIN PinB1 // Analog Input -#define TEMP_BED_PIN PinB2 // Analog Input (1,2 or I2C) +#define TEMP_0_PIN PinB0 // Analog Input +#define TEMP_1_PIN PinB1 // Analog Input +#define TEMP_BED_PIN PinB2 // Analog Input (1,2 or I2C) // // Heaters / Fans // -#define HEATER_0_PIN PinB3 // DONE PWM on RIGHT connector -#define HEATER_BED_PIN PinB4 +#define HEATER_0_PIN PinB3 // DONE PWM on RIGHT connector +#define HEATER_BED_PIN PinB4 #ifndef FAN_PIN - #define FAN_PIN PinD6 // PWM on MIDDLE connector + #define FAN_PIN PinD6 // PWM on MIDDLE connector #endif // // Misc. Functions // -#define SDSS PinD3 +#define SDSS PinD3 -#define I2C_SCL_PIN PinC0 -#define I2C_SDA_PIN PinC1 +#define I2C_SCL_PIN PinC0 +#define I2C_SDA_PIN PinC1 // future proofing -#define __FS PinC4 -#define __FD PinC3 -#define __GS PinC2 -#define __GD PinD5 +#define __FS PinC4 +#define __FD PinC3 +#define __GS PinC2 +#define __GD PinD5 -#define UNUSED_PWM PinD6 // PWM on LEFT connector +#define UNUSED_PWM PinD6 // PWM on LEFT connector diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 64506af4c819..ab261041ea4d 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -60,48 +60,48 @@ // // Limit Switches // -#define X_STOP_PIN PinC2 -#define Y_STOP_PIN PinC3 -#define Z_STOP_PIN PinC4 +#define X_STOP_PIN PinC2 +#define Y_STOP_PIN PinC3 +#define Z_STOP_PIN PinC4 // // Steppers // -#define X_STEP_PIN PinD7 -#define X_DIR_PIN PinC5 +#define X_STEP_PIN PinD7 +#define X_DIR_PIN PinC5 -#define Y_STEP_PIN PinC6 -#define Y_DIR_PIN PinC7 +#define Y_STEP_PIN PinC6 +#define Y_DIR_PIN PinC7 -#define Z_STEP_PIN PinB3 -#define Z_DIR_PIN PinB2 +#define Z_STEP_PIN PinB3 +#define Z_DIR_PIN PinB2 -#define E0_STEP_PIN PinB1 -#define E0_DIR_PIN PinB0 +#define E0_STEP_PIN PinB1 +#define E0_DIR_PIN PinB0 // // Temperature Sensors // -#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) -#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) +#define TEMP_0_PIN PinB7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN PinB6 // Analog Input (pin 34 bed) // // Heaters / Fans // -#define HEATER_0_PIN PinD5 // (extruder) +#define HEATER_0_PIN PinD5 // (extruder) #ifndef FAN_PIN - #define FAN_PIN PinB4 // Works for Panelolu2 too + #define FAN_PIN PinB4 // Works for Panelolu2 too #endif #if DISABLED(SANGUINOLOLU_V_1_2) - #define HEATER_BED_PIN PinD6 // (bed) - #define X_ENABLE_PIN PinB4 - #define Y_ENABLE_PIN PinB4 + #define HEATER_BED_PIN PinD6 // (bed) + #define X_ENABLE_PIN PinB4 + #define Y_ENABLE_PIN PinB4 #ifndef Z_ENABLE_PIN - #define Z_ENABLE_PIN PinB4 + #define Z_ENABLE_PIN PinB4 #endif - #define E0_ENABLE_PIN PinB4 + #define E0_ENABLE_PIN PinB4 #endif // @@ -114,17 +114,17 @@ * If you encounter issues with these pins, upgrade your * Sanguino libraries! See #368. */ -//#define SDSS PinA7 -#define SDSS PinA0 +//#define SDSS PinA7 +#define SDSS PinA0 #if IS_MELZI - #define LED_PIN PinA4 + #define LED_PIN PinA4 #elif MB(STB_11) - #define LCD_BACKLIGHT_PIN PinC1 // LCD backlight LED + #define LCD_BACKLIGHT_PIN PinC1 // LCD backlight LED #endif -#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header - #define CASE_LIGHT_PIN PinB4 // Hardware PWM - see if IO Header is available +#if !HAS_CUTTER && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL)// try to use IO Header + #define CASE_LIGHT_PIN PinB4 // Hardware PWM - see if IO Header is available #endif /** @@ -147,49 +147,49 @@ #if ENABLED(LCD_FOR_MELZI) - #define LCD_PINS_RS PinC1 - #define LCD_PINS_ENABLE PinC0 - #define LCD_PINS_D4 PinD3 - #define KILL_PIN PinD2 - #define BEEPER_PIN PinA4 + #define LCD_PINS_RS PinC1 + #define LCD_PINS_ENABLE PinC0 + #define LCD_PINS_D4 PinD3 + #define KILL_PIN PinD2 + #define BEEPER_PIN PinA4 - #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #elif IS_U8GLIB_ST7920 // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI - #define LCD_PINS_RS PinA1 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE PinA2 // SID (MOSI) - #define LCD_PINS_D4 PinC1 // SCK (CLK) clock + #define LCD_PINS_RS PinA1 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE PinA2 // SID (MOSI) + #define LCD_PINS_D4 PinC1 // SCK (CLK) clock // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. - #define BEEPER_PIN PinA4 + #define BEEPER_PIN PinA4 #else // Sanguinololu >=1.3 - #define LCD_PINS_RS PinB4 - #define LCD_PINS_ENABLE PinC1 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA2 - #define LCD_PINS_D6 PinA3 - #define LCD_PINS_D7 PinA4 + #define LCD_PINS_RS PinB4 + #define LCD_PINS_ENABLE PinC1 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA2 + #define LCD_PINS_D6 PinA3 + #define LCD_PINS_D7 PinA4 #endif #else - #define DOGLCD_A0 PinA1 + #define DOGLCD_A0 PinA1 #if ENABLED(MAKRPANEL) - #define BEEPER_PIN PinA2 - #define DOGLCD_CS PinC1 - #define LCD_BACKLIGHT_PIN PinA3 // PA3 + #define BEEPER_PIN PinA2 + #define DOGLCD_CS PinC1 + #define LCD_BACKLIGHT_PIN PinA3 // PA3 #elif IS_MELZI - #define BEEPER_PIN PinA4 - #define DOGLCD_CS PinA3 + #define BEEPER_PIN PinA4 + #define DOGLCD_CS PinA3 #else // !MAKRPANEL - #define DOGLCD_CS PinA2 + #define DOGLCD_CS PinA2 #endif @@ -199,59 +199,59 @@ #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define LCD_PINS_RS PinA3 - #define LCD_PINS_ENABLE PinA2 - #define LCD_PINS_D4 PinD2 - #define LCD_PINS_D5 PinD3 - #define LCD_PINS_D6 PinC0 - #define LCD_PINS_D7 PinC1 + #define LCD_PINS_RS PinA3 + #define LCD_PINS_ENABLE PinA2 + #define LCD_PINS_D4 PinD2 + #define LCD_PINS_D5 PinD3 + #define LCD_PINS_D6 PinC0 + #define LCD_PINS_D7 PinC1 #else - #define LCD_PINS_RS PinB4 - #define LCD_PINS_ENABLE PinC1 - #define LCD_PINS_D4 PinA1 - #define LCD_PINS_D5 PinA2 - #define LCD_PINS_D6 PinA3 - #define LCD_PINS_D7 PinA4 + #define LCD_PINS_RS PinB4 + #define LCD_PINS_ENABLE PinC1 + #define LCD_PINS_D4 PinA1 + #define LCD_PINS_D5 PinA2 + #define LCD_PINS_D6 PinA3 + #define LCD_PINS_D7 PinA4 #endif #if ENABLED(LCD_FOR_MELZI) - #define BTN_ENC PinA3 - #define BTN_EN1 PinA2 - #define BTN_EN2 PinA1 + #define BTN_ENC PinA3 + #define BTN_EN1 PinA2 + #define BTN_EN2 PinA1 #elif ENABLED(ZONESTAR_LCD) // For the Tronxy Melzi boards - #define ADC_KEYPAD_PIN PinB1 + #define ADC_KEYPAD_PIN PinB1 #define BTN_EN1 -1 #define BTN_EN2 -1 #elif ENABLED(LCD_I2C_PANELOLU2) #if IS_MELZI - #define BTN_ENC PinA2 + #define BTN_ENC PinA2 #ifndef LCD_SDSS - #define LCD_SDSS PinA1 // Panelolu2 SD card reader rather than the Melzi + #define LCD_SDSS PinA1 // Panelolu2 SD card reader rather than the Melzi #endif #else - #define BTN_ENC PinA1 + #define BTN_ENC PinA1 #endif #else // !LCD_FOR_MELZI && !ZONESTAR_LCD && !LCD_I2C_PANELOLU2 - #define BTN_ENC PinC0 + #define BTN_ENC PinC0 #ifndef LCD_SDSS - #define LCD_SDSS PinA3 // Smart Controller SD card reader rather than the Melzi + #define LCD_SDSS PinA3 // Smart Controller SD card reader rather than the Melzi #endif #endif #if IS_NEWPANEL && !defined(BTN_EN1) - #define BTN_EN1 PinD3 - #define BTN_EN2 PinD2 + #define BTN_EN1 PinD3 + #define BTN_EN2 PinD2 #endif #endif // HAS_WIRED_LCD @@ -260,11 +260,11 @@ // M3/M4/M5 - Spindle/Laser Control // #if HAS_CUTTER - #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL) // try to use IO Header + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !BOTH(HAS_WIRED_LCD, IS_NEWPANEL)// try to use IO Header - #define SPINDLE_LASER_ENA_PIN PinD2 // Pullup or pulldown! - #define SPINDLE_LASER_PWM_PIN PinB4 // Hardware PWM - #define SPINDLE_DIR_PIN PinD3 + #define SPINDLE_LASER_ENA_PIN PinD2 // Pullup or pulldown! + #define SPINDLE_LASER_PWM_PIN PinB4 // Hardware PWM + #define SPINDLE_DIR_PIN PinD3 #elif !MB(MELZI) // use X stepper motor socket @@ -298,11 +298,11 @@ #undef X_DIR_PIN #undef X_ENABLE_PIN #undef X_STEP_PIN - #define X_DIR_PIN PinB0 - #define X_ENABLE_PIN PinD6 - #define X_STEP_PIN PinB1 - #define SPINDLE_LASER_PWM_PIN PinD7 // Hardware PWM - #define SPINDLE_LASER_ENA_PIN PinC5 // Pullup! + #define X_DIR_PIN PinB0 + #define X_ENABLE_PIN PinD6 + #define X_STEP_PIN PinB1 + #define SPINDLE_LASER_PWM_PIN PinD7 // Hardware PWM + #define SPINDLE_LASER_ENA_PIN PinC5 // Pullup! #define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin #endif #endif diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index f9ba526fd56c..e06c27be8072 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -97,51 +97,51 @@ // // Limit Switches // -#define X_STOP_PIN PinE3 // E3 -#define Y_STOP_PIN PinB4 // B4 PWM2A -#define Z_STOP_PIN PinE4 // E4 +#define X_STOP_PIN PinE3 // E3 +#define Y_STOP_PIN PinB4 // B4 PWM2A +#define Z_STOP_PIN PinE4 // E4 // // Steppers // -#define X_STEP_PIN PinA0 // A0 -#define X_DIR_PIN PinA1 // A1 -#define X_ENABLE_PIN PinE7 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN PinA2 // A2 -#define Y_DIR_PIN PinA3 // A3 -#define Y_ENABLE_PIN PinE6 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN PinA4 // A4 -#define Z_DIR_PIN PinA5 // A5 -#define Z_ENABLE_PIN PinC7 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN PinA6 // A6 -#define E0_DIR_PIN PinA7 // A7 -#define E0_ENABLE_PIN PinC3 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define E1_STEP_PIN PinB5 // B5 - #define E1_DIR_PIN PinE5 // E5 - #define E1_ENABLE_PIN PinF4 // F4 + #define E1_STEP_PIN PinB5 // B5 + #define E1_DIR_PIN PinE5 // E5 + #define E1_ENABLE_PIN PinF4 // F4 - #define E2_STEP_PIN PinD2 // D2 - #define E2_DIR_PIN PinD3 // D3 - #define E2_ENABLE_PIN PinF5 // F5 + #define E2_STEP_PIN PinD2 // D2 + #define E2_DIR_PIN PinD3 // D3 + #define E2_ENABLE_PIN PinF5 // F5 #else - #define E1_STEP_PIN PinD2 // D2 - #define E1_DIR_PIN PinD3 // D3 - #define E1_ENABLE_PIN PinF5 // F5 + #define E1_STEP_PIN PinD2 // D2 + #define E1_DIR_PIN PinD3 // D3 + #define E1_ENABLE_PIN PinF5 // F5 - #define E2_STEP_PIN PinB5 // B5 - #define E2_DIR_PIN PinE5 // E5 - #define E2_ENABLE_PIN PinF4 // F4 + #define E2_STEP_PIN PinB5 // B5 + #define E2_DIR_PIN PinE5 // E5 + #define E2_ENABLE_PIN PinF4 // F4 #endif #endif // NO_EXTRUDRBOARD // Enable control of stepper motor currents with the I2C based MCP4728 DAC used on Printrboard REVF -#define HAS_MOTOR_CURRENT_DAC 1 +#define HAS_MOTOR_CURRENT_DAC 1 // Set default drive strength percents if not already defined - X, Y, Z, E axis #ifndef DAC_MOTOR_CURRENT_DEFAULT @@ -161,37 +161,37 @@ // // Temperature Sensors // -#define TEMP_0_PIN PinD1 // Analog Input (Extruder) -#define TEMP_BED_PIN PinD0 // Analog Input (Bed) +#define TEMP_0_PIN PinD1 // Analog Input (Extruder) +#define TEMP_BED_PIN PinD0 // Analog Input (Bed) #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define TEMP_1_PIN PinD2 // Analog Input (Extrudrboard A THERM) - #define TEMP_2_PIN PinD3 // Analog Input (Extrudrboard B THERM) + #define TEMP_1_PIN PinD2 // Analog Input (Extrudrboard A THERM) + #define TEMP_2_PIN PinD3 // Analog Input (Extrudrboard B THERM) #else - #define TEMP_1_PIN PinD3 // Analog Input (Extrudrboard B THERM) - #define TEMP_2_PIN PinD2 // Analog Input (Extrudrboard A THERM) + #define TEMP_1_PIN PinD3 // Analog Input (Extrudrboard B THERM) + #define TEMP_2_PIN PinD2 // Analog Input (Extrudrboard A THERM) #endif #endif // // Heaters / Fans // -#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder -#define HEATER_BED_PIN PinC4 // C4 PWM3C +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C #if DISABLED(NO_EXTRUDRBOARD) #if DISABLED(NO_EXTRUDRBOARD_OUTPUT_SWAP) - #define HEATER_1_PIN PinF6 // F6 - Extrudrboard A HOTEND - #define HEATER_2_PIN PinF7 // F7 - Extrudrboard B HOTEND + #define HEATER_1_PIN PinF6 // F6 - Extrudrboard A HOTEND + #define HEATER_2_PIN PinF7 // F7 - Extrudrboard B HOTEND #else - #define HEATER_1_PIN PinF7 // F7 - Extrudrboard B HOTEND - #define HEATER_2_PIN PinF6 // F6 - Extrudrboard A HOTEND + #define HEATER_1_PIN PinF7 // F7 - Extrudrboard B HOTEND + #define HEATER_2_PIN PinF6 // F6 - Extrudrboard A HOTEND #endif #endif #ifndef FAN_PIN - #define FAN_PIN PinC6 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // @@ -200,27 +200,27 @@ //#define USE_INTERNAL_SD #if HAS_WIRED_LCD - #define LCD_PINS_RS PinE1 // E1 JP11-11 - #define LCD_PINS_ENABLE PinE0 // E0 JP11-10 - #define LCD_PINS_D4 PinD7 // D7 JP11-8 - #define LCD_PINS_D5 PinD6 // D6 JP11-7 - #define LCD_PINS_D6 PinD5 // D5 JP11-6 - #define LCD_PINS_D7 PinD4 // D4 JP11-5 + #define LCD_PINS_RS PinE1 // E1 JP11-11 + #define LCD_PINS_ENABLE PinE0 // E0 JP11-10 + #define LCD_PINS_D4 PinD7 // D7 JP11-8 + #define LCD_PINS_D5 PinD6 // D6 JP11-7 + #define LCD_PINS_D6 PinD5 // D5 JP11-6 + #define LCD_PINS_D7 PinD4 // D4 JP11-5 #if EITHER(VIKI2, miniVIKI) - #define BEEPER_PIN PinE0 // E0 JP11-10 - #define DOGLCD_A0 PinF2 // F2 JP2-2 - #define DOGLCD_CS PinF3 // F3 JP2-4 + #define BEEPER_PIN PinE0 // E0 JP11-10 + #define DOGLCD_A0 PinF2 // F2 JP2-2 + #define DOGLCD_CS PinF3 // F3 JP2-4 - #define BTN_EN1 PinD2 // D2 TX1 JP2-5 - #define BTN_EN2 PinD3 // D3 RX1 JP2-7 - #define BTN_ENC PinF7 // F7 TDI JP2-12 + #define BTN_EN1 PinD2 // D2 TX1 JP2-5 + #define BTN_EN2 PinD3 // D3 RX1 JP2-7 + #define BTN_ENC PinF7 // F7 TDI JP2-12 - #define SDSS PinD3 // F5 TMS JP2-8 + #define SDSS PinD3 // F5 TMS JP2-8 - #define STAT_LED_RED_PIN PinC2 // C2 JP11-14 - #define STAT_LED_BLUE_PIN PinC0 // C0 JP11-12 + #define STAT_LED_RED_PIN PinC2 // C2 JP11-14 + #define STAT_LED_BLUE_PIN PinC0 // C0 JP11-12 #define LCD_SCREEN_ROTATE 180 // 0, 90, 180, 270 @@ -228,33 +228,33 @@ #if DISABLED(USE_INTERNAL_SD) // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define SDSS PinC1 // 36 C1 EXP2-13 EXP2-07 - #define SD_DETECT_PIN PinE1 // 34 E1 EXP2-11 EXP2-04 + #define SDSS PinC1 // 36 C1 EXP2-13 EXP2-07 + #define SD_DETECT_PIN PinE1 // 34 E1 EXP2-11 EXP2-04 #endif // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define DOGLCD_A0 PinD4 // 29 D4 EXP2-05 EXP1-04 - #define DOGLCD_CS PinD5 // 30 D5 EXP2-06 EXP1-05 - #define BTN_ENC PinD6 // 31 D6 EXP2-07 EXP1-09 - #define BEEPER_PIN PinD7 // 32 D7 EXP2-08 EXP1-10 - #define KILL_PIN PinE0 // 33 E0 EXP2-10 EXP2-03 - #define BTN_EN1 PinC0 // 35 C0 EXP2-12 EXP2-06 - #define BTN_EN2 PinC2 // 37 C2 EXP2-14 EXP2-08 - //#define LCD_BACKLIGHT_PIN PinF5 // 56 F5 EXP1-12 Not Implemented - //#define SCK PinB1 // 11 B1 ICSP-04 EXP2-09 - //#define MOSI PinB2 // 12 B2 ICSP-03 EXP2-05 - //#define MISO PinB3 // 13 B3 ICSP-06 EXP2-05 + #define DOGLCD_A0 PinD4 // 29 D4 EXP2-05 EXP1-04 + #define DOGLCD_CS PinD5 // 30 D5 EXP2-06 EXP1-05 + #define BTN_ENC PinD6 // 31 D6 EXP2-07 EXP1-09 + #define BEEPER_PIN PinD7 // 32 D7 EXP2-08 EXP1-10 + #define KILL_PIN PinE0 // 33 E0 EXP2-10 EXP2-03 + #define BTN_EN1 PinC0 // 35 C0 EXP2-12 EXP2-06 + #define BTN_EN2 PinC2 // 37 C2 EXP2-14 EXP2-08 + //#define LCD_BACKLIGHT_PIN PinF5 // 56 F5 EXP1-12 Not Implemented + //#define SCK PinB1 // 11 B1 ICSP-04 EXP2-09 + //#define MOSI PinB2 // 12 B2 ICSP-03 EXP2-05 + //#define MISO PinB3 // 13 B3 ICSP-06 EXP2-05 // Alter timing for graphical display - #define BOARD_ST7920_DELAY_1 313 - #define BOARD_ST7920_DELAY_2 313 - #define BOARD_ST7920_DELAY_3 313 + #define BOARD_ST7920_DELAY_1 313 + #define BOARD_ST7920_DELAY_2 313 + #define BOARD_ST7920_DELAY_3 313 #else - #define BTN_EN1 PinC0 // C0 JP11-12 - #define BTN_EN2 PinC1 // C1 JP11-13 - #define BTN_ENC PinC2 // C2 JP11-14 + #define BTN_EN1 PinC0 // C0 JP11-12 + #define BTN_EN2 PinC1 // C1 JP11-13 + #define BTN_ENC PinC2 // C2 JP11-14 #endif @@ -265,7 +265,7 @@ // // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. #ifndef SDSS - #define SDSS PinB0 // 10 B0 + #define SDSS PinB0 // 10 B0 #endif /** @@ -276,5 +276,5 @@ * which will let you use Channel B on the Extrudrboard as E1. */ #ifndef FILWIDTH_PIN - #define FILWIDTH_PIN PinD2 // Analog Input + #define FILWIDTH_PIN PinD2 // Analog Input #endif diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index 8a4ea7903473..bd8ad2364e1d 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -76,51 +76,51 @@ // // Limit Switches // -#define X_STOP_PIN PinB5 // B5 -#define Y_STOP_PIN PinB6 // B6 -//#define Z_STOP_PIN PinB7 // B7 -#define Z_STOP_PIN PinE4 // E4 For inductive sensor. -//#define E_STOP_PIN PinE4 // E4 +#define X_STOP_PIN PinB5 // B5 +#define Y_STOP_PIN PinB6 // B6 +//#define Z_STOP_PIN PinB7 // B7 +#define Z_STOP_PIN PinE4 // E4 For inductive sensor. +//#define E_STOP_PIN PinE4 // E4 // // Steppers // -#define X_STEP_PIN PinA0 // A0 -#define X_DIR_PIN PinA1 // A1 -#define X_ENABLE_PIN PinE7 // E7 +#define X_STEP_PIN PinA0 // A0 +#define X_DIR_PIN PinA1 // A1 +#define X_ENABLE_PIN PinE7 // E7 -#define Y_STEP_PIN PinA2 // A2 -#define Y_DIR_PIN PinA3 // A3 -#define Y_ENABLE_PIN PinE6 // E6 +#define Y_STEP_PIN PinA2 // A2 +#define Y_DIR_PIN PinA3 // A3 +#define Y_ENABLE_PIN PinE6 // E6 -#define Z_STEP_PIN PinA4 // A4 -#define Z_DIR_PIN PinA5 // A5 -#define Z_ENABLE_PIN PinC7 // C7 +#define Z_STEP_PIN PinA4 // A4 +#define Z_DIR_PIN PinA5 // A5 +#define Z_ENABLE_PIN PinC7 // C7 -#define E0_STEP_PIN PinA6 // A6 -#define E0_DIR_PIN PinA7 // A7 -#define E0_ENABLE_PIN PinC3 // C3 +#define E0_STEP_PIN PinA6 // A6 +#define E0_DIR_PIN PinA7 // A7 +#define E0_ENABLE_PIN PinC3 // C3 // // Temperature Sensors // -#define TEMP_0_PIN PinD7 // F7 Analog Input (Extruder) -#define TEMP_BED_PIN PinD6 // F6 Analog Input (Bed) +#define TEMP_0_PIN PinD7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN PinD6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder -#define HEATER_BED_PIN PinC4 // C4 PWM3C - Bed +#define HEATER_0_PIN PinC5 // C5 PWM3B - Extruder +#define HEATER_BED_PIN PinC4 // C4 PWM3C - Bed #ifndef FAN_PIN - #define FAN_PIN PinC6 // C6 PWM3A + #define FAN_PIN PinC6 // C6 PWM3A #endif // // Misc. Functions // -#define SDSS PinB0 // B0 +#define SDSS PinB0 // B0 // Extension header pin mapping // ---------------------------- @@ -131,11 +131,11 @@ // PWM-D24 A4 (An), IO // 5V GND // 12V GND -#define EXT_AUX_SCL_D0 PinD0 // D0 PWM0B -#define EXT_AUX_SDA_D1 PinD1 // D1 -#define EXT_AUX_RX1_D2 PinD2 // D2 -#define EXT_AUX_TX1_D3 PinD3 // D3 -#define EXT_AUX_PWM_D24 PinB4 // B4 PWM2A +#define EXT_AUX_SCL_D0 PinD0 // D0 PWM0B +#define EXT_AUX_SDA_D1 PinD1 // D1 +#define EXT_AUX_RX1_D2 PinD2 // D2 +#define EXT_AUX_TX1_D3 PinD3 // D3 +#define EXT_AUX_PWM_D24 PinB4 // B4 PWM2A #define EXT_AUX_A0 0 // F0 Analog Input #define EXT_AUX_A0_IO 38 // F0 Digital IO #define EXT_AUX_A1 1 // F1 Analog Input @@ -174,10 +174,10 @@ // // M3/M4/M5 - Spindle/Laser Control // - #define SPINDLE_LASER_PWM_PIN PinB4 // B4 PWM2A - #define SPINDLE_LASER_ENA_PIN PinF1 // F1 Pin should have a pullup! - #define SPINDLE_DIR_PIN PinF2 // F2 + #define SPINDLE_LASER_PWM_PIN PinB4 // B4 PWM2A + #define SPINDLE_LASER_ENA_PIN PinF1 // F1 Pin should have a pullup! + #define SPINDLE_DIR_PIN PinF2 // F2 - #define CASE_LIGHT_PIN PinD0 // D0 PWM0B + #define CASE_LIGHT_PIN PinD0 // D0 PWM0B #endif From dd2f7ec33599f09f81cd3b19e2e01026fe4ca404 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Dec 2022 11:12:34 -0600 Subject: [PATCH 41/83] some formatting --- Marlin/src/HAL/AVR/HAL.cpp | 39 +- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 3769 ++++++++++++------------- 2 files changed, 1845 insertions(+), 1963 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index cbe72abf9262..c0deceb3d002 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -64,10 +64,7 @@ void save_reset_reason() { #include "registers.h" MarlinHAL::MarlinHAL() { -#if ENABLED(HAL_AVR_DIRTY_INIT) - // Clean-wipe the device state. - _ATmega_resetperipherals(); -#endif + TERN_(HAL_AVR_DIRTY_INIT, _ATmega_resetperipherals()); // Clean-wipe the device state. } void MarlinHAL::init() { @@ -88,26 +85,24 @@ void MarlinHAL::init() { init_pwm_timers(); // Init user timers to default frequency - 1000HZ -#if defined(BEEPER_PIN) || ENABLED(ATMEGA_NO_BEEPFIX) - // Make sure no alternative is locked onto the BEEPER. - // This fixes the issue where the ATmega is constantly beeping. - // Might destroy other peripherals using the pin; to circumvent that please undefine one of the above things! - // The true culprit is the AVR ArduinoCore that enables peripherals redundantly. - // (USART1 on the GeeeTech GT2560) - _ATmega_savePinAlternate(BEEPER_PIN); - - OUT_WRITE(BEEPER_PIN, LOW); -#endif + #if defined(BEEPER_PIN) || ENABLED(ATMEGA_NO_BEEPFIX) + // Make sure no alternative is locked onto the BEEPER. + // This fixes the issue where the ATmega is constantly beeping. + // Might destroy other peripherals using the pin; to circumvent that please undefine one of the above things! + // The true culprit is the AVR ArduinoCore that enables peripherals redundantly. + // (USART1 on the GeeeTech GT2560) + _ATmega_savePinAlternate(BEEPER_PIN); - // EXAMPLE: beep loop using proper pin state. -#if defined(BEEPER_PIN) && 0 - while (true) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); - } -#endif + #endif + + // EXAMPLE: beep loop using proper pin state. + #if 0 && defined(BEEPER_PIN) + while (true) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + } + #endif } void MarlinHAL::reboot() { diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 43096a33e03f..8850a84c31d0 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -63,1361 +63,1325 @@ #if DISABLED(SOFTWARE_SPI) + // Hardware SPI + #ifndef LPC_MAINOSCILLATOR_FREQ #error "Missing LPC176X/LPC175X main oscillator frequency (LPC_MAINOSCILLATOR_FREQ)! Consult manufacturer schematics for further details (XTAL1/XTAL2 pins as guidance)" #endif -static void _spi_on_error(const uint32_t code=0) { - for (;;) { - #if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + static void _spi_on_error(const uint32_t code=0) { + for (;;) { + #if ENABLED(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); if (code > 0) delay(500); + for (uint32_t n = 0; n < code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); + delay(250); + OUT_WRITE(BEEPER_PIN, LOW); + if (n < code - 1) delay(250); + } + if (code > 0) delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + #endif + } + } + + static void __attribute__((unused)) _spi_infobeep(uint32_t code) { + #if PIN_EXISTS(BEEPER) OUT_WRITE(BEEPER_PIN, HIGH); delay(500); - OUT_WRITE(BEEPER_PIN, LOW); if (code > 0) delay(500); + OUT_WRITE(BEEPER_PIN, LOW); + if (code > 0) delay(500); for (uint32_t n = 0; n < code; n++) { OUT_WRITE(BEEPER_PIN, HIGH); - delay(250); + delay(200); OUT_WRITE(BEEPER_PIN, LOW); - if (n < code - 1) delay(250); + if (n < code-1) + delay(200); } - if (code > 0) delay(800); - OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(400); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); #endif } -} - -static void __attribute__((unused)) _spi_infobeep(uint32_t code) { -#if PIN_EXISTS(BEEPER) - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - if (code > 0) - delay(500); - for (uint32_t n = 0; n < code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - if (n < code-1) - delay(200); - } - delay(500); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(400); - OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); -#endif -} - -template -inline numberType __MIN(numberType a, numberType b) { - return ( a < b ? a : b ); -} - -namespace MarlinLPC { - -// NXP UM10360 date: 20th of November, 2022 - -// There are pins for each "port" on the LPC1768. Do not be confused with other architectures -// where there is GPIO_0 .. GPIO_n linearly numbered. The naming convention on the LPC1768 is -// very unique. - -struct pinsel0_reg_t { - uint32_t p0_00 : 2; - uint32_t p0_01 : 2; - uint32_t p0_02 : 2; - uint32_t p0_03 : 2; - uint32_t p0_04 : 2; - uint32_t p0_05 : 2; - uint32_t p0_06 : 2; - uint32_t p0_07 : 2; - uint32_t p0_08 : 2; - uint32_t p0_09 : 2; - uint32_t p0_10 : 2; - uint32_t p0_11 : 2; - uint32_t reserved1 : 6; - uint32_t p0_15 : 2; -}; -static_assert(sizeof(pinsel0_reg_t) == 4, "invalid size of LPC pinsel0_reg_t"); - -struct pinsel1_reg_t { - uint32_t p0_16 : 2; - uint32_t p0_17 : 2; - uint32_t p0_18 : 2; - uint32_t p0_19 : 2; - uint32_t p0_20 : 2; - uint32_t p0_21 : 2; - uint32_t p0_22 : 2; - uint32_t p0_23 : 2; - uint32_t p0_24 : 2; - uint32_t p0_25 : 2; - uint32_t p0_26 : 2; - uint32_t p0_27 : 2; - uint32_t p0_28 : 2; - uint32_t p0_29 : 2; - uint32_t p0_30 : 2; - uint32_t reserved1 : 2; -}; -static_assert(sizeof(pinsel1_reg_t) == 4, "invalid size of LPC pinsel1_reg_t"); - -struct pinsel2_reg_t { - uint32_t p1_00 : 2; - uint32_t p1_01 : 2; - uint32_t reserved1 : 4; - uint32_t p1_04 : 2; - uint32_t reserved2 : 6; - uint32_t p1_08 : 2; - uint32_t p1_09 : 2; - uint32_t p1_10 : 2; - uint32_t reserved3 : 6; - uint32_t p1_14 : 2; - uint32_t p1_15 : 2; -}; -static_assert(sizeof(pinsel2_reg_t) == 4, "invalid size of LPC pinsel2_reg_t"); - -struct pinsel3_reg_t { - uint32_t p1_16 : 2; - uint32_t p1_17 : 2; - uint32_t p1_18 : 2; - uint32_t p1_19 : 2; - uint32_t p1_20 : 2; - uint32_t p1_21 : 2; - uint32_t p1_22 : 2; - uint32_t p1_23 : 2; - uint32_t p1_24 : 2; - uint32_t p1_25 : 2; - uint32_t p1_26 : 2; - uint32_t p1_27 : 2; - uint32_t p1_28 : 2; - uint32_t p1_29 : 2; - uint32_t p1_30 : 2; - uint32_t p1_31 : 2; -}; -static_assert(sizeof(pinsel3_reg_t) == 4, "invalid size of LPC pinsel3_reg_t"); - -struct pinsel4_reg_t { - uint32_t p2_00 : 2; - uint32_t p2_01 : 2; - uint32_t p2_02 : 2; - uint32_t p2_03 : 2; - uint32_t p2_04 : 2; - uint32_t p2_05 : 2; - uint32_t p2_06 : 2; - uint32_t p2_07 : 2; - uint32_t p2_08 : 2; - uint32_t p2_09 : 2; - uint32_t p2_10 : 2; - uint32_t p2_11 : 2; - uint32_t p2_12 : 2; - uint32_t p2_13 : 2; - uint32_t p2_14 : 2; - uint32_t p2_15 : 2; -}; -static_assert(sizeof(pinsel4_reg_t) == 4, "invalid size of LPC pinsel4_reg_t"); - -struct pinsel7_reg_t { - uint32_t reserved1 : 18; - uint32_t p3_25 : 2; - uint32_t p3_26 : 2; - uint32_t reserved2 : 10; -}; -static_assert(sizeof(pinsel7_reg_t) == 4, "invalid size of LPC pinsel7_reg_t"); - -struct pinsel9_reg_t { - uint32_t reserved1 : 24; - uint32_t p4_28 : 2; - uint32_t p4_29 : 2; - uint32_t reserved2 : 4; -}; -static_assert(sizeof(pinsel9_reg_t) == 4, "invalid size of LPC pinsel9_reg_t"); - -struct pinsel10_reg_t { - uint32_t reserved1 : 2; - uint32_t gpio_trace : 1; - uint32_t reserved2 : 29; -}; -static_assert(sizeof(pinsel10_reg_t) == 4, "invalid size of LPC pinsel10_reg_t"); - -#define LPC_PINMODE_PULLUP 0 -#define LPC_PINMODE_REPEATER 1 -#define LPC_PINMODE_NONE 2 -#define LPC_PINMODE_PULLDOWN 3 - -struct pinmode0_reg_t { - uint32_t p0_00mode : 2; - uint32_t p0_01mode : 2; - uint32_t p0_02mode : 2; - uint32_t p0_03mode : 2; - uint32_t p0_04mode : 2; - uint32_t p0_05mode : 2; - uint32_t p0_06mode : 2; - uint32_t p0_07mode : 2; - uint32_t p0_08mode : 2; - uint32_t p0_09mode : 2; - uint32_t p0_10mode : 2; - uint32_t p0_11mode : 2; - uint32_t reserved1 : 6; - uint32_t p0_15mode : 2; -}; -static_assert(sizeof(pinmode0_reg_t) == 4, "invalid size of LPC pinmode0_reg_t"); - -struct pinmode1_reg_t { - uint32_t p0_16mode : 2; - uint32_t p0_17mode : 2; - uint32_t p0_18mode : 2; - uint32_t p0_19mode : 2; - uint32_t p0_20mode : 2; - uint32_t p0_21mode : 2; - uint32_t p0_22mode : 2; - uint32_t p0_23mode : 2; - uint32_t p0_24mode : 2; - uint32_t p0_25mode : 2; - uint32_t p0_26mode : 2; - uint32_t reserved1 : 10; -}; -static_assert(sizeof(pinmode1_reg_t) == 4, "invalid size of pinmode1_reg_t"); - -struct pinmode2_reg_t { - uint32_t p1_00mode : 2; - uint32_t p1_01mode : 2; - uint32_t reserved1 : 4; - uint32_t p1_04mode : 2; - uint32_t reserved2 : 6; - uint32_t p1_08mode : 2; - uint32_t p1_09mode : 2; - uint32_t p1_10mode : 2; - uint32_t reserved3 : 6; - uint32_t p1_14mode : 2; - uint32_t p1_15mode : 2; -}; -static_assert(sizeof(pinmode2_reg_t) == 4, "invalid size of pinmode2_reg_t"); - -struct pinmode3_reg_t { - uint32_t p1_16mode : 2; - uint32_t p1_17mode : 2; - uint32_t p1_18mode : 2; - uint32_t p1_19mode : 2; - uint32_t p1_20mode : 2; - uint32_t p1_21mode : 2; - uint32_t p1_22mode : 2; - uint32_t p1_23mode : 2; - uint32_t p1_24mode : 2; - uint32_t p1_25mode : 2; - uint32_t p1_26mode : 2; - uint32_t p1_27mode : 2; - uint32_t p1_28mode : 2; - uint32_t p1_29mode : 2; - uint32_t p1_30mode : 2; - uint32_t p1_31mode : 2; -}; -static_assert(sizeof(pinmode3_reg_t) == 4, "invalid size of pinmode3_reg_t"); - -struct pinmode4_reg_t { - uint32_t p2_00mode : 2; - uint32_t p2_01mode : 2; - uint32_t p2_02mode : 2; - uint32_t p2_03mode : 2; - uint32_t p2_04mode : 2; - uint32_t p2_05mode : 2; - uint32_t p2_06mode : 2; - uint32_t p2_07mode : 2; - uint32_t p2_08mode : 2; - uint32_t p2_09mode : 2; - uint32_t p2_10mode : 2; - uint32_t p2_11mode : 2; - uint32_t p2_12mode : 2; - uint32_t p2_13mode : 2; - uint32_t reserved1 : 4; -}; -static_assert(sizeof(pinmode4_reg_t) == 4, "invalid size of pinmode4_reg_t"); - -struct pinmode7_reg_t { - uint32_t reserved1 : 18; - uint32_t p3_25mode : 2; - uint32_t p3_26mode : 2; - uint32_t reserved2 : 10; -}; -static_assert(sizeof(pinmode7_reg_t) == 4, "invalid size of pinmode7_reg_t"); - -struct pinmode9_reg_t { - uint32_t reserved1 : 24; - uint32_t p4_28mode : 2; - uint32_t p4_29mode : 2; - uint32_t reserved2 : 4; -}; -static_assert(sizeof(pinmode9_reg_t) == 4, "invalid size of pinmode9_reg_t"); - -static pinsel0_reg_t& PINSEL0 = *(pinsel0_reg_t*)0x4002C000; -static pinsel1_reg_t& PINSEL1 = *(pinsel1_reg_t*)0x4002C004; -static pinsel2_reg_t& PINSEL2 = *(pinsel2_reg_t*)0x4002C008; -static pinsel3_reg_t& PINSEL3 = *(pinsel3_reg_t*)0x4002C00C; -static pinsel4_reg_t& PINSEL4 = *(pinsel4_reg_t*)0x4002C010; -static pinsel7_reg_t& PINSEL7 = *(pinsel7_reg_t*)0x4002C01C; -//static pinsel8_reg_t& PINSEL8 = *(pinsel8_reg_t*)0x4002C020; -static pinsel9_reg_t& PINSEL9 = *(pinsel9_reg_t*)0x4002C024; -static pinsel10_reg_t& PINSEL10 = *(pinsel10_reg_t*)0x4002C028; - -static pinmode0_reg_t& PINMODE0 = *(pinmode0_reg_t*)0x4002C040; -static pinmode1_reg_t& PINMODE1 = *(pinmode1_reg_t*)0x4002C044; -static pinmode2_reg_t& PINMODE2 = *(pinmode2_reg_t*)0x4002C048; -static pinmode3_reg_t& PINMODE3 = *(pinmode3_reg_t*)0x4002C04C; -static pinmode4_reg_t& PINMODE4 = *(pinmode4_reg_t*)0x4002C050; -//static pinmode5_reg_t& PINMODE5 = *(pinmode5_reg_t*)0x4002C054; -//static pinmode6_reg_t& PINMODE6 = *(pinmode6_reg_t*)0x4002C058; -static pinmode7_reg_t& PINMODE7 = *(pinmode7_reg_t*)0x4002C05C; -static pinmode9_reg_t& PINMODE9 = *(pinmode9_reg_t*)0x4002C064; - -// Left out OD and I2C-specific. -// UM10360 page 103: I am only taking the pin descriptions for LPC176x -// but support could (easily) be enabled for LPC175x aswell, if the community demands it. - -#if 0 - -#define LPC_GPIODIR_INPUT 0 -#define LPC_GPIODIR_OUTPUT 1 - -struct fioXdir_reg_t { - uint32_t val; - - inline void set(uint8_t reg, uint8_t val) { - if (val == LPC_GPIODIR_INPUT) - val &= ~(1<> reg ); - } -}; + template + inline numberType __MIN(numberType a, numberType b) { + return ( a < b ? a : b ); + } + + namespace MarlinLPC { + + // NXP UM10360 date: 20th of November, 2022 + + // There are pins for each "port" on the LPC1768. Do not be confused with other architectures + // where there is GPIO_0 .. GPIO_n linearly numbered. The naming convention on the LPC1768 is + // very unique. + + struct pinsel0_reg_t { + uint32_t p0_00 : 2; + uint32_t p0_01 : 2; + uint32_t p0_02 : 2; + uint32_t p0_03 : 2; + uint32_t p0_04 : 2; + uint32_t p0_05 : 2; + uint32_t p0_06 : 2; + uint32_t p0_07 : 2; + uint32_t p0_08 : 2; + uint32_t p0_09 : 2; + uint32_t p0_10 : 2; + uint32_t p0_11 : 2; + uint32_t reserved1 : 6; + uint32_t p0_15 : 2; + }; + static_assert(sizeof(pinsel0_reg_t) == 4, "invalid size of LPC pinsel0_reg_t"); + + struct pinsel1_reg_t { + uint32_t p0_16 : 2; + uint32_t p0_17 : 2; + uint32_t p0_18 : 2; + uint32_t p0_19 : 2; + uint32_t p0_20 : 2; + uint32_t p0_21 : 2; + uint32_t p0_22 : 2; + uint32_t p0_23 : 2; + uint32_t p0_24 : 2; + uint32_t p0_25 : 2; + uint32_t p0_26 : 2; + uint32_t p0_27 : 2; + uint32_t p0_28 : 2; + uint32_t p0_29 : 2; + uint32_t p0_30 : 2; + uint32_t reserved1 : 2; + }; + static_assert(sizeof(pinsel1_reg_t) == 4, "invalid size of LPC pinsel1_reg_t"); + + struct pinsel2_reg_t { + uint32_t p1_00 : 2; + uint32_t p1_01 : 2; + uint32_t reserved1 : 4; + uint32_t p1_04 : 2; + uint32_t reserved2 : 6; + uint32_t p1_08 : 2; + uint32_t p1_09 : 2; + uint32_t p1_10 : 2; + uint32_t reserved3 : 6; + uint32_t p1_14 : 2; + uint32_t p1_15 : 2; + }; + static_assert(sizeof(pinsel2_reg_t) == 4, "invalid size of LPC pinsel2_reg_t"); + + struct pinsel3_reg_t { + uint32_t p1_16 : 2; + uint32_t p1_17 : 2; + uint32_t p1_18 : 2; + uint32_t p1_19 : 2; + uint32_t p1_20 : 2; + uint32_t p1_21 : 2; + uint32_t p1_22 : 2; + uint32_t p1_23 : 2; + uint32_t p1_24 : 2; + uint32_t p1_25 : 2; + uint32_t p1_26 : 2; + uint32_t p1_27 : 2; + uint32_t p1_28 : 2; + uint32_t p1_29 : 2; + uint32_t p1_30 : 2; + uint32_t p1_31 : 2; + }; + static_assert(sizeof(pinsel3_reg_t) == 4, "invalid size of LPC pinsel3_reg_t"); + + struct pinsel4_reg_t { + uint32_t p2_00 : 2; + uint32_t p2_01 : 2; + uint32_t p2_02 : 2; + uint32_t p2_03 : 2; + uint32_t p2_04 : 2; + uint32_t p2_05 : 2; + uint32_t p2_06 : 2; + uint32_t p2_07 : 2; + uint32_t p2_08 : 2; + uint32_t p2_09 : 2; + uint32_t p2_10 : 2; + uint32_t p2_11 : 2; + uint32_t p2_12 : 2; + uint32_t p2_13 : 2; + uint32_t p2_14 : 2; + uint32_t p2_15 : 2; + }; + static_assert(sizeof(pinsel4_reg_t) == 4, "invalid size of LPC pinsel4_reg_t"); + + struct pinsel7_reg_t { + uint32_t reserved1 : 18; + uint32_t p3_25 : 2; + uint32_t p3_26 : 2; + uint32_t reserved2 : 10; + }; + static_assert(sizeof(pinsel7_reg_t) == 4, "invalid size of LPC pinsel7_reg_t"); + + struct pinsel9_reg_t { + uint32_t reserved1 : 24; + uint32_t p4_28 : 2; + uint32_t p4_29 : 2; + uint32_t reserved2 : 4; + }; + static_assert(sizeof(pinsel9_reg_t) == 4, "invalid size of LPC pinsel9_reg_t"); + + struct pinsel10_reg_t { + uint32_t reserved1 : 2; + uint32_t gpio_trace : 1; + uint32_t reserved2 : 29; + }; + static_assert(sizeof(pinsel10_reg_t) == 4, "invalid size of LPC pinsel10_reg_t"); + + #define LPC_PINMODE_PULLUP 0 + #define LPC_PINMODE_REPEATER 1 + #define LPC_PINMODE_NONE 2 + #define LPC_PINMODE_PULLDOWN 3 + + struct pinmode0_reg_t { + uint32_t p0_00mode : 2; + uint32_t p0_01mode : 2; + uint32_t p0_02mode : 2; + uint32_t p0_03mode : 2; + uint32_t p0_04mode : 2; + uint32_t p0_05mode : 2; + uint32_t p0_06mode : 2; + uint32_t p0_07mode : 2; + uint32_t p0_08mode : 2; + uint32_t p0_09mode : 2; + uint32_t p0_10mode : 2; + uint32_t p0_11mode : 2; + uint32_t reserved1 : 6; + uint32_t p0_15mode : 2; + }; + static_assert(sizeof(pinmode0_reg_t) == 4, "invalid size of LPC pinmode0_reg_t"); + + struct pinmode1_reg_t { + uint32_t p0_16mode : 2; + uint32_t p0_17mode : 2; + uint32_t p0_18mode : 2; + uint32_t p0_19mode : 2; + uint32_t p0_20mode : 2; + uint32_t p0_21mode : 2; + uint32_t p0_22mode : 2; + uint32_t p0_23mode : 2; + uint32_t p0_24mode : 2; + uint32_t p0_25mode : 2; + uint32_t p0_26mode : 2; + uint32_t reserved1 : 10; + }; + static_assert(sizeof(pinmode1_reg_t) == 4, "invalid size of pinmode1_reg_t"); + + struct pinmode2_reg_t { + uint32_t p1_00mode : 2; + uint32_t p1_01mode : 2; + uint32_t reserved1 : 4; + uint32_t p1_04mode : 2; + uint32_t reserved2 : 6; + uint32_t p1_08mode : 2; + uint32_t p1_09mode : 2; + uint32_t p1_10mode : 2; + uint32_t reserved3 : 6; + uint32_t p1_14mode : 2; + uint32_t p1_15mode : 2; + }; + static_assert(sizeof(pinmode2_reg_t) == 4, "invalid size of pinmode2_reg_t"); + + struct pinmode3_reg_t { + uint32_t p1_16mode : 2; + uint32_t p1_17mode : 2; + uint32_t p1_18mode : 2; + uint32_t p1_19mode : 2; + uint32_t p1_20mode : 2; + uint32_t p1_21mode : 2; + uint32_t p1_22mode : 2; + uint32_t p1_23mode : 2; + uint32_t p1_24mode : 2; + uint32_t p1_25mode : 2; + uint32_t p1_26mode : 2; + uint32_t p1_27mode : 2; + uint32_t p1_28mode : 2; + uint32_t p1_29mode : 2; + uint32_t p1_30mode : 2; + uint32_t p1_31mode : 2; + }; + static_assert(sizeof(pinmode3_reg_t) == 4, "invalid size of pinmode3_reg_t"); + + struct pinmode4_reg_t { + uint32_t p2_00mode : 2; + uint32_t p2_01mode : 2; + uint32_t p2_02mode : 2; + uint32_t p2_03mode : 2; + uint32_t p2_04mode : 2; + uint32_t p2_05mode : 2; + uint32_t p2_06mode : 2; + uint32_t p2_07mode : 2; + uint32_t p2_08mode : 2; + uint32_t p2_09mode : 2; + uint32_t p2_10mode : 2; + uint32_t p2_11mode : 2; + uint32_t p2_12mode : 2; + uint32_t p2_13mode : 2; + uint32_t reserved1 : 4; + }; + static_assert(sizeof(pinmode4_reg_t) == 4, "invalid size of pinmode4_reg_t"); + + struct pinmode7_reg_t { + uint32_t reserved1 : 18; + uint32_t p3_25mode : 2; + uint32_t p3_26mode : 2; + uint32_t reserved2 : 10; + }; + static_assert(sizeof(pinmode7_reg_t) == 4, "invalid size of pinmode7_reg_t"); + + struct pinmode9_reg_t { + uint32_t reserved1 : 24; + uint32_t p4_28mode : 2; + uint32_t p4_29mode : 2; + uint32_t reserved2 : 4; + }; + static_assert(sizeof(pinmode9_reg_t) == 4, "invalid size of pinmode9_reg_t"); + + static pinsel0_reg_t &PINSEL0 = *(pinsel0_reg_t*)0x4002C000; + static pinsel1_reg_t &PINSEL1 = *(pinsel1_reg_t*)0x4002C004; + static pinsel2_reg_t &PINSEL2 = *(pinsel2_reg_t*)0x4002C008; + static pinsel3_reg_t &PINSEL3 = *(pinsel3_reg_t*)0x4002C00C; + static pinsel4_reg_t &PINSEL4 = *(pinsel4_reg_t*)0x4002C010; + static pinsel7_reg_t &PINSEL7 = *(pinsel7_reg_t*)0x4002C01C; + //static pinsel8_reg_t &PINSEL8 = *(pinsel8_reg_t*)0x4002C020; + static pinsel9_reg_t &PINSEL9 = *(pinsel9_reg_t*)0x4002C024; + static pinsel10_reg_t &PINSEL10 = *(pinsel10_reg_t*)0x4002C028; + + static pinmode0_reg_t &PINMODE0 = *(pinmode0_reg_t*)0x4002C040; + static pinmode1_reg_t &PINMODE1 = *(pinmode1_reg_t*)0x4002C044; + static pinmode2_reg_t &PINMODE2 = *(pinmode2_reg_t*)0x4002C048; + static pinmode3_reg_t &PINMODE3 = *(pinmode3_reg_t*)0x4002C04C; + static pinmode4_reg_t &PINMODE4 = *(pinmode4_reg_t*)0x4002C050; + //static pinmode5_reg_t &PINMODE5 = *(pinmode5_reg_t*)0x4002C054; + //static pinmode6_reg_t &PINMODE6 = *(pinmode6_reg_t*)0x4002C058; + static pinmode7_reg_t &PINMODE7 = *(pinmode7_reg_t*)0x4002C05C; + static pinmode9_reg_t &PINMODE9 = *(pinmode9_reg_t*)0x4002C064; + + // Left out OD and I2C-specific. + // UM10360 page 103: I am only taking the pin descriptions for LPC176x + // but support could (easily) be enabled for LPC175x aswell, if the community demands it. + + #if 0 + + #define LPC_GPIODIR_INPUT 0 + #define LPC_GPIODIR_OUTPUT 1 + + struct fioXdir_reg_t { + uint32_t val; + + inline void set(uint8_t reg, uint8_t val) { + if (val == LPC_GPIODIR_INPUT) + val &= ~(1<> reg ); - } -}; - -static fioXdir_reg_t& FIO0DIR = *(fioXdir_reg_t*)0x2009C000; -static fioXdir_reg_t& FIO1DIR = *(fioXdir_reg_t*)0x2009C020; -static fioXdir_reg_t& FIO2DIR = *(fioXdir_reg_t*)0x2009C040; -static fioXdir_reg_t& FIO3DIR = *(fioXdir_reg_t*)0x2009C060; -static fioXdir_reg_t& FIO4DIR = *(fioXdir_reg_t*)0x2009C080; - -static fioXmask_reg_t& FIO0MASK = *(fioXmask_reg_t*)0x2009C010; -static fioXmask_reg_t& FIO1MASK = *(fioXmask_reg_t*)0x2009C030; -static fioXmask_reg_t& FIO2MASK = *(fioXmask_reg_t*)0x2009C050; -static fioXmask_reg_t& FIO3MASK = *(fioXmask_reg_t*)0x2009C070; -static fioXmask_reg_t& FIO4MASK = *(fioXmask_reg_t*)0x2009C090; - -static fioXpin_reg_t& FIO0PIN = *(fioXpin_reg_t*)0x2009C014; -static fioXpin_reg_t& FIO1PIN = *(fioXpin_reg_t*)0x2009C034; -static fioXpin_reg_t& FIO2PIN = *(fioXpin_reg_t*)0x2009C054; -static fioXpin_reg_t& FIO3PIN = *(fioXpin_reg_t*)0x2009C074; -static fioXpin_reg_t& FIO4PIN = *(fioXpin_reg_t*)0x2009C094; - -#endif - -// Find a valid port-mapping for the given GPIO to a SPI bus peripheral. -// If it fails then a recommended SPI bus with a recommended set of GPIO -// pins should be used. -// The LPC1768 is a really good architecture, even though in comparison -// to the ESP32 it does not support mapping any peripheral signal to any -// GPIO pin. -struct portMapResult_t { - inline portMapResult_t() { - func = 0xFF; - } - inline bool isMapped() const { - return ( func != 0xFF ); - } - uint8_t func; -}; - -static bool SPIFindPortMapping( - int gpio_sck, int gpio_miso, int gpio_mosi, int gpio_cs, - uint8_t& sspBusOut, portMapResult_t& map_sck_out, portMapResult_t& map_miso_out, portMapResult_t& map_mosi_out, portMapResult_t& map_cs_out -) -{ - portMapResult_t map_sck, map_miso, map_mosi, map_cs; - bool found = false; - - if ((gpio_sck == P0_15 || gpio_sck == P1_20) || (gpio_miso == P0_17 || gpio_miso == P1_23) || (gpio_mosi == P0_18 || gpio_mosi == P1_24) || (gpio_cs == P0_16 || gpio_cs == P1_21)) { - sspBusOut = 0; - if (gpio_sck == P0_15) { - map_sck.func = 2; - } - else if (gpio_sck == P1_20) { - map_sck.func = 3; - } - if (gpio_miso == P0_17) { - map_miso.func = 2; - } - else if (gpio_miso == P1_23) { - map_miso.func = 3; - } - if (gpio_mosi == P0_18) { - map_mosi.func = 2; - } - else if (gpio_mosi == P1_24) { - map_mosi.func = 3; - } - if (gpio_cs == P0_16) { - map_cs.func = 2; - } - else if (gpio_cs == P1_21) { - map_cs.func = 3; - } - found = true; - } - else if ((gpio_sck == P0_07 || gpio_sck == P1_31) || gpio_miso == P0_08 || gpio_mosi == P0_09 || gpio_cs == P0_06) { - sspBusOut = 1; - if (gpio_sck == P0_07) { - map_sck.func = 2; - } - else if (gpio_sck == P1_31) { - map_sck.func = 2; - } - if (gpio_miso == P0_08) { - map_miso.func = 2; - } - if (gpio_mosi == P0_09) { - map_mosi.func = 2; - } - if (gpio_cs == P0_06) { - map_cs.func = 2; - } - found = true; - } - if (found) { - map_sck_out = map_sck; - map_miso_out = map_miso; - map_mosi_out = map_mosi; - map_cs_out = map_cs; - } - return found; -} - -struct gpioMapResult_t { - uint8_t sspBusIdx; - int gpio_sck; - int gpio_miso; - int gpio_mosi; - int gpio_cs; -}; - -static void MapPortPinFunc(int pin, uint8_t func) { -#define _SWENT_MPPF(PS,PT,PN) case P##PT##_##PN: PINSEL##PS.p##PT##_##PN = func; break; - switch(pin) { - _SWENT_MPPF(0,0,00)_SWENT_MPPF(0,0,01)_SWENT_MPPF(0,0,02)_SWENT_MPPF(0,0,03)_SWENT_MPPF(0,0,04)_SWENT_MPPF(0,0,05)_SWENT_MPPF(0,0,06)_SWENT_MPPF(0,0,07) - _SWENT_MPPF(0,0,08)_SWENT_MPPF(0,0,09)_SWENT_MPPF(0,0,10)_SWENT_MPPF(0,0,11)_SWENT_MPPF(0,0,15) - _SWENT_MPPF(1,0,16)_SWENT_MPPF(1,0,17)_SWENT_MPPF(1,0,18)_SWENT_MPPF(1,0,19)_SWENT_MPPF(1,0,20) - _SWENT_MPPF(1,0,21)_SWENT_MPPF(1,0,22)_SWENT_MPPF(1,0,23)_SWENT_MPPF(1,0,24)_SWENT_MPPF(1,0,25) - _SWENT_MPPF(1,0,26)_SWENT_MPPF(1,0,27)_SWENT_MPPF(1,0,28)_SWENT_MPPF(1,0,29)_SWENT_MPPF(1,0,30) - _SWENT_MPPF(2,1,00)_SWENT_MPPF(2,1,01)_SWENT_MPPF(2,1,04)_SWENT_MPPF(2,1,08)_SWENT_MPPF(2,1,09)_SWENT_MPPF(2,1,10) - _SWENT_MPPF(2,1,14)_SWENT_MPPF(2,1,15) - _SWENT_MPPF(3,1,16)_SWENT_MPPF(3,1,17)_SWENT_MPPF(3,1,18)_SWENT_MPPF(3,1,19)_SWENT_MPPF(3,1,20) - _SWENT_MPPF(3,1,21)_SWENT_MPPF(3,1,22)_SWENT_MPPF(3,1,23)_SWENT_MPPF(3,1,24)_SWENT_MPPF(3,1,25) - _SWENT_MPPF(3,1,26)_SWENT_MPPF(3,1,27)_SWENT_MPPF(3,1,28)_SWENT_MPPF(3,1,29)_SWENT_MPPF(3,1,30) - _SWENT_MPPF(3,1,31) - _SWENT_MPPF(4,2,00)_SWENT_MPPF(4,2,01)_SWENT_MPPF(4,2,02)_SWENT_MPPF(4,2,03)_SWENT_MPPF(4,2,04) - _SWENT_MPPF(4,2,05)_SWENT_MPPF(4,2,06)_SWENT_MPPF(4,2,07)_SWENT_MPPF(4,2,08)_SWENT_MPPF(4,2,09) - _SWENT_MPPF(4,2,10)_SWENT_MPPF(4,2,11)_SWENT_MPPF(4,2,12)_SWENT_MPPF(4,2,13) - _SWENT_MPPF(7,3,25)_SWENT_MPPF(7,3,26) - _SWENT_MPPF(9,4,28)_SWENT_MPPF(9,4,29) - } -#undef _SWENT_MPPF -} - -static void SetPortPinMode(int pin, uint8_t mode) { -#define _SWENT_MPPM(PM,PT,PN) case P##PT##_##PN: PINMODE##PM.p##PT##_##PN##mode = mode; break; - switch(pin) { - _SWENT_MPPM(0,0,00)_SWENT_MPPM(0,0,01)_SWENT_MPPM(0,0,02)_SWENT_MPPM(0,0,03)_SWENT_MPPM(0,0,04)_SWENT_MPPM(0,0,05) - _SWENT_MPPM(0,0,06)_SWENT_MPPM(0,0,07)_SWENT_MPPM(0,0,08)_SWENT_MPPM(0,0,09)_SWENT_MPPM(0,0,10)_SWENT_MPPM(0,0,11) - _SWENT_MPPM(0,0,15) - _SWENT_MPPM(1,0,16)_SWENT_MPPM(1,0,17)_SWENT_MPPM(1,0,18)_SWENT_MPPM(1,0,19)_SWENT_MPPM(1,0,20)_SWENT_MPPM(1,0,21) - _SWENT_MPPM(1,0,22)_SWENT_MPPM(1,0,23)_SWENT_MPPM(1,0,24)_SWENT_MPPM(1,0,25)_SWENT_MPPM(1,0,26) - _SWENT_MPPM(2,1,00)_SWENT_MPPM(2,1,01)_SWENT_MPPM(2,1,04)_SWENT_MPPM(2,1,08)_SWENT_MPPM(2,1,09)_SWENT_MPPM(2,1,10) - _SWENT_MPPM(2,1,14)_SWENT_MPPM(2,1,15) - _SWENT_MPPM(3,1,16)_SWENT_MPPM(3,1,17)_SWENT_MPPM(3,1,18)_SWENT_MPPM(3,1,19)_SWENT_MPPM(3,1,20)_SWENT_MPPM(3,1,21) - _SWENT_MPPM(3,1,22)_SWENT_MPPM(3,1,23)_SWENT_MPPM(3,1,24)_SWENT_MPPM(3,1,25)_SWENT_MPPM(3,1,26)_SWENT_MPPM(3,1,27) - _SWENT_MPPM(3,1,28)_SWENT_MPPM(3,1,29)_SWENT_MPPM(3,1,30)_SWENT_MPPM(3,1,31) - _SWENT_MPPM(4,2,00)_SWENT_MPPM(4,2,01)_SWENT_MPPM(4,2,02)_SWENT_MPPM(4,2,03)_SWENT_MPPM(4,2,04)_SWENT_MPPM(4,2,05) - _SWENT_MPPM(4,2,06)_SWENT_MPPM(4,2,07)_SWENT_MPPM(4,2,08)_SWENT_MPPM(4,2,09)_SWENT_MPPM(4,2,10)_SWENT_MPPM(4,2,11) - _SWENT_MPPM(4,2,12)_SWENT_MPPM(4,2,13) - _SWENT_MPPM(7,3,25)_SWENT_MPPM(7,3,26) - _SWENT_MPPM(9,4,28)_SWENT_MPPM(9,4,29) - } -#undef _SWENT_MPPM -} - -#if 0 -static void SetPortPinDirection(int pin, uint8_t dir) { -#define _SWENT_SPPD_(PT,PNN,PN) case P##PT##_##PNN: FIO##PT##DIR.set(PN, dir); break; -#define _SWENT_SPPD(PT,PN) case P##PT##_##PN: FIO##PT##DIR.set(PN, dir); break; - switch(pin) { - _SWENT_SPPD_(0,00,0)_SWENT_SPPD_(0,01,1)_SWENT_SPPD_(0,02,2)_SWENT_SPPD_(0,03,3)_SWENT_SPPD_(0,04,4)_SWENT_SPPD_(0,05,5)_SWENT_SPPD_(0,06,6) - _SWENT_SPPD_(0,07,7)_SWENT_SPPD_(0,08,8)_SWENT_SPPD_(0,09,9)_SWENT_SPPD(0,10)_SWENT_SPPD(0,11)_SWENT_SPPD(0,15)_SWENT_SPPD(0,16) - _SWENT_SPPD(0,17)_SWENT_SPPD(0,18)_SWENT_SPPD(0,19)_SWENT_SPPD(0,20)_SWENT_SPPD(0,21)_SWENT_SPPD(0,22)_SWENT_SPPD(0,23) - _SWENT_SPPD(0,24)_SWENT_SPPD(0,25)_SWENT_SPPD(0,26)_SWENT_SPPD(0,27)_SWENT_SPPD(0,28)_SWENT_SPPD(0,29)_SWENT_SPPD(0,30) - _SWENT_SPPD_(1,00,0)_SWENT_SPPD_(1,01,1)_SWENT_SPPD_(1,04,4)_SWENT_SPPD_(1,08,8)_SWENT_SPPD_(1,09,9)_SWENT_SPPD(1,10)_SWENT_SPPD(1,14) - _SWENT_SPPD(1,15)_SWENT_SPPD(1,16)_SWENT_SPPD(1,17)_SWENT_SPPD(1,18)_SWENT_SPPD(1,19)_SWENT_SPPD(1,20)_SWENT_SPPD(1,21) - _SWENT_SPPD(1,22)_SWENT_SPPD(1,23)_SWENT_SPPD(1,24)_SWENT_SPPD(1,25)_SWENT_SPPD(1,26)_SWENT_SPPD(1,27)_SWENT_SPPD(1,28) - _SWENT_SPPD(1,29)_SWENT_SPPD(1,30)_SWENT_SPPD(1,31) - _SWENT_SPPD_(2,00,0)_SWENT_SPPD_(2,01,1)_SWENT_SPPD_(2,02,2)_SWENT_SPPD_(2,03,3)_SWENT_SPPD_(2,04,4)_SWENT_SPPD_(2,05,5)_SWENT_SPPD_(2,06,6)_SWENT_SPPD_(2,07,7) - _SWENT_SPPD_(2,08,8)_SWENT_SPPD_(2,09,9)_SWENT_SPPD(2,10)_SWENT_SPPD(2,11)_SWENT_SPPD(2,12)_SWENT_SPPD(2,13) - _SWENT_SPPD(3,25)_SWENT_SPPD(3,26) - _SWENT_SPPD(4,28)_SWENT_SPPD(4,29) - } -#undef _SWENT_SPPD -#undef _SWENT_SPPD_ -} -#endif - -static gpioMapResult_t SPIMapGPIO(int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { - // First try to find a direct mapping to SSP peripheral based on the given pin hints. - uint8_t sspBusIdx; - portMapResult_t map_sck, map_miso, map_mosi, map_cs; - - bool foundPortMap = SPIFindPortMapping(hint_sck, hint_miso, hint_mosi, hint_cs, sspBusIdx, map_sck, map_miso, map_mosi, map_cs); - - if (foundPortMap == false) { - // Just select the default SSP config. - sspBusIdx = 0; - hint_sck = P0_15; - map_sck.func = 2; - hint_miso = P0_17; - map_miso.func = 2; - hint_mosi = P0_18; - map_mosi.func = 2; - hint_cs = P0_16; - map_cs.func = 2; - } + inline void set(uint8_t reg, bool enable) { + if (enable) + val |= (1<> reg ); + } + }; - // Map the functions that exist. - if (map_sck.isMapped()) { - MapPortPinFunc(hint_sck, map_sck.func); - SetPortPinMode(hint_sck, LPC_PINMODE_NONE); - } - if (map_miso.isMapped()) { - MapPortPinFunc(hint_miso, map_miso.func); - SetPortPinMode(hint_miso, LPC_PINMODE_PULLDOWN); - } - if (map_mosi.isMapped()) { - MapPortPinFunc(hint_mosi, map_mosi.func); - SetPortPinMode(hint_mosi, LPC_PINMODE_NONE); - } -#if 0 - if (map_cs.isMapped()) { - MapPortPinFunc(hint_cs, map_cs.func); - SetPortPinMode(hint_cs, LPC_PINMODE_NONE); - } -#endif - - gpioMapResult_t res; - res.sspBusIdx = sspBusIdx; - res.gpio_sck = ( map_sck.isMapped() ? hint_sck : -1 ); - res.gpio_miso = ( map_miso.isMapped() ? hint_miso : -1 ); - res.gpio_mosi = ( map_mosi.isMapped() ? hint_mosi : -1 ); - res.gpio_cs = ( map_cs.isMapped() ? hint_cs : -1 ); - return res; -} - -static void SPIUnmapGPIO(const gpioMapResult_t& res) { - // Reset to architecture default configs on the pins that we previously mapped. - if (res.gpio_sck >= 0) { - MapPortPinFunc(res.gpio_sck, 0); - SetPortPinMode(res.gpio_sck, LPC_PINMODE_PULLDOWN); - } - if (res.gpio_miso >= 0) { - MapPortPinFunc(res.gpio_miso, 0); - SetPortPinMode(res.gpio_miso, LPC_PINMODE_PULLDOWN); - } - if (res.gpio_mosi >= 0) { - MapPortPinFunc(res.gpio_mosi, 0); - SetPortPinMode(res.gpio_mosi, LPC_PINMODE_PULLDOWN); - } -#if 0 - if (res.gpio_cs >= 0) { - MapPortPinFunc(res.gpio_cs, 0); - SetPortPinMode(res.gpio_cs, LPC_PINMODE_PULLDOWN); - } -#endif -} - -#define LPC_OSCRANGE_1_20_MHZ 0 -#define LPC_OSCRANGE_15_25_MHZ 1 - -struct scs_reg_t { - uint32_t reserved1 : 4; - uint32_t OSCRANGE : 1; - uint32_t OSCEN : 1; - uint32_t OSCSTAT : 1; - uint32_t reserved2 : 25; -}; -static_assert(sizeof(scs_reg_t) == 4, "invalid size of LPC scs_reg_t"); - -static scs_reg_t& SCS = *(scs_reg_t*)0x400FC1A0; - -#define LPC_CLKSRC_IRC 0 // 4MHz -#define LPC_CLKSRC_MAINOSC 1 // depending on OSCRANGE -#define LPC_CLKSRC_RTCOSC 2 // 32kHz - -struct clksrcsel_reg_t { - uint32_t CLKSRC : 2; - uint32_t reserved1 : 30; -}; -static_assert(sizeof(clksrcsel_reg_t) == 4, "invalid size of LPC clksrcsel_reg_t"); - -static clksrcsel_reg_t& CLKSRCSEL = *(clksrcsel_reg_t*)0x400FC10C; - -struct pll0stat_reg_t { - uint32_t MSEL0 : 15; // M - 1 - uint32_t reserved1 : 1; - uint32_t NSEL0 : 8; // N - 1 - uint32_t PLLE0_STAT : 1; // enable bit - uint32_t PLLC0_STAT : 1; // connect bit - uint32_t PLOCK0 : 1; // ready bit - uint32_t reserved2 : 5; -}; -static_assert(sizeof(pll0stat_reg_t) == 4, "invalid size of LPC pll0stat_reg_t"); - -static pll0stat_reg_t& PLL0STAT = *(pll0stat_reg_t*)0x400FC088; - -struct cclkcfg_reg_t { - uint32_t CCLKSEL : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(cclkcfg_reg_t) == 4, "invalid size of LPC cclkcfg_reg_t"); - -static cclkcfg_reg_t& CCLKCFG = *(cclkcfg_reg_t*)0x400FC104; - -#define LPC_PCLKSEL_QUARTER 0 -#define LPC_PCLKSEL_ONE 1 -#define LPC_PCLKSEL_HALF 2 -#define LPC_PCLKSEL_8_6 3 // 1/8 for generic, 1/6 for CAN1/2 - -struct pclksel0_reg_t { - uint32_t PCLK_WDT : 2; - uint32_t PCLK_TIMER0 : 2; - uint32_t PCLK_TIMER1 : 2; - uint32_t PCLK_UART0 : 2; - uint32_t PCLK_UART1 : 2; - uint32_t reserved1 : 2; - uint32_t PCLK_PWM1 : 2; - uint32_t PCLK_I2C0 : 2; - uint32_t PCLK_SPI : 2; - uint32_t reserved2 : 2; - uint32_t PCLK_SSP1 : 2; - uint32_t PCLK_DAC : 2; - uint32_t PCLK_ADC : 2; - uint32_t PCLK_CAN1 : 2; - uint32_t PCLK_CAN2 : 2; - uint32_t PCLK_ACF : 2; -}; -static_assert(sizeof(pclksel0_reg_t) == 4, "invalid size of LPC pclksel0_reg_t"); - -static pclksel0_reg_t& PCLKSEL0 = *(pclksel0_reg_t*)0x400FC1A8; - -struct pclksel1_reg_t { - uint32_t PCLK_QEI : 2; - uint32_t PCLK_GPIOINT : 2; - uint32_t PCLK_PCB : 2; - uint32_t PCLK_I2C1 : 2; - uint32_t reserved1 : 2; - uint32_t PCLK_SSP0 : 2; - uint32_t PCLK_TIMER2 : 2; - uint32_t PCLK_TIMER3 : 2; - uint32_t PCLK_UART2 : 2; - uint32_t PCLK_UART3 : 2; - uint32_t PCLK_I2C2 : 2; - uint32_t PCLK_I2S : 2; - uint32_t reserved2 : 2; - uint32_t PCLK_RIT : 2; - uint32_t PCLK_SYSCON : 2; - uint32_t PCLK_MC : 2; -}; -static_assert(sizeof(pclksel1_reg_t) == 4, "invalid size of LPC pclksel1_reg_t"); - -static pclksel1_reg_t& PCLKSEL1 = *(pclksel1_reg_t*)0x400FC1AC; - -// Enables or disables peripherals (power control for peripherals). -struct pconp_reg_t { - uint32_t reserved1 : 1; - uint32_t PCTIM0 : 1; - uint32_t PCTIM1 : 1; - uint32_t PCUART0 : 1; - uint32_t PCUART1 : 1; - uint32_t reserved2 : 1; - uint32_t PCPWM1 : 1; - uint32_t PCI2C0 : 1; - uint32_t PCSPI : 1; - uint32_t PCRTC : 1; - uint32_t PCSSP1 : 1; - uint32_t reserved3 : 1; - uint32_t PCADC : 1; - uint32_t PCCAN1 : 1; - uint32_t PCCAN2 : 1; - uint32_t PCGPIO : 1; - uint32_t PCRIT : 1; - uint32_t PCMCPWM : 1; - uint32_t PCQEI : 1; - uint32_t PCI2C1 : 1; - uint32_t reserved4 : 1; - uint32_t PCSSP0 : 1; - uint32_t PCTIM2 : 1; - uint32_t PCTIM3 : 1; - uint32_t PCUART2 : 1; - uint32_t PCUART3 : 1; - uint32_t PCI2C2 : 1; - uint32_t PC12S : 1; - uint32_t reserved5 : 1; - uint32_t PCGPDMA : 1; - uint32_t PCENET : 1; - uint32_t PCUSB : 1; -}; -static_assert(sizeof(pconp_reg_t) == 4, "invalid size of LPC pconp_reg_t"); - -static pconp_reg_t& PCONP = *(pconp_reg_t*)0x400FC0C4; - -static uint32_t GetCPUClockFrequency() { - if (PLL0STAT.PLLE0_STAT == false || PLL0STAT.PLLC0_STAT == false) { - // The CPU is running on the IRC. - return 4000000; - } + struct fioXpin_reg_t { + uint32_t val; - uint32_t clksrc = 0; - - switch(CLKSRCSEL.CLKSRC) { - case LPC_CLKSRC_IRC: - clksrc = 4000000; - break; - case LPC_CLKSRC_MAINOSC: - clksrc = LPC_MAINOSCILLATOR_FREQ; - break; - case LPC_CLKSRC_RTCOSC: - clksrc = 32000; - break; - } + inline void set(uint8_t reg, bool high) { + if (high) + val |= (1<> reg ); + } + }; + + static fioXdir_reg_t &FIO0DIR = *(fioXdir_reg_t*)0x2009C000; + static fioXdir_reg_t &FIO1DIR = *(fioXdir_reg_t*)0x2009C020; + static fioXdir_reg_t &FIO2DIR = *(fioXdir_reg_t*)0x2009C040; + static fioXdir_reg_t &FIO3DIR = *(fioXdir_reg_t*)0x2009C060; + static fioXdir_reg_t &FIO4DIR = *(fioXdir_reg_t*)0x2009C080; + + static fioXmask_reg_t &FIO0MASK = *(fioXmask_reg_t*)0x2009C010; + static fioXmask_reg_t &FIO1MASK = *(fioXmask_reg_t*)0x2009C030; + static fioXmask_reg_t &FIO2MASK = *(fioXmask_reg_t*)0x2009C050; + static fioXmask_reg_t &FIO3MASK = *(fioXmask_reg_t*)0x2009C070; + static fioXmask_reg_t &FIO4MASK = *(fioXmask_reg_t*)0x2009C090; + + static fioXpin_reg_t &FIO0PIN = *(fioXpin_reg_t*)0x2009C014; + static fioXpin_reg_t &FIO1PIN = *(fioXpin_reg_t*)0x2009C034; + static fioXpin_reg_t &FIO2PIN = *(fioXpin_reg_t*)0x2009C054; + static fioXpin_reg_t &FIO3PIN = *(fioXpin_reg_t*)0x2009C074; + static fioXpin_reg_t &FIO4PIN = *(fioXpin_reg_t*)0x2009C094; - uint32_t M = PLL0STAT.MSEL0 + 1; // M = 25 - uint32_t N = PLL0STAT.NSEL0 + 1; // N = 2 + #endif - uint32_t f_cco = (2 * M * clksrc) / N; + // Find a valid port-mapping for the given GPIO to a SPI bus peripheral. + // If it fails then a recommended SPI bus with a recommended set of GPIO + // pins should be used. + // The LPC1768 is a really good architecture, even though in comparison + // to the ESP32 it does not support mapping any peripheral signal to any + // GPIO pin. + struct portMapResult_t { + inline portMapResult_t() { + func = 0xFF; + } + inline bool isMapped() const { + return ( func != 0xFF ); + } + uint8_t func; + }; + + static bool SPIFindPortMapping( + int gpio_sck, int gpio_miso, int gpio_mosi, int gpio_cs, + uint8_t &sspBusOut, portMapResult_t &map_sck_out, portMapResult_t &map_miso_out, portMapResult_t &map_mosi_out, portMapResult_t &map_cs_out + ) { + portMapResult_t map_sck, map_miso, map_mosi, map_cs; + bool found = false; + + if ((gpio_sck == P0_15 || gpio_sck == P1_20) || (gpio_miso == P0_17 || gpio_miso == P1_23) || (gpio_mosi == P0_18 || gpio_mosi == P1_24) || (gpio_cs == P0_16 || gpio_cs == P1_21)) { + sspBusOut = 0; + if (gpio_sck == P0_15) { + map_sck.func = 2; + } + else if (gpio_sck == P1_20) { + map_sck.func = 3; + } + if (gpio_miso == P0_17) { + map_miso.func = 2; + } + else if (gpio_miso == P1_23) { + map_miso.func = 3; + } + if (gpio_mosi == P0_18) { + map_mosi.func = 2; + } + else if (gpio_mosi == P1_24) { + map_mosi.func = 3; + } + if (gpio_cs == P0_16) { + map_cs.func = 2; + } + else if (gpio_cs == P1_21) { + map_cs.func = 3; + } + found = true; + } + else if ((gpio_sck == P0_07 || gpio_sck == P1_31) || gpio_miso == P0_08 || gpio_mosi == P0_09 || gpio_cs == P0_06) { + sspBusOut = 1; + if (gpio_sck == P0_07) { + map_sck.func = 2; + } + else if (gpio_sck == P1_31) { + map_sck.func = 2; + } + if (gpio_miso == P0_08) { + map_miso.func = 2; + } + if (gpio_mosi == P0_09) { + map_mosi.func = 2; + } + if (gpio_cs == P0_06) { + map_cs.func = 2; + } + found = true; + } + if (found) { + map_sck_out = map_sck; + map_miso_out = map_miso; + map_mosi_out = map_mosi; + map_cs_out = map_cs; + } + return found; + } + + struct gpioMapResult_t { + uint8_t sspBusIdx; + int gpio_sck; + int gpio_miso; + int gpio_mosi; + int gpio_cs; + }; + + static void MapPortPinFunc(int pin, uint8_t func) { + #define _SWENT_MPPF(PS,PT,PN) case P##PT##_##PN: PINSEL##PS.p##PT##_##PN = func; break; + switch (pin) { + _SWENT_MPPF(0,0,00)_SWENT_MPPF(0,0,01)_SWENT_MPPF(0,0,02)_SWENT_MPPF(0,0,03)_SWENT_MPPF(0,0,04)_SWENT_MPPF(0,0,05)_SWENT_MPPF(0,0,06)_SWENT_MPPF(0,0,07) + _SWENT_MPPF(0,0,08)_SWENT_MPPF(0,0,09)_SWENT_MPPF(0,0,10)_SWENT_MPPF(0,0,11)_SWENT_MPPF(0,0,15) + _SWENT_MPPF(1,0,16)_SWENT_MPPF(1,0,17)_SWENT_MPPF(1,0,18)_SWENT_MPPF(1,0,19)_SWENT_MPPF(1,0,20) + _SWENT_MPPF(1,0,21)_SWENT_MPPF(1,0,22)_SWENT_MPPF(1,0,23)_SWENT_MPPF(1,0,24)_SWENT_MPPF(1,0,25) + _SWENT_MPPF(1,0,26)_SWENT_MPPF(1,0,27)_SWENT_MPPF(1,0,28)_SWENT_MPPF(1,0,29)_SWENT_MPPF(1,0,30) + _SWENT_MPPF(2,1,00)_SWENT_MPPF(2,1,01)_SWENT_MPPF(2,1,04)_SWENT_MPPF(2,1,08)_SWENT_MPPF(2,1,09)_SWENT_MPPF(2,1,10) + _SWENT_MPPF(2,1,14)_SWENT_MPPF(2,1,15) + _SWENT_MPPF(3,1,16)_SWENT_MPPF(3,1,17)_SWENT_MPPF(3,1,18)_SWENT_MPPF(3,1,19)_SWENT_MPPF(3,1,20) + _SWENT_MPPF(3,1,21)_SWENT_MPPF(3,1,22)_SWENT_MPPF(3,1,23)_SWENT_MPPF(3,1,24)_SWENT_MPPF(3,1,25) + _SWENT_MPPF(3,1,26)_SWENT_MPPF(3,1,27)_SWENT_MPPF(3,1,28)_SWENT_MPPF(3,1,29)_SWENT_MPPF(3,1,30) + _SWENT_MPPF(3,1,31) + _SWENT_MPPF(4,2,00)_SWENT_MPPF(4,2,01)_SWENT_MPPF(4,2,02)_SWENT_MPPF(4,2,03)_SWENT_MPPF(4,2,04) + _SWENT_MPPF(4,2,05)_SWENT_MPPF(4,2,06)_SWENT_MPPF(4,2,07)_SWENT_MPPF(4,2,08)_SWENT_MPPF(4,2,09) + _SWENT_MPPF(4,2,10)_SWENT_MPPF(4,2,11)_SWENT_MPPF(4,2,12)_SWENT_MPPF(4,2,13) + _SWENT_MPPF(7,3,25)_SWENT_MPPF(7,3,26) + _SWENT_MPPF(9,4,28)_SWENT_MPPF(9,4,29) + } + #undef _SWENT_MPPF + } + + static void SetPortPinMode(int pin, uint8_t mode) { + #define _SWENT_MPPM(PM,PT,PN) case P##PT##_##PN: PINMODE##PM.p##PT##_##PN##mode = mode; break; + switch (pin) { + _SWENT_MPPM(0,0,00)_SWENT_MPPM(0,0,01)_SWENT_MPPM(0,0,02)_SWENT_MPPM(0,0,03)_SWENT_MPPM(0,0,04)_SWENT_MPPM(0,0,05) + _SWENT_MPPM(0,0,06)_SWENT_MPPM(0,0,07)_SWENT_MPPM(0,0,08)_SWENT_MPPM(0,0,09)_SWENT_MPPM(0,0,10)_SWENT_MPPM(0,0,11) + _SWENT_MPPM(0,0,15) + _SWENT_MPPM(1,0,16)_SWENT_MPPM(1,0,17)_SWENT_MPPM(1,0,18)_SWENT_MPPM(1,0,19)_SWENT_MPPM(1,0,20)_SWENT_MPPM(1,0,21) + _SWENT_MPPM(1,0,22)_SWENT_MPPM(1,0,23)_SWENT_MPPM(1,0,24)_SWENT_MPPM(1,0,25)_SWENT_MPPM(1,0,26) + _SWENT_MPPM(2,1,00)_SWENT_MPPM(2,1,01)_SWENT_MPPM(2,1,04)_SWENT_MPPM(2,1,08)_SWENT_MPPM(2,1,09)_SWENT_MPPM(2,1,10) + _SWENT_MPPM(2,1,14)_SWENT_MPPM(2,1,15) + _SWENT_MPPM(3,1,16)_SWENT_MPPM(3,1,17)_SWENT_MPPM(3,1,18)_SWENT_MPPM(3,1,19)_SWENT_MPPM(3,1,20)_SWENT_MPPM(3,1,21) + _SWENT_MPPM(3,1,22)_SWENT_MPPM(3,1,23)_SWENT_MPPM(3,1,24)_SWENT_MPPM(3,1,25)_SWENT_MPPM(3,1,26)_SWENT_MPPM(3,1,27) + _SWENT_MPPM(3,1,28)_SWENT_MPPM(3,1,29)_SWENT_MPPM(3,1,30)_SWENT_MPPM(3,1,31) + _SWENT_MPPM(4,2,00)_SWENT_MPPM(4,2,01)_SWENT_MPPM(4,2,02)_SWENT_MPPM(4,2,03)_SWENT_MPPM(4,2,04)_SWENT_MPPM(4,2,05) + _SWENT_MPPM(4,2,06)_SWENT_MPPM(4,2,07)_SWENT_MPPM(4,2,08)_SWENT_MPPM(4,2,09)_SWENT_MPPM(4,2,10)_SWENT_MPPM(4,2,11) + _SWENT_MPPM(4,2,12)_SWENT_MPPM(4,2,13) + _SWENT_MPPM(7,3,25)_SWENT_MPPM(7,3,26) + _SWENT_MPPM(9,4,28)_SWENT_MPPM(9,4,29) + } + #undef _SWENT_MPPM + } + + #if 0 + static void SetPortPinDirection(int pin, uint8_t dir) { + #define _SWENT_SPPD_(PT,PNN,PN) case P##PT##_##PNN: FIO##PT##DIR.set(PN, dir); break; + #define _SWENT_SPPD(PT,PN) case P##PT##_##PN: FIO##PT##DIR.set(PN, dir); break; + switch (pin) { + _SWENT_SPPD_(0,00,0)_SWENT_SPPD_(0,01,1)_SWENT_SPPD_(0,02,2)_SWENT_SPPD_(0,03,3)_SWENT_SPPD_(0,04,4)_SWENT_SPPD_(0,05,5)_SWENT_SPPD_(0,06,6) + _SWENT_SPPD_(0,07,7)_SWENT_SPPD_(0,08,8)_SWENT_SPPD_(0,09,9)_SWENT_SPPD(0,10)_SWENT_SPPD(0,11)_SWENT_SPPD(0,15)_SWENT_SPPD(0,16) + _SWENT_SPPD(0,17)_SWENT_SPPD(0,18)_SWENT_SPPD(0,19)_SWENT_SPPD(0,20)_SWENT_SPPD(0,21)_SWENT_SPPD(0,22)_SWENT_SPPD(0,23) + _SWENT_SPPD(0,24)_SWENT_SPPD(0,25)_SWENT_SPPD(0,26)_SWENT_SPPD(0,27)_SWENT_SPPD(0,28)_SWENT_SPPD(0,29)_SWENT_SPPD(0,30) + _SWENT_SPPD_(1,00,0)_SWENT_SPPD_(1,01,1)_SWENT_SPPD_(1,04,4)_SWENT_SPPD_(1,08,8)_SWENT_SPPD_(1,09,9)_SWENT_SPPD(1,10)_SWENT_SPPD(1,14) + _SWENT_SPPD(1,15)_SWENT_SPPD(1,16)_SWENT_SPPD(1,17)_SWENT_SPPD(1,18)_SWENT_SPPD(1,19)_SWENT_SPPD(1,20)_SWENT_SPPD(1,21) + _SWENT_SPPD(1,22)_SWENT_SPPD(1,23)_SWENT_SPPD(1,24)_SWENT_SPPD(1,25)_SWENT_SPPD(1,26)_SWENT_SPPD(1,27)_SWENT_SPPD(1,28) + _SWENT_SPPD(1,29)_SWENT_SPPD(1,30)_SWENT_SPPD(1,31) + _SWENT_SPPD_(2,00,0)_SWENT_SPPD_(2,01,1)_SWENT_SPPD_(2,02,2)_SWENT_SPPD_(2,03,3)_SWENT_SPPD_(2,04,4)_SWENT_SPPD_(2,05,5)_SWENT_SPPD_(2,06,6)_SWENT_SPPD_(2,07,7) + _SWENT_SPPD_(2,08,8)_SWENT_SPPD_(2,09,9)_SWENT_SPPD(2,10)_SWENT_SPPD(2,11)_SWENT_SPPD(2,12)_SWENT_SPPD(2,13) + _SWENT_SPPD(3,25)_SWENT_SPPD(3,26) + _SWENT_SPPD(4,28)_SWENT_SPPD(4,29) + } + #undef _SWENT_SPPD + #undef _SWENT_SPPD_ + } + #endif - uint32_t cclkdiv = CCLKCFG.CCLKSEL + 1; + static gpioMapResult_t SPIMapGPIO(int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { + // First try to find a direct mapping to SSP peripheral based on the given pin hints. + uint8_t sspBusIdx; + portMapResult_t map_sck, map_miso, map_mosi, map_cs; + + bool foundPortMap = SPIFindPortMapping(hint_sck, hint_miso, hint_mosi, hint_cs, sspBusIdx, map_sck, map_miso, map_mosi, map_cs); + + if (!foundPortMap) { + // Just select the default SSP config. + sspBusIdx = 0; + hint_sck = P0_15; + map_sck.func = 2; + hint_miso = P0_17; + map_miso.func = 2; + hint_mosi = P0_18; + map_mosi.func = 2; + hint_cs = P0_16; + map_cs.func = 2; + } - return (f_cco / cclkdiv); -} + // Map the functions that exist. + if (map_sck.isMapped()) { + MapPortPinFunc(hint_sck, map_sck.func); + SetPortPinMode(hint_sck, LPC_PINMODE_NONE); + } + if (map_miso.isMapped()) { + MapPortPinFunc(hint_miso, map_miso.func); + SetPortPinMode(hint_miso, LPC_PINMODE_PULLDOWN); + } + if (map_mosi.isMapped()) { + MapPortPinFunc(hint_mosi, map_mosi.func); + SetPortPinMode(hint_mosi, LPC_PINMODE_NONE); + } + #if 0 + if (map_cs.isMapped()) { + MapPortPinFunc(hint_cs, map_cs.func); + SetPortPinMode(hint_cs, LPC_PINMODE_NONE); + } + #endif + + gpioMapResult_t res; + res.sspBusIdx = sspBusIdx; + res.gpio_sck = ( map_sck.isMapped() ? hint_sck : -1 ); + res.gpio_miso = ( map_miso.isMapped() ? hint_miso : -1 ); + res.gpio_mosi = ( map_mosi.isMapped() ? hint_mosi : -1 ); + res.gpio_cs = ( map_cs.isMapped() ? hint_cs : -1 ); + return res; + } + + static void SPIUnmapGPIO(const gpioMapResult_t &res) { + // Reset to architecture default configs on the pins that we previously mapped. + if (res.gpio_sck >= 0) { + MapPortPinFunc(res.gpio_sck, 0); + SetPortPinMode(res.gpio_sck, LPC_PINMODE_PULLDOWN); + } + if (res.gpio_miso >= 0) { + MapPortPinFunc(res.gpio_miso, 0); + SetPortPinMode(res.gpio_miso, LPC_PINMODE_PULLDOWN); + } + if (res.gpio_mosi >= 0) { + MapPortPinFunc(res.gpio_mosi, 0); + SetPortPinMode(res.gpio_mosi, LPC_PINMODE_PULLDOWN); + } + #if 0 + if (res.gpio_cs >= 0) { + MapPortPinFunc(res.gpio_cs, 0); + SetPortPinMode(res.gpio_cs, LPC_PINMODE_PULLDOWN); + } + #endif + } + + #define LPC_OSCRANGE_1_20_MHZ 0 + #define LPC_OSCRANGE_15_25_MHZ 1 + + struct scs_reg_t { + uint32_t reserved1 : 4; + uint32_t OSCRANGE : 1; + uint32_t OSCEN : 1; + uint32_t OSCSTAT : 1; + uint32_t reserved2 : 25; + }; + static_assert(sizeof(scs_reg_t) == 4, "invalid size of LPC scs_reg_t"); + + static scs_reg_t &SCS = *(scs_reg_t*)0x400FC1A0; + + #define LPC_CLKSRC_IRC 0 // 4MHz + #define LPC_CLKSRC_MAINOSC 1 // depending on OSCRANGE + #define LPC_CLKSRC_RTCOSC 2 // 32kHz + + struct clksrcsel_reg_t { + uint32_t CLKSRC : 2; + uint32_t reserved1 : 30; + }; + static_assert(sizeof(clksrcsel_reg_t) == 4, "invalid size of LPC clksrcsel_reg_t"); + + static clksrcsel_reg_t &CLKSRCSEL = *(clksrcsel_reg_t*)0x400FC10C; + + struct pll0stat_reg_t { + uint32_t MSEL0 : 15; // M - 1 + uint32_t reserved1 : 1; + uint32_t NSEL0 : 8; // N - 1 + uint32_t PLLE0_STAT : 1; // enable bit + uint32_t PLLC0_STAT : 1; // connect bit + uint32_t PLOCK0 : 1; // ready bit + uint32_t reserved2 : 5; + }; + static_assert(sizeof(pll0stat_reg_t) == 4, "invalid size of LPC pll0stat_reg_t"); + + static pll0stat_reg_t &PLL0STAT = *(pll0stat_reg_t*)0x400FC088; + + struct cclkcfg_reg_t { + uint32_t CCLKSEL : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(cclkcfg_reg_t) == 4, "invalid size of LPC cclkcfg_reg_t"); + + static cclkcfg_reg_t &CCLKCFG = *(cclkcfg_reg_t*)0x400FC104; + + #define LPC_PCLKSEL_QUARTER 0 + #define LPC_PCLKSEL_ONE 1 + #define LPC_PCLKSEL_HALF 2 + #define LPC_PCLKSEL_8_6 3 // 1/8 for generic, 1/6 for CAN1/2 + + struct pclksel0_reg_t { + uint32_t PCLK_WDT : 2; + uint32_t PCLK_TIMER0 : 2; + uint32_t PCLK_TIMER1 : 2; + uint32_t PCLK_UART0 : 2; + uint32_t PCLK_UART1 : 2; + uint32_t reserved1 : 2; + uint32_t PCLK_PWM1 : 2; + uint32_t PCLK_I2C0 : 2; + uint32_t PCLK_SPI : 2; + uint32_t reserved2 : 2; + uint32_t PCLK_SSP1 : 2; + uint32_t PCLK_DAC : 2; + uint32_t PCLK_ADC : 2; + uint32_t PCLK_CAN1 : 2; + uint32_t PCLK_CAN2 : 2; + uint32_t PCLK_ACF : 2; + }; + static_assert(sizeof(pclksel0_reg_t) == 4, "invalid size of LPC pclksel0_reg_t"); + + static pclksel0_reg_t &PCLKSEL0 = *(pclksel0_reg_t*)0x400FC1A8; + + struct pclksel1_reg_t { + uint32_t PCLK_QEI : 2; + uint32_t PCLK_GPIOINT : 2; + uint32_t PCLK_PCB : 2; + uint32_t PCLK_I2C1 : 2; + uint32_t reserved1 : 2; + uint32_t PCLK_SSP0 : 2; + uint32_t PCLK_TIMER2 : 2; + uint32_t PCLK_TIMER3 : 2; + uint32_t PCLK_UART2 : 2; + uint32_t PCLK_UART3 : 2; + uint32_t PCLK_I2C2 : 2; + uint32_t PCLK_I2S : 2; + uint32_t reserved2 : 2; + uint32_t PCLK_RIT : 2; + uint32_t PCLK_SYSCON : 2; + uint32_t PCLK_MC : 2; + }; + static_assert(sizeof(pclksel1_reg_t) == 4, "invalid size of LPC pclksel1_reg_t"); + + static pclksel1_reg_t &PCLKSEL1 = *(pclksel1_reg_t*)0x400FC1AC; + + // Enables or disables peripherals (power control for peripherals). + struct pconp_reg_t { + uint32_t reserved1 : 1; + uint32_t PCTIM0 : 1; + uint32_t PCTIM1 : 1; + uint32_t PCUART0 : 1; + uint32_t PCUART1 : 1; + uint32_t reserved2 : 1; + uint32_t PCPWM1 : 1; + uint32_t PCI2C0 : 1; + uint32_t PCSPI : 1; + uint32_t PCRTC : 1; + uint32_t PCSSP1 : 1; + uint32_t reserved3 : 1; + uint32_t PCADC : 1; + uint32_t PCCAN1 : 1; + uint32_t PCCAN2 : 1; + uint32_t PCGPIO : 1; + uint32_t PCRIT : 1; + uint32_t PCMCPWM : 1; + uint32_t PCQEI : 1; + uint32_t PCI2C1 : 1; + uint32_t reserved4 : 1; + uint32_t PCSSP0 : 1; + uint32_t PCTIM2 : 1; + uint32_t PCTIM3 : 1; + uint32_t PCUART2 : 1; + uint32_t PCUART3 : 1; + uint32_t PCI2C2 : 1; + uint32_t PC12S : 1; + uint32_t reserved5 : 1; + uint32_t PCGPDMA : 1; + uint32_t PCENET : 1; + uint32_t PCUSB : 1; + }; + static_assert(sizeof(pconp_reg_t) == 4, "invalid size of LPC pconp_reg_t"); + + static pconp_reg_t &PCONP = *(pconp_reg_t*)0x400FC0C4; + + static uint32_t GetCPUClockFrequency() { + if (!PLL0STAT.PLLE0_STAT || !PLL0STAT.PLLC0_STAT) { + // The CPU is running on the IRC. + return 4000000; + } -struct sspClockResult_t { - uint32_t pclk_ssp : 2; - uint32_t scr : 8; - uint32_t cpsdvsr : 8; // value between 2 and 254 -}; + uint32_t clksrc = 0; -static sspClockResult_t SPICalculateClock(uint32_t maxClockFreq) { - uint32_t cpuFreq = GetCPUClockFrequency(); + switch (CLKSRCSEL.CLKSRC) { + case LPC_CLKSRC_IRC: clksrc = 4000000; break; + case LPC_CLKSRC_MAINOSC: clksrc = LPC_MAINOSCILLATOR_FREQ; break; + case LPC_CLKSRC_RTCOSC: clksrc = 32000; break; + } - if (maxClockFreq >= cpuFreq) { - // Return the fastest clock. - sspClockResult_t maxRes; - maxRes.pclk_ssp = LPC_PCLKSEL_ONE; - maxRes.scr = 0; - maxRes.cpsdvsr = 2; // minimum value. - return maxRes; - } + uint32_t M = PLL0STAT.MSEL0 + 1; // M = 25 + uint32_t N = PLL0STAT.NSEL0 + 1; // N = 2 - uint32_t DIV_ceil = ((cpuFreq + (maxClockFreq - 1)) / maxClockFreq); + uint32_t f_cco = (2 * M * clksrc) / N; - if (/* DIV_ceil >= 1 && */ DIV_ceil <= 256) { - uint32_t rem_two = (DIV_ceil % 2); + uint32_t cclkdiv = CCLKCFG.CCLKSEL + 1; - if (rem_two == 0 && DIV_ceil >= 2 && DIV_ceil <= 254) { - sspClockResult_t accRes; - accRes.pclk_ssp = LPC_PCLKSEL_ONE; - accRes.scr = 0; - accRes.cpsdvsr = DIV_ceil; - return accRes; - } - else { - // Return a very accurate SCR representation. - sspClockResult_t accRes; - accRes.pclk_ssp = LPC_PCLKSEL_ONE; - accRes.scr = (DIV_ceil+rem_two)/2 - 1; - accRes.cpsdvsr = 2; // minimum value. - return accRes; + return (f_cco / cclkdiv); } - } - // Brute-force find the clock result. - // Still very fast, optimized using math. - sspClockResult_t best; - best.pclk_ssp = LPC_PCLKSEL_8_6; - best.scr = 255; - best.cpsdvsr = 254; - uint32_t last_best_clockfreq = 0; - bool has_result = false; - - uint32_t ps_ssp = 2; - - while (ps_ssp <= 8) { - uint32_t ps_dvsr = (1<<7)*ps_ssp; - - while (ps_dvsr <= (254u*ps_ssp)) { - uint32_t presc = (ps_dvsr*ps_ssp); - uint32_t scr = (DIV_ceil/presc); - uint32_t freq = (cpuFreq/(presc*scr)); - - if (freq <= maxClockFreq) { - if (has_result == false || last_best_clockfreq < freq) { - last_best_clockfreq = freq; - if (ps_ssp == 2) - best.pclk_ssp = LPC_PCLKSEL_HALF; - else if (ps_ssp == 4) - best.pclk_ssp = LPC_PCLKSEL_QUARTER; - else - best.pclk_ssp = LPC_PCLKSEL_8_6; - best.scr = (scr-1); - best.cpsdvsr = ps_dvsr; - has_result = true; - } + struct sspClockResult_t { + uint32_t pclk_ssp : 2; + uint32_t scr : 8; + uint32_t cpsdvsr : 8; // value between 2 and 254 + }; + + static sspClockResult_t SPICalculateClock(uint32_t maxClockFreq) { + uint32_t cpuFreq = GetCPUClockFrequency(); + + if (maxClockFreq >= cpuFreq) { + // Return the fastest clock. + sspClockResult_t maxRes; + maxRes.pclk_ssp = LPC_PCLKSEL_ONE; + maxRes.scr = 0; + maxRes.cpsdvsr = 2; // minimum value. + return maxRes; } - ps_dvsr += ps_ssp*2; - } + uint32_t DIV_ceil = ((cpuFreq + (maxClockFreq - 1)) / maxClockFreq); - ps_ssp *= 2; - } + if (/* DIV_ceil >= 1 && */ DIV_ceil <= 256) { + uint32_t rem_two = (DIV_ceil % 2); - return best; -} - -struct sspNcr0_reg_t { - uint32_t DSS : 4; - uint32_t FRF : 2; - uint32_t CPOL : 1; - uint32_t CPHA : 1; - uint32_t SCR : 8; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(sspNcr0_reg_t) == 4, "invalid size of LPC sspNcr0_reg_t"); - -struct sspNcr1_reg_t { - uint32_t LBM : 1; - uint32_t SSE : 1; - uint32_t MS : 1; - uint32_t SOD : 1; - uint32_t reserved1 : 28; -}; -static_assert(sizeof(sspNcr1_reg_t) == 4, "invalid size of LPC sspNcr1_reg_t"); - -struct sspNdr_reg_t { - uint32_t DATA : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(sspNdr_reg_t) == 4, "invalid size of LPC sspNdr_reg_t"); - -struct sspNsr_reg_t { - uint32_t TFE : 1; - uint32_t TNF : 1; - uint32_t RNE : 1; - uint32_t RFF : 1; - uint32_t BSY : 1; - uint32_t reserved1 : 27; -}; -static_assert(sizeof(sspNsr_reg_t) == 4, "invalid size of LPC sspNsr_reg_t"); - -struct sspNcpsr_reg_t { - uint32_t CPSDVSR : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(sspNcpsr_reg_t) == 4, "invalid size of LPC sspNcpsr_reg_t"); - -struct sspNimsc_reg_t { - uint32_t RORIM : 1; - uint32_t RTIM : 1; - uint32_t RXIM : 1; - uint32_t TXIM : 1; - uint32_t reserved1 : 28; -}; -static_assert(sizeof(sspNimsc_reg_t) == 4, "invalid size of LPC sspNimsc_reg_t"); - -struct sspNris_reg_t { - uint32_t RORRIS : 1; - uint32_t RTRIS : 1; - uint32_t RXRIS : 1; - uint32_t TXRIS : 1; - uint32_t reserved1 : 28; -}; -static_assert(sizeof(sspNris_reg_t) == 4, "invalid size of LPC sspNris_reg_t"); - -struct sspNmis_reg_t { - uint32_t RORMIS : 1; - uint32_t RTMIS : 1; - uint32_t RXMIS : 1; - uint32_t TXMIS : 1; - uint32_t reserved1 : 28; -}; -static_assert(sizeof(sspNmis_reg_t) == 4, "invalid size of LPC sspNmis_reg_t"); - -struct sspNicr_reg_t { - uint32_t RORIC : 1; - uint32_t RTIC : 1; - uint32_t reserved1 : 30; -}; -static_assert(sizeof(sspNicr_reg_t) == 4, "invalid size of LPC sspNicr_reg_t"); - -struct sspNdmacr_reg_t { - uint32_t RXDMAE : 1; - uint32_t TXDMAE : 1; - uint32_t reserved1 : 30; -}; -static_assert(sizeof(sspNdmacr_reg_t) == 4, "invalid size of LPC sspNdmacr_reg_t"); - -struct ssp_dev_t { - sspNcr0_reg_t CR0; - sspNcr1_reg_t CR1; - sspNdr_reg_t DR; - sspNsr_reg_t SR; - sspNcpsr_reg_t CPSR; - sspNimsc_reg_t IMSC; - sspNris_reg_t RIS; - sspNmis_reg_t MIS; - sspNicr_reg_t ICR; - sspNdmacr_reg_t DMACR; -}; -static_assert(sizeof(ssp_dev_t) == 40, "invalid size of LPC ssp_dev_t"); - -static volatile ssp_dev_t& SSP0 = *(volatile ssp_dev_t*)0x40088000; -static volatile ssp_dev_t& SSP1 = *(volatile ssp_dev_t*)0x40030000; - -inline volatile ssp_dev_t& SPIGetBusFromIndex(uint8_t idx) { - if (idx == 0) return SSP0; - if (idx == 1) return SSP1; - return SSP0; // default -} - -inline uint8_t SPIGetBusIndex(volatile ssp_dev_t& SSP) { - if (&SSP == &SSP0) return 0; - if (&SSP == &SSP1) return 1; - return 0; // default -} - -#ifndef HALSPI_DISABLE_DMA - -struct DMACIntStat_reg_t { - uint32_t IntStat : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACIntStat_reg_t) == 4, "invalid size of LPC DMACIntStat_reg_t"); - -static DMACIntStat_reg_t& DMACIntStat = *(DMACIntStat_reg_t*)0x50004000; - -struct DMACIntTCStat_reg_t { - uint32_t IntTCStat : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACIntTCStat_reg_t) == 4, "invalid size of LPC DMACIntTCStat_reg_t"); - -static DMACIntTCStat_reg_t& DMACIntTCStat = *(DMACIntTCStat_reg_t*)0x50004004; - -struct DMACIntTCClear_reg_t { - uint32_t IntTCClear : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACIntTCClear_reg_t) == 4, "invalid size of LPC DMAIntTCClear_reg_t"); - -static DMACIntTCClear_reg_t& DMACIntTCClear = *(DMACIntTCClear_reg_t*)0x50004008; - -struct DMACIntErrStat_reg_t { - uint32_t IntErrStat : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACIntErrStat_reg_t) == 4, "invalid size of LPC DMACIntErrStat_reg_t"); - -static DMACIntErrStat_reg_t& DMACIntErrStat = *(DMACIntErrStat_reg_t*)0x5000400C; - -struct DMACIntErrClr_reg_t { - uint32_t IntErrClr : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACIntErrClr_reg_t) == 4, "invalid size of LPC DMACIntErrClr_reg_t"); - -static DMACIntErrClr_reg_t& DMACIntErrClr = *(DMACIntErrClr_reg_t*)0x50004010; - -struct DMACRawIntTCStat_reg_t { - uint32_t RawIntTCStat : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACRawIntTCStat_reg_t) == 4, "invalid size of LPC DMACRawIntTCStat_reg_t"); - -static DMACRawIntTCStat_reg_t& DMACRawIntTCStat = *(DMACRawIntTCStat_reg_t*)0x50004014; - -struct DMACRawIntErrStat_reg_t { - uint32_t RawIntErrStat : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACRawIntErrStat_reg_t) == 4, "invalid size of LPC DMACRawIntErrStat_reg_t"); - -static DMACRawIntErrStat_reg_t& DMACRawIntErrStat = *(DMACRawIntErrStat_reg_t*)0x50004018; - -struct DMACEnbldChns_reg_t { - uint32_t EnabledChannels : 8; - uint32_t reserved1 : 24; -}; -static_assert(sizeof(DMACEnbldChns_reg_t) == 4, "invalid size of LPC DMACEnbldChns_reg_t"); - -static DMACEnbldChns_reg_t& DMACEnbldChns = *(DMACEnbldChns_reg_t*)0x5000401C; - -struct DMACSoftBReq_reg_t { - uint32_t SoftBReq : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(DMACSoftBReq_reg_t) == 4, "invalid size of LPC DMACSoftBReq_reg_t"); - -static DMACSoftBReq_reg_t& DMACSoftBReq = *(DMACSoftBReq_reg_t*)0x50004020; - -struct DMACSoftSReq_reg_t { - uint32_t SoftSReq : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(DMACSoftSReq_reg_t) == 4, "invalid size of LPC DMACSoftSReq_reg_t"); - -static DMACSoftSReq_reg_t& DMACSoftSReq = *(DMACSoftSReq_reg_t*)0x50004024; - -struct DMACSoftLBReq_reg_t { - uint32_t SoftLBReq : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(DMACSoftLBReq_reg_t) == 4, "invalid size of LPC DMACSoftLBReq_reg_t"); - -static DMACSoftLBReq_reg_t& DMACSoftLBReq = *(DMACSoftLBReq_reg_t*)0x50004028; - -struct DMACSoftLSReq_reg_t { - uint32_t SoftLSReq : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(DMACSoftLSReq_reg_t) == 4, "invalid size of LPC DMACSoftLSReq_reg_t"); - -static DMACSoftLSReq_reg_t& DMACSoftLSReq = *(DMACSoftLSReq_reg_t*)0x5000402C; - -struct DMACConfig_reg_t { - uint32_t E : 1; - uint32_t M : 1; - uint32_t reserved1 : 30; -}; -static_assert(sizeof(DMACConfig_reg_t) == 4, "invalid size of LPC DMACConfig_reg_t"); - -static DMACConfig_reg_t& DMACConfig = *(DMACConfig_reg_t*)0x50004030; - -struct DMACSync_reg_t { - uint32_t DMACSync : 16; - uint32_t reserved1 : 16; -}; -static_assert(sizeof(DMACSync_reg_t) == 4, "invalid size of LPC DMACSync_reg_t"); - -static DMACSync_reg_t& DMACSync = *(DMACSync_reg_t*)0x50004034; - -struct DMAReqSel_reg_t { - uint32_t DMASEL08 : 1; - uint32_t DMASEL09 : 1; - uint32_t DMASEL10 : 1; - uint32_t DMASEL11 : 1; - uint32_t DMASEL12 : 1; - uint32_t DMASEL13 : 1; - uint32_t DMASEL14 : 1; - uint32_t DMASEL15 : 1; - uint32_t reserved : 24; -}; -static_assert(sizeof(DMAReqSel_reg_t) == 4, "invalid size of LPC DMAReqSel_reg_t"); - -static DMAReqSel_reg_t& DMAReqSel = *(DMAReqSel_reg_t*)0x400FC1C4; - -struct DMACCxLLI_reg_t { - uint32_t reserved1 : 2; - uint32_t LLI : 30; -}; -static_assert(sizeof(DMACCxLLI_reg_t) == 4, "invalid size of LPC DMACCxLLI_reg_t"); - -struct DMACCxControl_reg_t { - uint32_t TransferSize : 12; - uint32_t SBSize : 3; - uint32_t DBSize : 3; - uint32_t SWidth : 3; - uint32_t DWidth : 3; - uint32_t reserved1 : 2; - uint32_t SI : 1; - uint32_t DI : 1; - uint32_t Prot1 : 1; - uint32_t Prot2 : 1; - uint32_t Prot3 : 1; - uint32_t I : 1; -}; -static_assert(sizeof(DMACCxControl_reg_t) == 4, "invalid size of LPC DMACCxControl_reg_t"); - -struct DMACCxConfig_reg_t { - uint32_t E : 1; - uint32_t SrcPeripheral : 5; - uint32_t DestPeripheral : 5; - uint32_t TransferType : 3; - uint32_t IE : 1; - uint32_t ITC : 1; - uint32_t L : 1; - uint32_t A : 1; - uint32_t H : 1; - uint32_t reserved1 : 13; -}; -static_assert(sizeof(DMACCxConfig_reg_t) == 4, "invalid size of LPC DMACCxConfig_reg_t"); - -struct DMACChannel_dev_t { - uint32_t SrcAddr; - uint32_t DestAddr; - DMACCxLLI_reg_t LLI; - DMACCxControl_reg_t Control; - DMACCxConfig_reg_t Config; -}; -static_assert(sizeof(DMACChannel_dev_t) == 20, "invalid size of LPC DMACChannel_dev_t"); - -static DMACChannel_dev_t& DMACC0 = *(DMACChannel_dev_t*)0x50004100; -static DMACChannel_dev_t& DMACC1 = *(DMACChannel_dev_t*)0x50004120; -static DMACChannel_dev_t& DMACC2 = *(DMACChannel_dev_t*)0x50004140; -static DMACChannel_dev_t& DMACC3 = *(DMACChannel_dev_t*)0x50004160; -static DMACChannel_dev_t& DMACC4 = *(DMACChannel_dev_t*)0x50004180; -static DMACChannel_dev_t& DMACC5 = *(DMACChannel_dev_t*)0x500041A0; -static DMACChannel_dev_t& DMACC6 = *(DMACChannel_dev_t*)0x500041C0; -static DMACChannel_dev_t& DMACC7 = *(DMACChannel_dev_t*)0x500041E0; - -static DMACChannel_dev_t& DMAGetChannel(uint32_t idx) { - switch(idx) { - case 0: return DMACC0; - case 1: return DMACC1; - case 2: return DMACC2; - case 3: return DMACC3; - case 4: return DMACC4; - case 5: return DMACC5; - case 6: return DMACC6; - case 7: return DMACC7; - } - return DMACC0; // default. -} - -static uint32_t __attribute__((unused)) DMAGetChannelIndex(DMACChannel_dev_t& DMACC) { - if (&DMACC == &DMACC0) return 0; - if (&DMACC == &DMACC1) return 1; - if (&DMACC == &DMACC2) return 2; - if (&DMACC == &DMACC3) return 3; - if (&DMACC == &DMACC4) return 4; - if (&DMACC == &DMACC5) return 5; - if (&DMACC == &DMACC6) return 6; - if (&DMACC == &DMACC7) return 7; - return 0; // default. -} - -#ifdef HAL_SPI_SUPPORTS_ASYNC - -struct DMACCxLLI_desc_t { - uint32_t SrcAddr; - uint32_t DestAddr; - DMACCxLLI_desc_t *Next; - DMACCxControl_reg_t Control; -}; -static_assert(sizeof(DMACCxLLI_desc_t) == 16, "invalid size of LPC DMACCxLLI_desc_t"); - -struct DMACCxLLI_desc_user_t : public DMACCxLLI_desc_t { - // User data by software. - bool available = true; -}; - -#ifndef HALSPI_LPC_STATIC_DMADESCS -#define HALSPI_LPC_STATIC_DMADESCS 3 -#endif - -static DMACCxLLI_desc_user_t _available_dma_descs[HALSPI_LPC_STATIC_DMADESCS]; - -static DMACCxLLI_desc_user_t* DMAFindFreeChainLLI() { - for (auto& item : _available_dma_descs) { - if (item.available) { - return &item; - } - } - return nullptr; -} - -struct dma_process_t { - DMACChannel_dev_t *current_DMACC; - const void *current_buffer; - size_t curoff; - size_t txlen; - uint8_t txunitsize; - void (*completeCallback)(void*); - void *complete_ud; - DMACCxLLI_desc_user_t *last_chain; - bool is_active = false; -}; - -static dma_process_t _dma_async_proc; - -static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { - DMACCxLLI_desc_user_t *first = nullptr; - DMACCxLLI_desc_user_t *last = nullptr; - - uint32_t txwidth = 0; - - if (proc.txunitsize == 1) { - txwidth = 0; - } - else if (proc.txunitsize == 2) { - txwidth = 1; - } - else if (proc.txunitsize == 4) { - txwidth = 2; - } - else - _spi_on_error(4); - - DMACCxControl_reg_t Control; - Control.SBSize = 0; - Control.DBSize = 0; - Control.SWidth = txwidth; - Control.DWidth = txwidth; - Control.SI = true; - Control.DI = false; - Control.Prot1 = 1; - Control.Prot2 = 0; - Control.Prot3 = 1; - Control.I = false; - - bool init_ch_prog = false; - - auto& DMACC = *proc.current_DMACC; - DMACC.Config.ITC = true; - - while (proc.curoff < proc.txlen) { - size_t left = (proc.txlen - proc.curoff); - size_t takecnt = (uint32_t)__MIN (left, (1<<12)-1); - - Control.TransferSize = takecnt; - - uint32_t SrcAddr = ( (uint32_t)proc.current_buffer + proc.curoff * proc.txunitsize ); - uint32_t DestAddr = (uint32_t)&SSP.DR; - - if (init_ch_prog == false) { - // We first have to program the channel itself. - DMACC.SrcAddr = SrcAddr; - DMACC.DestAddr = DestAddr; - DMACC.LLI.LLI = 0; - DMACC.Control = Control; - init_ch_prog = true; - } - else { - auto *freelli = DMAFindFreeChainLLI(); + if (rem_two == 0 && DIV_ceil >= 2 && DIV_ceil <= 254) { + sspClockResult_t accRes; + accRes.pclk_ssp = LPC_PCLKSEL_ONE; + accRes.scr = 0; + accRes.cpsdvsr = DIV_ceil; + return accRes; + } + else { + // Return a very accurate SCR representation. + sspClockResult_t accRes; + accRes.pclk_ssp = LPC_PCLKSEL_ONE; + accRes.scr = (DIV_ceil+rem_two)/2 - 1; + accRes.cpsdvsr = 2; // minimum value. + return accRes; + } + } - if (freelli == nullptr) break; + // Brute-force find the clock result. + // Still very fast, optimized using math. + sspClockResult_t best; + best.pclk_ssp = LPC_PCLKSEL_8_6; + best.scr = 255; + best.cpsdvsr = 254; + uint32_t last_best_clockfreq = 0; + bool has_result = false; + + uint32_t ps_ssp = 2; + + while (ps_ssp <= 8) { + uint32_t ps_dvsr = (1<<7)*ps_ssp; + + while (ps_dvsr <= (254u*ps_ssp)) { + uint32_t presc = (ps_dvsr*ps_ssp); + uint32_t scr = (DIV_ceil/presc); + uint32_t freq = (cpuFreq/(presc*scr)); + + if (freq <= maxClockFreq) { + if (!has_result || last_best_clockfreq < freq) { + last_best_clockfreq = freq; + if (ps_ssp == 2) + best.pclk_ssp = LPC_PCLKSEL_HALF; + else if (ps_ssp == 4) + best.pclk_ssp = LPC_PCLKSEL_QUARTER; + else + best.pclk_ssp = LPC_PCLKSEL_8_6; + best.scr = (scr-1); + best.cpsdvsr = ps_dvsr; + has_result = true; + } + } - freelli->SrcAddr = SrcAddr; - freelli->DestAddr = DestAddr; - freelli->Next = nullptr; - freelli->Control = Control; - freelli->available = false; + ps_dvsr += ps_ssp*2; + } - if (first == nullptr) { - first = freelli; - DMACC.LLI.LLI = ( (uint32_t)freelli >> 2 ); + ps_ssp *= 2; } - if (last) { - last->Next = freelli; + return best; + } + + struct sspNcr0_reg_t { + uint32_t DSS : 4; + uint32_t FRF : 2; + uint32_t CPOL : 1; + uint32_t CPHA : 1; + uint32_t SCR : 8; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(sspNcr0_reg_t) == 4, "invalid size of LPC sspNcr0_reg_t"); + + struct sspNcr1_reg_t { + uint32_t LBM : 1; + uint32_t SSE : 1; + uint32_t MS : 1; + uint32_t SOD : 1; + uint32_t reserved1 : 28; + }; + static_assert(sizeof(sspNcr1_reg_t) == 4, "invalid size of LPC sspNcr1_reg_t"); + + struct sspNdr_reg_t { + uint32_t DATA : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(sspNdr_reg_t) == 4, "invalid size of LPC sspNdr_reg_t"); + + struct sspNsr_reg_t { + uint32_t TFE : 1; + uint32_t TNF : 1; + uint32_t RNE : 1; + uint32_t RFF : 1; + uint32_t BSY : 1; + uint32_t reserved1 : 27; + }; + static_assert(sizeof(sspNsr_reg_t) == 4, "invalid size of LPC sspNsr_reg_t"); + + struct sspNcpsr_reg_t { + uint32_t CPSDVSR : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(sspNcpsr_reg_t) == 4, "invalid size of LPC sspNcpsr_reg_t"); + + struct sspNimsc_reg_t { + uint32_t RORIM : 1; + uint32_t RTIM : 1; + uint32_t RXIM : 1; + uint32_t TXIM : 1; + uint32_t reserved1 : 28; + }; + static_assert(sizeof(sspNimsc_reg_t) == 4, "invalid size of LPC sspNimsc_reg_t"); + + struct sspNris_reg_t { + uint32_t RORRIS : 1; + uint32_t RTRIS : 1; + uint32_t RXRIS : 1; + uint32_t TXRIS : 1; + uint32_t reserved1 : 28; + }; + static_assert(sizeof(sspNris_reg_t) == 4, "invalid size of LPC sspNris_reg_t"); + + struct sspNmis_reg_t { + uint32_t RORMIS : 1; + uint32_t RTMIS : 1; + uint32_t RXMIS : 1; + uint32_t TXMIS : 1; + uint32_t reserved1 : 28; + }; + static_assert(sizeof(sspNmis_reg_t) == 4, "invalid size of LPC sspNmis_reg_t"); + + struct sspNicr_reg_t { + uint32_t RORIC : 1; + uint32_t RTIC : 1; + uint32_t reserved1 : 30; + }; + static_assert(sizeof(sspNicr_reg_t) == 4, "invalid size of LPC sspNicr_reg_t"); + + struct sspNdmacr_reg_t { + uint32_t RXDMAE : 1; + uint32_t TXDMAE : 1; + uint32_t reserved1 : 30; + }; + static_assert(sizeof(sspNdmacr_reg_t) == 4, "invalid size of LPC sspNdmacr_reg_t"); + + struct ssp_dev_t { + sspNcr0_reg_t CR0; + sspNcr1_reg_t CR1; + sspNdr_reg_t DR; + sspNsr_reg_t SR; + sspNcpsr_reg_t CPSR; + sspNimsc_reg_t IMSC; + sspNris_reg_t RIS; + sspNmis_reg_t MIS; + sspNicr_reg_t ICR; + sspNdmacr_reg_t DMACR; + }; + static_assert(sizeof(ssp_dev_t) == 40, "invalid size of LPC ssp_dev_t"); + + static volatile ssp_dev_t &SSP0 = *(volatile ssp_dev_t*)0x40088000; + static volatile ssp_dev_t &SSP1 = *(volatile ssp_dev_t*)0x40030000; + + inline volatile ssp_dev_t &SPIGetBusFromIndex(uint8_t idx) { + if (idx == 0) return SSP0; + if (idx == 1) return SSP1; + return SSP0; // default + } + + inline uint8_t SPIGetBusIndex(volatile ssp_dev_t &SSP) { + if (&SSP == &SSP0) return 0; + if (&SSP == &SSP1) return 1; + return 0; // default + } + + #ifndef HALSPI_DISABLE_DMA + + struct DMACIntStat_reg_t { + uint32_t IntStat : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACIntStat_reg_t) == 4, "invalid size of LPC DMACIntStat_reg_t"); + + static DMACIntStat_reg_t &DMACIntStat = *(DMACIntStat_reg_t*)0x50004000; + + struct DMACIntTCStat_reg_t { + uint32_t IntTCStat : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACIntTCStat_reg_t) == 4, "invalid size of LPC DMACIntTCStat_reg_t"); + + static DMACIntTCStat_reg_t &DMACIntTCStat = *(DMACIntTCStat_reg_t*)0x50004004; + + struct DMACIntTCClear_reg_t { + uint32_t IntTCClear : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACIntTCClear_reg_t) == 4, "invalid size of LPC DMAIntTCClear_reg_t"); + + static DMACIntTCClear_reg_t &DMACIntTCClear = *(DMACIntTCClear_reg_t*)0x50004008; + + struct DMACIntErrStat_reg_t { + uint32_t IntErrStat : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACIntErrStat_reg_t) == 4, "invalid size of LPC DMACIntErrStat_reg_t"); + + static DMACIntErrStat_reg_t &DMACIntErrStat = *(DMACIntErrStat_reg_t*)0x5000400C; + + struct DMACIntErrClr_reg_t { + uint32_t IntErrClr : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACIntErrClr_reg_t) == 4, "invalid size of LPC DMACIntErrClr_reg_t"); + + static DMACIntErrClr_reg_t &DMACIntErrClr = *(DMACIntErrClr_reg_t*)0x50004010; + + struct DMACRawIntTCStat_reg_t { + uint32_t RawIntTCStat : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACRawIntTCStat_reg_t) == 4, "invalid size of LPC DMACRawIntTCStat_reg_t"); + + static DMACRawIntTCStat_reg_t &DMACRawIntTCStat = *(DMACRawIntTCStat_reg_t*)0x50004014; + + struct DMACRawIntErrStat_reg_t { + uint32_t RawIntErrStat : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACRawIntErrStat_reg_t) == 4, "invalid size of LPC DMACRawIntErrStat_reg_t"); + + static DMACRawIntErrStat_reg_t &DMACRawIntErrStat = *(DMACRawIntErrStat_reg_t*)0x50004018; + + struct DMACEnbldChns_reg_t { + uint32_t EnabledChannels : 8; + uint32_t reserved1 : 24; + }; + static_assert(sizeof(DMACEnbldChns_reg_t) == 4, "invalid size of LPC DMACEnbldChns_reg_t"); + + static DMACEnbldChns_reg_t &DMACEnbldChns = *(DMACEnbldChns_reg_t*)0x5000401C; + + struct DMACSoftBReq_reg_t { + uint32_t SoftBReq : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(DMACSoftBReq_reg_t) == 4, "invalid size of LPC DMACSoftBReq_reg_t"); + + static DMACSoftBReq_reg_t &DMACSoftBReq = *(DMACSoftBReq_reg_t*)0x50004020; + + struct DMACSoftSReq_reg_t { + uint32_t SoftSReq : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(DMACSoftSReq_reg_t) == 4, "invalid size of LPC DMACSoftSReq_reg_t"); + + static DMACSoftSReq_reg_t &DMACSoftSReq = *(DMACSoftSReq_reg_t*)0x50004024; + + struct DMACSoftLBReq_reg_t { + uint32_t SoftLBReq : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(DMACSoftLBReq_reg_t) == 4, "invalid size of LPC DMACSoftLBReq_reg_t"); + + static DMACSoftLBReq_reg_t &DMACSoftLBReq = *(DMACSoftLBReq_reg_t*)0x50004028; + + struct DMACSoftLSReq_reg_t { + uint32_t SoftLSReq : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(DMACSoftLSReq_reg_t) == 4, "invalid size of LPC DMACSoftLSReq_reg_t"); + + static DMACSoftLSReq_reg_t &DMACSoftLSReq = *(DMACSoftLSReq_reg_t*)0x5000402C; + + struct DMACConfig_reg_t { + uint32_t E : 1; + uint32_t M : 1; + uint32_t reserved1 : 30; + }; + static_assert(sizeof(DMACConfig_reg_t) == 4, "invalid size of LPC DMACConfig_reg_t"); + + static DMACConfig_reg_t &DMACConfig = *(DMACConfig_reg_t*)0x50004030; + + struct DMACSync_reg_t { + uint32_t DMACSync : 16; + uint32_t reserved1 : 16; + }; + static_assert(sizeof(DMACSync_reg_t) == 4, "invalid size of LPC DMACSync_reg_t"); + + static DMACSync_reg_t &DMACSync = *(DMACSync_reg_t*)0x50004034; + + struct DMAReqSel_reg_t { + uint32_t DMASEL08 : 1; + uint32_t DMASEL09 : 1; + uint32_t DMASEL10 : 1; + uint32_t DMASEL11 : 1; + uint32_t DMASEL12 : 1; + uint32_t DMASEL13 : 1; + uint32_t DMASEL14 : 1; + uint32_t DMASEL15 : 1; + uint32_t reserved : 24; + }; + static_assert(sizeof(DMAReqSel_reg_t) == 4, "invalid size of LPC DMAReqSel_reg_t"); + + static DMAReqSel_reg_t &DMAReqSel = *(DMAReqSel_reg_t*)0x400FC1C4; + + struct DMACCxLLI_reg_t { + uint32_t reserved1 : 2; + uint32_t LLI : 30; + }; + static_assert(sizeof(DMACCxLLI_reg_t) == 4, "invalid size of LPC DMACCxLLI_reg_t"); + + struct DMACCxControl_reg_t { + uint32_t TransferSize : 12; + uint32_t SBSize : 3; + uint32_t DBSize : 3; + uint32_t SWidth : 3; + uint32_t DWidth : 3; + uint32_t reserved1 : 2; + uint32_t SI : 1; + uint32_t DI : 1; + uint32_t Prot1 : 1; + uint32_t Prot2 : 1; + uint32_t Prot3 : 1; + uint32_t I : 1; + }; + static_assert(sizeof(DMACCxControl_reg_t) == 4, "invalid size of LPC DMACCxControl_reg_t"); + + struct DMACCxConfig_reg_t { + uint32_t E : 1; + uint32_t SrcPeripheral : 5; + uint32_t DestPeripheral : 5; + uint32_t TransferType : 3; + uint32_t IE : 1; + uint32_t ITC : 1; + uint32_t L : 1; + uint32_t A : 1; + uint32_t H : 1; + uint32_t reserved1 : 13; + }; + static_assert(sizeof(DMACCxConfig_reg_t) == 4, "invalid size of LPC DMACCxConfig_reg_t"); + + struct DMACChannel_dev_t { + uint32_t SrcAddr; + uint32_t DestAddr; + DMACCxLLI_reg_t LLI; + DMACCxControl_reg_t Control; + DMACCxConfig_reg_t Config; + }; + static_assert(sizeof(DMACChannel_dev_t) == 20, "invalid size of LPC DMACChannel_dev_t"); + + static DMACChannel_dev_t &DMACC0 = *(DMACChannel_dev_t*)0x50004100; + static DMACChannel_dev_t &DMACC1 = *(DMACChannel_dev_t*)0x50004120; + static DMACChannel_dev_t &DMACC2 = *(DMACChannel_dev_t*)0x50004140; + static DMACChannel_dev_t &DMACC3 = *(DMACChannel_dev_t*)0x50004160; + static DMACChannel_dev_t &DMACC4 = *(DMACChannel_dev_t*)0x50004180; + static DMACChannel_dev_t &DMACC5 = *(DMACChannel_dev_t*)0x500041A0; + static DMACChannel_dev_t &DMACC6 = *(DMACChannel_dev_t*)0x500041C0; + static DMACChannel_dev_t &DMACC7 = *(DMACChannel_dev_t*)0x500041E0; + + static DMACChannel_dev_t& DMAGetChannel(const uint32_t idx) { + switch (idx) { + case 0: return DMACC0; + case 1: return DMACC1; + case 2: return DMACC2; + case 3: return DMACC3; + case 4: return DMACC4; + case 5: return DMACC5; + case 6: return DMACC6; + case 7: return DMACC7; + } + return DMACC0; // default. } - last = freelli; - } - proc.curoff += takecnt; - } + static uint32_t __attribute__((unused)) DMAGetChannelIndex(DMACChannel_dev_t &DMACC) { + if (&DMACC == &DMACC0) return 0; + if (&DMACC == &DMACC1) return 1; + if (&DMACC == &DMACC2) return 2; + if (&DMACC == &DMACC3) return 3; + if (&DMACC == &DMACC4) return 4; + if (&DMACC == &DMACC5) return 5; + if (&DMACC == &DMACC6) return 6; + if (&DMACC == &DMACC7) return 7; + return 0; // default. + } - if (last) { - last->Control.I = true; - } - else { - DMACC.Control.I = true; - } + #ifdef HAL_SPI_SUPPORTS_ASYNC - proc.last_chain = first; -} + struct DMACCxLLI_desc_t { + uint32_t SrcAddr; + uint32_t DestAddr; + DMACCxLLI_desc_t *Next; + DMACCxControl_reg_t Control; + }; + static_assert(sizeof(DMACCxLLI_desc_t) == 16, "invalid size of LPC DMACCxLLI_desc_t"); -#endif //HAL_SPI_SUPPORTS_ASYNC + struct DMACCxLLI_desc_user_t : public DMACCxLLI_desc_t { + // User data by software. + bool available = true; + }; -#endif //HALSPI_DISABLE_DMA + #ifndef HALSPI_LPC_STATIC_DMADESCS + #define HALSPI_LPC_STATIC_DMADESCS 3 + #endif -} // namespace MarlinLPC + static DMACCxLLI_desc_user_t _available_dma_descs[HALSPI_LPC_STATIC_DMADESCS]; - // Hardware SPI + static DMACCxLLI_desc_user_t* DMAFindFreeChainLLI() { + for (auto &item : _available_dma_descs) + if (item.available) return &item; + return nullptr; + } -#ifndef HALSPI_LOOPBEEP_TIMEOUT -#define HALSPI_LOOPBEEP_TIMEOUT 3000 -#endif - - struct spi_monitored_loop - { - private: -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - uint32_t _start_millis; -#endif - public: - inline spi_monitored_loop() { -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - _start_millis = millis(); -#endif - } - inline void update(unsigned int beep_code) { -#if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) - if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; - OUT_WRITE(BEEPER_PIN, HIGH); - delay(500); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(1000); - for (unsigned int n = 0; n < beep_code; n++) { - OUT_WRITE(BEEPER_PIN, HIGH); - delay(200); - OUT_WRITE(BEEPER_PIN, LOW); - delay(200); + struct dma_process_t { + DMACChannel_dev_t *current_DMACC; + const void *current_buffer; + size_t curoff; + size_t txlen; + uint8_t txunitsize; + void (*completeCallback)(void*); + void *complete_ud; + DMACCxLLI_desc_user_t *last_chain; + bool is_active = false; + }; + + static dma_process_t _dma_async_proc; + + static void DMAProgramSSPChain(volatile ssp_dev_t &SSP, dma_process_t &proc) { + DMACCxLLI_desc_user_t *first = nullptr; + DMACCxLLI_desc_user_t *last = nullptr; + + uint32_t txwidth = 0; + + if (proc.txunitsize == 1) txwidth = 0; + else if (proc.txunitsize == 2) txwidth = 1; + else if (proc.txunitsize == 4) txwidth = 2; + else _spi_on_error(4); + + DMACCxControl_reg_t Control; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.SI = true; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 1; + Control.I = false; + + bool init_ch_prog = false; + + auto &DMACC = *proc.current_DMACC; + DMACC.Config.ITC = true; + + while (proc.curoff < proc.txlen) { + size_t left = (proc.txlen - proc.curoff); + size_t takecnt = (uint32_t)__MIN (left, (1<<12)-1); + + Control.TransferSize = takecnt; + + uint32_t SrcAddr = ( (uint32_t)proc.current_buffer + proc.curoff * proc.txunitsize ); + uint32_t DestAddr = (uint32_t)&SSP.DR; + + if (!init_ch_prog) { + // We first have to program the channel itself. + DMACC.SrcAddr = SrcAddr; + DMACC.DestAddr = DestAddr; + DMACC.LLI.LLI = 0; + DMACC.Control = Control; + init_ch_prog = true; + } + else { + auto *freelli = DMAFindFreeChainLLI(); + + if (freelli == nullptr) break; + + freelli->SrcAddr = SrcAddr; + freelli->DestAddr = DestAddr; + freelli->Next = nullptr; + freelli->Control = Control; + freelli->available = false; + + if (first == nullptr) { + first = freelli; + DMACC.LLI.LLI = ( (uint32_t)freelli >> 2 ); + } + + if (last) last->Next = freelli; + last = freelli; + } + + proc.curoff += takecnt; + } + + if (last) last->Control.I = true; + else DMACC.Control.I = true; + + proc.last_chain = first; + } + + #endif // HAL_SPI_SUPPORTS_ASYNC + + #endif // !HALSPI_DISABLE_DMA + + } // namespace MarlinLPC + + #ifndef HALSPI_LOOPBEEP_TIMEOUT + #define HALSPI_LOOPBEEP_TIMEOUT 3000 + #endif + + struct spi_monitored_loop { + private: + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + uint32_t _start_millis; + #endif + public: + void spi_monitored_loop() { + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + _start_millis = millis(); + #endif + } + void update(unsigned int beep_code) { + #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) + if ((millis() - _start_millis) <= HALSPI_LOOPBEEP_TIMEOUT) return; + OUT_WRITE(BEEPER_PIN, HIGH); delay(500); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(1000); + for (unsigned int n = 0; n < beep_code; n++) { + OUT_WRITE(BEEPER_PIN, HIGH); delay(200); + OUT_WRITE(BEEPER_PIN, LOW); delay(200); + } + delay(800); + OUT_WRITE(BEEPER_PIN, HIGH); delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); delay(2000); + #endif } - delay(800); - OUT_WRITE(BEEPER_PIN, HIGH); - delay(1000); - OUT_WRITE(BEEPER_PIN, LOW); - delay(2000); -#endif - } }; static MarlinLPC::gpioMapResult_t _ssp_gpioMap; @@ -1429,30 +1393,30 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { static volatile uint8_t _ssp_framesize; static volatile bool _ssp_dirty_rxbuffer; -#ifdef HAL_SPI_SUPPORTS_ASYNC - - struct ssp_process_t { - volatile MarlinLPC::ssp_dev_t *current_ssp; - const void *current_buffer; - size_t curoff_bytes; - size_t txlen_bytes; - uint8_t txunitsize; - bool is_active = false; - void (*completeCallback)(void*); - void *complete_ud; - }; + #ifdef HAL_SPI_SUPPORTS_ASYNC + + struct ssp_process_t { + volatile MarlinLPC::ssp_dev_t *current_ssp; + const void *current_buffer; + size_t curoff_bytes; + size_t txlen_bytes; + uint8_t txunitsize; + bool is_active = false; + void (*completeCallback)(void*); + void *complete_ud; + }; - static ssp_process_t _ssp_async_proc; + static ssp_process_t _ssp_async_proc; -#endif //HAL_SPI_SUPPORTS_ASYNC + #endif // HAL_SPI_SUPPORTS_ASYNC static void _spiAsyncBarrier() { -#ifdef HAL_SPI_SUPPORTS_ASYNC - while (_ssp_async_proc.is_active) { /* wait until completion of any async SPI TX */ } -#ifndef HALSPI_DISABLE_DMA - while (MarlinLPC::_dma_async_proc.is_active) { /* wait until completion of any async DMA TX */ } -#endif -#endif + #ifdef HAL_SPI_SUPPORTS_ASYNC + while (_ssp_async_proc.is_active) { /* wait for any async SPI TX to finish */ } + #ifndef HALSPI_DISABLE_DMA + while (MarlinLPC::_dma_async_proc.is_active) { /* wait for any async DMA TX to finish */ } + #endif + #endif } void spiBegin() { @@ -1471,7 +1435,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { OUT_WRITE(pin, HIGH); } - static void _spiConfigClock(volatile MarlinLPC::ssp_dev_t& SSP, int clockMode) { + static void _spiConfigClock(volatile MarlinLPC::ssp_dev_t &SSP, int clockMode) { if (clockMode == SPI_CLKMODE_0) { SSP.CR0.CPOL = false; SSP.CR0.CPHA = false; @@ -1492,12 +1456,11 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { } void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { -#ifdef HAL_SPI_SUPPORTS_ASYNC - while (_ssp_is_active) { /* wait until completion of any other SPI activity */ } -#else - if (_ssp_is_active) - _spi_on_error(1); -#endif + #ifdef HAL_SPI_SUPPORTS_ASYNC + while (_ssp_is_active) { /* wait for any other SPI activity to finish */ } + #else + if (_ssp_is_active) _spi_on_error(1); + #endif _ssp_gpioMap = MarlinLPC::SPIMapGPIO(hint_sck, hint_miso, hint_mosi, -1); _ssp_is_active = true; @@ -1506,7 +1469,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { MarlinLPC::sspClockResult_t clockRes = MarlinLPC::SPICalculateClock(maxClockFreq); uint8_t sspBusIdx = _ssp_gpioMap.sspBusIdx; - auto& SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); if (sspBusIdx == 0) { MarlinLPC::PCONP.PCSSP0 = true; @@ -1548,7 +1511,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { } static void _spiStart() { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); SSP.CR1.SSE = true; if (_ssp_cs_pin >= 0) { MarlinLPC::MapPortPinFunc(_ssp_cs_pin, 0); // make sure that the CS pin is configured as GPIO. @@ -1556,27 +1519,24 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { } } static void _spiEnd() { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); spi_monitored_loop tfew; - while (SSP.SR.TFE == false) { tfew.update(1); /* wait until all items from the TX queue were pushed */ } + while (!SSP.SR.TFE) { tfew.update(1); /* wait until all items from the TX queue were pushed */ } spi_monitored_loop bsyw; while (SSP.SR.BSY) { bsyw.update(2); /* wait until the current data transfer has finished (clean shutdown) */ } - if (_ssp_cs_pin >= 0) { - OUT_WRITE(_ssp_cs_pin, HIGH); - } + if (_ssp_cs_pin >= 0) OUT_WRITE(_ssp_cs_pin, HIGH); SSP.CR1.SSE = false; } static void _maybe_start_transaction() { - if (_ssp_transaction_is_running == false) { + if (!_ssp_transaction_is_running) { _spiStart(); _ssp_transaction_is_running = true; } } void spiClose() { - if (_ssp_is_active == false) - _spi_on_error(2); + if (!_ssp_is_active) _spi_on_error(2); _spiAsyncBarrier(); @@ -1587,12 +1547,10 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _ssp_transaction_is_running = false; } - if (sspBusIdx == 0) { + if (sspBusIdx == 0) MarlinLPC::PCONP.PCSSP0 = false; - } - else if (sspBusIdx == 1) { + else if (sspBusIdx == 1) MarlinLPC::PCONP.PCSSP1 = false; - } MarlinLPC::SPIUnmapGPIO(_ssp_gpioMap); @@ -1602,58 +1560,37 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { void spiSetBitOrder(int bitOrder) { if (_ssp_bitOrder != bitOrder) { _spiAsyncBarrier(); - - if (_ssp_transaction_is_running) { - _spiEnd(); - } - + if (_ssp_transaction_is_running) _spiEnd(); _ssp_bitOrder = bitOrder; - - if (_ssp_transaction_is_running) { - _spiStart(); - } + if (_ssp_transaction_is_running) _spiStart(); } } void spiSetClockMode(int clockMode) { if (_ssp_clockMode != clockMode) { _spiAsyncBarrier(); - - if (_ssp_transaction_is_running) { - _spiEnd(); - } - - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - + if (_ssp_transaction_is_running) _spiEnd(); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spiConfigClock(SSP, clockMode); - - if (_ssp_transaction_is_running) { - _spiStart(); - } + if (_ssp_transaction_is_running) _spiStart(); } } - void spiEstablish() { - _maybe_start_transaction(); - } + void spiEstablish() { _maybe_start_transaction(); } // Internal. inline void _spiSetFrameSize(uint8_t fsize) { if (_ssp_framesize != fsize) { _spiAsyncBarrier(); - if (_ssp_transaction_is_running) { - _spiEnd(); - } + if (_ssp_transaction_is_running) _spiEnd(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); SSP.CR0.DSS = (fsize * 8)-1; _ssp_framesize = fsize; - if (_ssp_transaction_is_running) { - _spiStart(); - } + if (_ssp_transaction_is_running) _spiStart(); } } @@ -1661,8 +1598,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { template inline numberType _flip_bits(numberType v) { numberType result = 0; - for (unsigned int n = 0; n < (sizeof(numberType)*8); n++) - { + for (unsigned int n = 0; n < sizeof(numberType) * 8; n++) { result <<= 1; bool bitval = ( v & (1< - inline void _spi_push_to_queue(volatile MarlinLPC::ssp_dev_t& SSP, numberType val) { + inline void _spi_push_to_queue(volatile MarlinLPC::ssp_dev_t &SSP, numberType val) { bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); if (_ssp_framesize == 1) { // Push it byte-by-byte (DSS = 7). @@ -1680,34 +1616,24 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); for (uint32_t n = 0; n < num_bytes; n++) { - uint32_t byte_idx; - - if (revbytes) { - byte_idx = (num_bytes-1) - n; - } - else { - byte_idx = 0; - } + uint32_t = revbytes ? (num_bytes - 1) - n : 0; uint32_t bitidx = byte_idx * 8; spi_monitored_loop tnfw; - while (SSP.SR.TNF == false) { tnfw.update(3); /* wait for space on the TX FIFO */ } + while (!SSP.SR.TNF) { tnfw.update(3); /* wait for space on the TX FIFO */ } uint8_t byteval = (val >> bitidx) & 0xFF; - if (revbits) - byteval = _flip_bits(byteval); + if (revbits) byteval = _flip_bits(byteval); SSP.DR.DATA = byteval; } } else if (_ssp_framesize == 2) { spi_monitored_loop tnfw; - while (SSP.SR.TNF == false) { tnfw.update(3); /* wait for space om´n the TX FIFO */ } + while (!SSP.SR.TNF) { tnfw.update(3); /* wait for space om´n the TX FIFO */ } - if (revbits) { - val = _flip_bits(val); - } + if (revbits) val = _flip_bits(val); // The number size must match the framesize. SSP.DR.DATA = val; @@ -1723,7 +1649,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_push_to_queue(SSP, val); @@ -1740,7 +1666,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_push_to_queue(SSP, val); @@ -1748,11 +1674,11 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _ssp_dirty_rxbuffer = true; } - static void _spi_flush_rxqueue(volatile MarlinLPC::ssp_dev_t& SSP) { - if (_ssp_dirty_rxbuffer == false) return; + static void _spi_flush_rxqueue(volatile MarlinLPC::ssp_dev_t &SSP) { + if (!_ssp_dirty_rxbuffer) return; spi_monitored_loop tfew; - while (SSP.SR.TFE == false) { tfew.update(4); /* wait until any tx data has been acquired that is still left */ } + while (!SSP.SR.TFE) { tfew.update(4); /* wait until any tx data has been acquired that is still left */ } spi_monitored_loop bsyw; while (SSP.SR.BSY) { bsyw.update(5); /* wait until transfers and their parallel receives have finished */ } spi_monitored_loop rnew; @@ -1765,7 +1691,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { } template - inline numberType _spi_fetch_from_queue(volatile MarlinLPC::ssp_dev_t& SSP) { + inline numberType _spi_fetch_from_queue(volatile MarlinLPC::ssp_dev_t &SSP) { numberType result = 0; bool revbits = (_ssp_bitOrder == SPI_BITORDER_MSB); @@ -1776,37 +1702,26 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { bool revbytes = (_ssp_bitOrder == SPI_BITORDER_LSB); for (uint32_t n = 0; n < num_bytes; n++) { - uint32_t byte_idx; - - if (revbytes) { - byte_idx = (num_bytes-1) - n; - } - else { - byte_idx = n; - } + uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : 0; uint32_t bitidx = byte_idx * 8; spi_monitored_loop rnew; - while (SSP.SR.RNE == false) { rnew.update(7); /* wait until we have received any data */ } + while (!SSP.SR.RNE) { rnew.update(7); /* wait for any data */ } uint8_t byteval = SSP.DR.DATA & 0xFF; - if (revbits) { - byteval = _flip_bits(byteval); - } + if (revbits) byteval = _flip_bits(byteval); result |= ( (numberType)byteval << bitidx ); } } else if (_ssp_framesize == 2) { spi_monitored_loop rnew; - while (SSP.SR.RNE == false) { rnew.update(7); /* wait until we have received any data */ } + while (!SSP.SR.RNE) { rnew.update(7); /* wait for any data */ } result = SSP.DR.DATA; - if (revbits) { - result = _flip_bits(result); - } + if (revbits) result = _flip_bits(result); } return result; } @@ -1823,7 +1738,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_flush_rxqueue(SSP); @@ -1841,7 +1756,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_flush_rxqueue(SSP); @@ -1863,7 +1778,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_flush_rxqueue(SSP); @@ -1882,7 +1797,7 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _spiAsyncBarrier(); - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); _spi_push_to_queue(SSP, token); @@ -1893,150 +1808,134 @@ static void DMAProgramSSPChain(volatile ssp_dev_t& SSP, dma_process_t& proc) { _ssp_dirty_rxbuffer = true; } -#ifndef HALSPI_DISABLE_DMA + #ifndef HALSPI_DISABLE_DMA -static void _dmaStart() { - MarlinLPC::PCONP.PCGPDMA = true; - MarlinLPC::DMACConfig.E = true; - MarlinLPC::DMACConfig.M = 0; -} + static void _dmaStart() { + MarlinLPC::PCONP.PCGPDMA = true; + MarlinLPC::DMACConfig.E = true; + MarlinLPC::DMACConfig.M = 0; + } -static void _dmaEnd() { - MarlinLPC::DMACConfig.E = false; - MarlinLPC::PCONP.PCGPDMA = false; -} + static void _dmaEnd() { + MarlinLPC::DMACConfig.E = false; + MarlinLPC::PCONP.PCGPDMA = false; + } -static void _dmacInitSSP(MarlinLPC::DMACChannel_dev_t& DMACC, uint8_t sspBusIdx) { - if (sspBusIdx == 0) { - DMACC.Config.DestPeripheral = 0; - } - else if (sspBusIdx == 1) { - DMACC.Config.DestPeripheral = 2; - } - DMACC.Config.TransferType = 1; // memory to peripheral - DMACC.Config.IE = false; - DMACC.Config.ITC = false; - DMACC.Config.L = false; - DMACC.Config.H = false; -} + static void _dmacInitSSP(MarlinLPC::DMACChannel_dev_t &DMACC, uint8_t sspBusIdx) { + if (sspBusIdx == 0) + DMACC.Config.DestPeripheral = 0; + else if (sspBusIdx == 1) + DMACC.Config.DestPeripheral = 2; + DMACC.Config.TransferType = 1; // memory to peripheral + DMACC.Config.IE = false; + DMACC.Config.ITC = false; + DMACC.Config.L = false; + DMACC.Config.H = false; + } -template -inline void _dmaSendBlocking(const numberType *buf, uint32_t cnt) { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + template + inline void _dmaSendBlocking(const numberType *buf, uint32_t cnt) { + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - uint32_t txwidth = 0; + uint32_t txwidth = 0; - if (sizeof(numberType) == 1) { - txwidth = 0; - } - else if (sizeof(numberType) == 2) { - txwidth = 1; - } - else if (sizeof(numberType) == 4) { - txwidth = 2; - } - else - _spi_on_error(5); - - auto& DMACC = MarlinLPC::DMAGetChannel(0); - DMACC.DestAddr = (uint32_t)&SSP.DR; - DMACC.LLI.LLI = 0; - _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); - - size_t curoff = 0; - - while (curoff < cnt) { - uint32_t left = (cnt - curoff); - uint32_t takecnt = __MIN (left, (1<<12)-1); - - MarlinLPC::DMACCxControl_reg_t Control; - Control.TransferSize = takecnt; - Control.SBSize = 0; - Control.DBSize = 0; - Control.SWidth = txwidth; - Control.DWidth = txwidth; - Control.reserved1 = 0; - Control.SI = true; - Control.DI = false; - Control.Prot1 = 1; - Control.Prot2 = 0; - Control.Prot3 = 0; - Control.I = false; - - DMACC.SrcAddr = (uint32_t)( buf + curoff ); - DMACC.Control = Control; - - curoff += takecnt; - - // Kick off the DMA. - DMACC.Config.E = true; - while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } - } + if (sizeof(numberType) == 1) txwidth = 0; + else if (sizeof(numberType) == 2) txwidth = 1; + else if (sizeof(numberType) == 4) txwidth = 2; + else _spi_on_error(5); + + auto &DMACC = MarlinLPC::DMAGetChannel(0); + DMACC.DestAddr = (uint32_t)&SSP.DR; + DMACC.LLI.LLI = 0; + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + + size_t curoff = 0; + + while (curoff < cnt) { + uint32_t left = (cnt - curoff); + uint32_t takecnt = __MIN (left, (1<<12)-1); + + MarlinLPC::DMACCxControl_reg_t Control; + Control.TransferSize = takecnt; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.reserved1 = 0; + Control.SI = true; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 0; + Control.I = false; + + DMACC.SrcAddr = (uint32_t)( buf + curoff ); + DMACC.Control = Control; + + curoff += takecnt; + + // Kick off the DMA. + DMACC.Config.E = true; + while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + } - _ssp_dirty_rxbuffer = true; -} + _ssp_dirty_rxbuffer = true; + } -template -static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + template + static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - uint32_t txwidth = 0; + uint32_t txwidth = 0; - if (sizeof(numberType) == 1) { - txwidth = 0; - } - else if (sizeof(numberType) == 2) { - txwidth = 1; - } - else if (sizeof(numberType) == 4) { - txwidth = 2; - } - else - _spi_on_error(5); - - auto& DMACC = MarlinLPC::DMAGetChannel(0); - DMACC.SrcAddr = (uint32_t)&val; - DMACC.DestAddr = (uint32_t)&SSP.DR; - DMACC.LLI.LLI = 0; - _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); - - size_t curoff = 0; - - while (curoff < repcnt) { - uint32_t left = (repcnt - curoff); - uint32_t takecnt = __MIN (left, (1<<12)-1); - - MarlinLPC::DMACCxControl_reg_t Control; - Control.TransferSize = takecnt; - Control.SBSize = 0; - Control.DBSize = 0; - Control.SWidth = txwidth; - Control.DWidth = txwidth; - Control.reserved1 = 0; - Control.SI = false; - Control.DI = false; - Control.Prot1 = 1; - Control.Prot2 = 0; - Control.Prot3 = 0; - Control.I = false; - - DMACC.Control = Control; - - curoff += takecnt; - - // Kick off the DMA. - DMACC.Config.E = true; - while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } - } + if (sizeof(numberType) == 1) txwidth = 0; + else if (sizeof(numberType) == 2) txwidth = 1; + else if (sizeof(numberType) == 4) txwidth = 2; + else _spi_on_error(5); + + auto &DMACC = MarlinLPC::DMAGetChannel(0); + DMACC.SrcAddr = (uint32_t)&val; + DMACC.DestAddr = (uint32_t)&SSP.DR; + DMACC.LLI.LLI = 0; + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + + size_t curoff = 0; + + while (curoff < repcnt) { + uint32_t left = (repcnt - curoff); + uint32_t takecnt = __MIN (left, (1<<12)-1); + + MarlinLPC::DMACCxControl_reg_t Control; + Control.TransferSize = takecnt; + Control.SBSize = 0; + Control.DBSize = 0; + Control.SWidth = txwidth; + Control.DWidth = txwidth; + Control.reserved1 = 0; + Control.SI = false; + Control.DI = false; + Control.Prot1 = 1; + Control.Prot2 = 0; + Control.Prot3 = 0; + Control.I = false; + + DMACC.Control = Control; + + curoff += takecnt; + + // Kick off the DMA. + DMACC.Config.E = true; + while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + } - _ssp_dirty_rxbuffer = true; -} + _ssp_dirty_rxbuffer = true; + } -#endif + #endif // !HALSPI_DISABLE_DMA -#ifndef HALSPI_DMA_THRESHOLD -#define HALSPI_DMA_THRESHOLD 32 -#endif + #ifndef HALSPI_DMA_THRESHOLD + #define HALSPI_DMA_THRESHOLD 32 + #endif // !HALSPI_DMA_THRESHOLD void spiWrite(const uint8_t *buf, uint16_t cnt) { if (cnt == 0) return; @@ -2048,20 +1947,18 @@ static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { _spiAsyncBarrier(); -#ifndef HALSPI_DISABLE_DMA - if (cnt > HALSPI_DMA_THRESHOLD) { - _dmaStart(); - _dmaSendBlocking(buf, cnt); - _dmaEnd(); - return; - } -#endif + #ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendBlocking(buf, cnt); + _dmaEnd(); + return; + } + #endif - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - for (uint16_t n = 0; n < cnt; n++) { - _spi_push_to_queue(SSP, buf[n]); - } + for (uint16_t n = 0; n < cnt; n++) _spi_push_to_queue(SSP, buf[n]); _ssp_dirty_rxbuffer = true; } @@ -2076,20 +1973,18 @@ static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { _spiAsyncBarrier(); -#ifndef HALSPI_DISABLE_DMA - if (cnt > HALSPI_DMA_THRESHOLD) { - _dmaStart(); - _dmaSendBlocking(buf, cnt); - _dmaEnd(); - return; - } -#endif + #ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendBlocking(buf, cnt); + _dmaEnd(); + return; + } + #endif - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - for (uint16_t n = 0; n < cnt; n++) { - _spi_push_to_queue(SSP, buf[n]); - } + for (uint16_t n = 0; n < cnt; n++) _spi_push_to_queue(SSP, buf[n]); _ssp_dirty_rxbuffer = true; } @@ -2104,20 +1999,18 @@ static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { _spiAsyncBarrier(); -#ifndef HALSPI_DISABLE_DMA - if (repcnt > HALSPI_DMA_THRESHOLD) { - _dmaStart(); - _dmaSendRepeatBlocking(val, repcnt); - _dmaEnd(); - return; - } -#endif + #ifndef HALSPI_DISABLE_DMA + if (repcnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendRepeatBlocking(val, repcnt); + _dmaEnd(); + return; + } + #endif - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - for (uint16_t n = 0; n < repcnt; n++) { - _spi_push_to_queue(SSP, val); - } + for (uint16_t n = 0; n < repcnt; n++) _spi_push_to_queue(SSP, val); _ssp_dirty_rxbuffer = true; } @@ -2132,437 +2025,431 @@ static void _dmaSendRepeatBlocking(numberType val, uint32_t repcnt) { _spiAsyncBarrier(); -#ifndef HALSPI_DISABLE_DMA - if (repcnt > HALSPI_DMA_THRESHOLD) { - _dmaStart(); - _dmaSendRepeatBlocking(val, repcnt); - _dmaEnd(); - return; - } -#endif + #ifndef HALSPI_DISABLE_DMA + if (repcnt > HALSPI_DMA_THRESHOLD) { + _dmaStart(); + _dmaSendRepeatBlocking(val, repcnt); + _dmaEnd(); + return; + } + #endif - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - for (uint16_t n = 0; n < repcnt; n++) { - _spi_push_to_queue(SSP, val); - } + for (uint16_t n = 0; n < repcnt; n++) _spi_push_to_queue(SSP, val); _ssp_dirty_rxbuffer = true; } -#ifdef HAL_SPI_SUPPORTS_ASYNC + #ifdef HAL_SPI_SUPPORTS_ASYNC -#ifndef HALSPI_DISABLE_DMA + #ifndef HALSPI_DISABLE_DMA -static void _dmaUninstallInterrupt(); + static void _dmaUninstallInterrupt(); -static void _dmacAdvance(MarlinLPC::dma_process_t& proc) { - // If there is any last chain that was used then clear it. - if (auto *last_chain = proc.last_chain) { - MarlinLPC::DMACCxLLI_desc_user_t *iter = last_chain; + static void _dmacAdvance(MarlinLPC::dma_process_t &proc) { + // If there is any last chain that was used then clear it. + if (auto *last_chain = proc.last_chain) { + MarlinLPC::DMACCxLLI_desc_user_t *iter = last_chain; - while (iter) { - iter->available = true; - iter = (MarlinLPC::DMACCxLLI_desc_user_t*)iter->Next; - } - proc.last_chain = nullptr; - } + while (iter) { + iter->available = true; + iter = (MarlinLPC::DMACCxLLI_desc_user_t*)iter->Next; + } + proc.last_chain = nullptr; + } - auto& DMACC = *proc.current_DMACC; + auto &DMACC = *proc.current_DMACC; - if (proc.curoff == proc.txlen) { - // Disable the terminal count interrupt. - DMACC.Control.I = false; - DMACC.Config.ITC = false; + if (proc.curoff == proc.txlen) { + // Disable the terminal count interrupt. + DMACC.Control.I = false; + DMACC.Config.ITC = false; - _dmaUninstallInterrupt(); - _dmaEnd(); + _dmaUninstallInterrupt(); + _dmaEnd(); - auto completeCallback = proc.completeCallback; - void *complete_ud = proc.complete_ud; + auto completeCallback = proc.completeCallback; + void *complete_ud = proc.complete_ud; - // Finished. - proc.current_DMACC = nullptr; - proc.current_buffer = nullptr; - proc.curoff = 0; - proc.txlen = 0; - proc.txunitsize = 0; - proc.completeCallback = nullptr; - proc.complete_ud = nullptr; - proc.is_active = false; + // Finished. + proc.current_DMACC = nullptr; + proc.current_buffer = nullptr; + proc.curoff = 0; + proc.txlen = 0; + proc.txunitsize = 0; + proc.completeCallback = nullptr; + proc.complete_ud = nullptr; + proc.is_active = false; - if (completeCallback) { - completeCallback(complete_ud); - } - return; - } + if (completeCallback) { + completeCallback(complete_ud); + } + return; + } - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - MarlinLPC::DMAProgramSSPChain(SSP, proc); + MarlinLPC::DMAProgramSSPChain(SSP, proc); - // Kick-off another async TX. - DMACC.Config.E = true; -} + // Kick-off another async TX. + DMACC.Config.E = true; + } -static void _dma_interrupt() { - for (uint8_t n = 0; n < 8; n++) { - uint32_t chmask = (1< -inline void _dmaSendAsync(const numberType *buf, uint32_t cnt, void (*completeCallback)(void*), void *ud) { - auto& DMACC = MarlinLPC::DMAGetChannel(0); - - auto& proc = MarlinLPC::_dma_async_proc; - proc.current_DMACC = &DMACC; - proc.current_buffer = buf; - proc.curoff = 0; - proc.txlen = cnt; - proc.txunitsize = sizeof(numberType); - proc.completeCallback = completeCallback; - proc.complete_ud = ud; - proc.is_active = true; - - _dmaStart(); - MarlinLPC::DMACIntTCClear.IntTCClear |= (1<<0); - _dmaInstallInterrupt(); - _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); - _dmacAdvance(proc); -} - -#endif - -#include "../shared/SPI/bufmgmt.h" - - static void _spiDisableInterrupt(uint8_t sspBusIdx); - - template - inline void _spi_interrupt( void ) { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); - - ssp_process_t& proc = _ssp_async_proc; - - if (proc.is_active == false || proc.current_ssp != &SSP) - _spi_on_error(3); - - using namespace ::bufmgmt; - - // Check interrupt type. - if (SSP.MIS.TXMIS) { - bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); - bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); - uint8_t txunitsize = proc.txunitsize; - size_t txmax = proc.txlen_bytes; - const void *current_buffer = proc.current_buffer; - uint8_t framesize = _ssp_framesize; - - uint32_t curoff_bytes = proc.curoff_bytes; - - // Write as much data as possible. - while (SSP.SR.TNF) { - bool has_more_data = false; - - if (framesize == 1) { - uint8_t byteval; - if (txunitsize == 1) { - if (curoff_bytes < txmax) { - const uint8_t *buf = (const uint8_t*)current_buffer; - byteval = GetByteFromNumber( - buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], - GetLocalByteIndexFromTotalByteIndex (curoff_bytes), - !revbytes - ); - has_more_data = true; - } - } - else if (txunitsize == 2) { - if (curoff_bytes < txmax) { - const uint16_t *buf = (const uint16_t*)current_buffer; - byteval = GetByteFromNumber( - buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], - GetLocalByteIndexFromTotalByteIndex (curoff_bytes), - !revbytes - ); - has_more_data = true; - } - } + static void _dmaInstallInterrupt() { + nvicSetIRQHandler((IRQn_Type)26, _dma_interrupt); + nvicInstallRedirect(); + NVIC_EnableIRQ((IRQn_Type)26); + NVIC_SetPriority((IRQn_Type)26, 5); + } - if (has_more_data) { - if (revbits) { - byteval = _flip_bits(byteval); - } + static void _dmaUninstallInterrupt() { + NVIC_SetPriority((IRQn_Type)26, 255); + NVIC_DisableIRQ((IRQn_Type)26); + nvicUninstallRedirect(); + nvicResetIRQHandler((IRQn_Type)26); + } - // Push the data onto the (not-full) queue, byte-by-byte (DSS = 7). - SSP.DR.DATA = byteval; + template + inline void _dmaSendAsync(const numberType *buf, uint32_t cnt, void (*completeCallback)(void*), void *ud) { + auto &DMACC = MarlinLPC::DMAGetChannel(0); + + auto &proc = MarlinLPC::_dma_async_proc; + proc.current_DMACC = &DMACC; + proc.current_buffer = buf; + proc.curoff = 0; + proc.txlen = cnt; + proc.txunitsize = sizeof(numberType); + proc.completeCallback = completeCallback; + proc.complete_ud = ud; + proc.is_active = true; + + _dmaStart(); + MarlinLPC::DMACIntTCClear.IntTCClear |= (1<<0); + _dmaInstallInterrupt(); + _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + _dmacAdvance(proc); + } - curoff_bytes += sizeof(uint8_t); - } - } - else if (framesize == 2) { - uint16_t val; - if (txunitsize == 2) { - if (curoff_bytes < txmax) { - const uint16_t *buf = (const uint16_t*)current_buffer; - val = buf[ curoff_bytes / sizeof(uint16_t) ]; - has_more_data = true; - } - } + #endif // !HALSPI_DISABLE_DMA - if (has_more_data) { - if (revbits) { - val = _flip_bits(val); + #include "../shared/SPI/bufmgmt.h" + + static void _spiDisableInterrupt(uint8_t sspBusIdx); + + template + inline void _spi_interrupt( void ) { + auto &SSP = MarlinLPC::SPIGetBusFromIndex(sspBusIdx); + + ssp_process_t &proc = _ssp_async_proc; + + if (!proc.is_active || proc.current_ssp != &SSP) + _spi_on_error(3); + + using namespace ::bufmgmt; + + // Check interrupt type. + if (SSP.MIS.TXMIS) { + bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); + bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); + + uint8_t txunitsize = proc.txunitsize; + size_t txmax = proc.txlen_bytes; + const void *current_buffer = proc.current_buffer; + uint8_t framesize = _ssp_framesize; + + uint32_t curoff_bytes = proc.curoff_bytes; + + // Write as much data as possible. + while (SSP.SR.TNF) { + bool has_more_data = false; + + if (framesize == 1) { + uint8_t byteval; + if (txunitsize == 1) { + if (curoff_bytes < txmax) { + const uint8_t *buf = (const uint8_t*)current_buffer; + byteval = GetByteFromNumber( + buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], + GetLocalByteIndexFromTotalByteIndex (curoff_bytes), + !revbytes + ); + has_more_data = true; + } + } + else if (txunitsize == 2) { + if (curoff_bytes < txmax) { + const uint16_t *buf = (const uint16_t*)current_buffer; + byteval = GetByteFromNumber( + buf[ GetNumberIndexFromTotalByteIndex (curoff_bytes) ], + GetLocalByteIndexFromTotalByteIndex (curoff_bytes), + !revbytes + ); + has_more_data = true; + } } - SSP.DR.DATA = val; + if (has_more_data) { + if (revbits) { + byteval = _flip_bits(byteval); + } - curoff_bytes += sizeof(uint16_t); - } - } + // Push the data onto the (not-full) queue, byte-by-byte (DSS = 7). + SSP.DR.DATA = byteval; - if (has_more_data) { - // We are ignoring the reception part. - _ssp_dirty_rxbuffer = true; - } - else { - // Disable the interrupt. - _spiDisableInterrupt(sspBusIdx); + curoff_bytes += sizeof(uint8_t); + } + } + else if (framesize == 2) { + uint16_t val; + if (txunitsize == 2) { + if (curoff_bytes < txmax) { + const uint16_t *buf = (const uint16_t*)current_buffer; + val = buf[ curoff_bytes / sizeof(uint16_t) ]; + has_more_data = true; + } + } - SSP.IMSC.TXIM = false; + if (has_more_data) { + if (revbits) { + val = _flip_bits(val); + } - auto completeCallback = proc.completeCallback; - auto complete_ud = proc.complete_ud; + SSP.DR.DATA = val; - // We have finished the transfer, thus dismantle. - proc.current_ssp = nullptr; - proc.current_buffer = nullptr; - proc.curoff_bytes = 0; - proc.txlen_bytes = 0; - proc.txunitsize = 0; - proc.completeCallback = nullptr; - proc.complete_ud = nullptr; - proc.is_active = false; + curoff_bytes += sizeof(uint16_t); + } + } - // Call any completion routine. - if (completeCallback) { - completeCallback(complete_ud); + if (has_more_data) { + // We are ignoring the reception part. + _ssp_dirty_rxbuffer = true; } + else { + // Disable the interrupt. + _spiDisableInterrupt(sspBusIdx); + + SSP.IMSC.TXIM = false; + + auto completeCallback = proc.completeCallback; + auto complete_ud = proc.complete_ud; + + // We have finished the transfer, thus dismantle. + proc.current_ssp = nullptr; + proc.current_buffer = nullptr; + proc.curoff_bytes = 0; + proc.txlen_bytes = 0; + proc.txunitsize = 0; + proc.completeCallback = nullptr; + proc.complete_ud = nullptr; + proc.is_active = false; + + // Call any completion routine. + if (completeCallback) { + completeCallback(complete_ud); + } - goto finished; + goto finished; + } } - } - // Save progress. - proc.curoff_bytes = curoff_bytes; + // Save progress. + proc.curoff_bytes = curoff_bytes; - finished:; + finished:; + } } - } - - static void _spi_interrupt_sspbus0() { - _spi_interrupt <0> (); - } - static void _spi_interrupt_sspbus1() { - _spi_interrupt <1> (); - } - static void _spiEnableInterrupt(uint8_t sspBusIdx) { - if (sspBusIdx == 0) { - nvicSetIRQHandler((IRQn_Type)14, _spi_interrupt_sspbus0); + static void _spi_interrupt_sspbus0() { + _spi_interrupt <0> (); } - else if (sspBusIdx == 1) { - nvicSetIRQHandler((IRQn_Type)15, _spi_interrupt_sspbus1); - } - nvicInstallRedirect(); - if (sspBusIdx == 0) { - NVIC_EnableIRQ((IRQn_Type)14); - NVIC_SetPriority((IRQn_Type)14, 5); + static void _spi_interrupt_sspbus1() { + _spi_interrupt <1> (); } - else if (sspBusIdx == 1) { - NVIC_EnableIRQ((IRQn_Type)15); - NVIC_SetPriority((IRQn_Type)15, 5); - } - } - static void _spiDisableInterrupt(uint8_t sspBusIdx) { - if (sspBusIdx == 0) { - NVIC_SetPriority((IRQn_Type)14, 255); - NVIC_DisableIRQ((IRQn_Type)14); - } - else if (sspBusIdx == 1) { - NVIC_SetPriority((IRQn_Type)15, 255); - NVIC_DisableIRQ((IRQn_Type)15); - } - nvicUninstallRedirect(); - if (sspBusIdx == 0) { - nvicResetIRQHandler((IRQn_Type)14); - } - else if (sspBusIdx == 1) { - nvicResetIRQHandler((IRQn_Type)15); + static void _spiEnableInterrupt(uint8_t sspBusIdx) { + if (sspBusIdx == 0) { + nvicSetIRQHandler((IRQn_Type)14, _spi_interrupt_sspbus0); + } + else if (sspBusIdx == 1) { + nvicSetIRQHandler((IRQn_Type)15, _spi_interrupt_sspbus1); + } + nvicInstallRedirect(); + if (sspBusIdx == 0) { + NVIC_EnableIRQ((IRQn_Type)14); + NVIC_SetPriority((IRQn_Type)14, 5); + } + else if (sspBusIdx == 1) { + NVIC_EnableIRQ((IRQn_Type)15); + NVIC_SetPriority((IRQn_Type)15, 5); + } } - } - template - static void _spiStartAsyncTX(const numberType *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { - auto& SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - - // Start the async process. - auto& proc = _ssp_async_proc; - proc.current_ssp = &SSP; - proc.current_buffer = buf; - proc.curoff_bytes = 0; - proc.txlen_bytes = cnt * sizeof(numberType); - proc.txunitsize = sizeof(numberType); - proc.completeCallback = completeCallback; - proc.complete_ud = ud; - proc.is_active = true; - - // Register the interrupt. - _spiEnableInterrupt(_ssp_gpioMap.sspBusIdx); - - // Enable the interrupt. This should kick it off. - SSP.IMSC.TXIM = true; - } - - void spiWriteAsync(const uint8_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { - if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { - if (completeCallback) { - completeCallback(ud); + static void _spiDisableInterrupt(uint8_t sspBusIdx) { + if (sspBusIdx == 0) { + NVIC_SetPriority((IRQn_Type)14, 255); + NVIC_DisableIRQ((IRQn_Type)14); + } + else if (sspBusIdx == 1) { + NVIC_SetPriority((IRQn_Type)15, 255); + NVIC_DisableIRQ((IRQn_Type)15); + } + nvicUninstallRedirect(); + if (sspBusIdx == 0) { + nvicResetIRQHandler((IRQn_Type)14); + } + else if (sspBusIdx == 1) { + nvicResetIRQHandler((IRQn_Type)15); } - return; } - _spiSetFrameSize(sizeof(uint8_t)); + template + static void _spiStartAsyncTX(const numberType *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - _maybe_start_transaction(); + // Start the async process. + auto &proc = _ssp_async_proc; + proc.current_ssp = &SSP; + proc.current_buffer = buf; + proc.curoff_bytes = 0; + proc.txlen_bytes = cnt * sizeof(numberType); + proc.txunitsize = sizeof(numberType); + proc.completeCallback = completeCallback; + proc.complete_ud = ud; + proc.is_active = true; - _spiAsyncBarrier(); + // Register the interrupt. + _spiEnableInterrupt(_ssp_gpioMap.sspBusIdx); -#ifndef HALSPI_DISABLE_DMA - if (cnt > HALSPI_DMA_THRESHOLD) { - _dmaSendAsync(buf, cnt, completeCallback, ud); - return; + // Enable the interrupt. This should kick it off. + SSP.IMSC.TXIM = true; } -#endif - - _spiStartAsyncTX(buf, cnt, completeCallback, ud); - } - void spiWriteAsync16(const uint16_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { - if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { - if (completeCallback) { - completeCallback(ud); + void spiWriteAsync(const uint8_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { + if (completeCallback) { + completeCallback(ud); + } + return; } - return; - } - _spiSetFrameSize(sizeof(uint16_t)); + _spiSetFrameSize(sizeof(uint8_t)); - _maybe_start_transaction(); + _maybe_start_transaction(); - _spiAsyncBarrier(); + _spiAsyncBarrier(); -#ifndef HALSPI_DISABLE_DMA - if (cnt > HALSPI_DMA_THRESHOLD) { - _dmaSendAsync(buf, cnt, completeCallback, ud); - return; + #ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaSendAsync(buf, cnt, completeCallback, ud); + return; + } + #endif + + _spiStartAsyncTX(buf, cnt, completeCallback, ud); } -#endif - _spiStartAsyncTX(buf, cnt, completeCallback, ud); - } + void spiWriteAsync16(const uint16_t *buf, uint16_t cnt, void (*completeCallback)(void*), void *ud) { + if (cnt == 0 || _ssp_gpioMap.gpio_mosi < 0) { + if (completeCallback) completeCallback(ud); + return; + } - void spiAsyncAbort() { - cli(); - { - auto& proc = _ssp_async_proc; + _spiSetFrameSize(sizeof(uint16_t)); - if (proc.is_active) { - auto& SSP = *proc.current_ssp; + _maybe_start_transaction(); - // Disable the interrupt processing. - SSP.IMSC.TXIM = false; + _spiAsyncBarrier(); - // Unregister the interrupt. - _spiDisableInterrupt(MarlinLPC::SPIGetBusIndex(SSP)); + #ifndef HALSPI_DISABLE_DMA + if (cnt > HALSPI_DMA_THRESHOLD) { + _dmaSendAsync(buf, cnt, completeCallback, ud); + return; + } + #endif - // Cancel the process. - proc.is_active = false; - } + _spiStartAsyncTX(buf, cnt, completeCallback, ud); } -#ifndef HALSPI_DISABLE_DMA - { - auto& proc = MarlinLPC::_dma_async_proc; - if (proc.is_active) { - auto& DMACC = *proc.current_DMACC; + void spiAsyncAbort() { + cli(); + { + auto &proc = _ssp_async_proc; - DMACC.Config.H = true; - while (DMACC.Config.A) { /* wait until the DMA channel has no more data to process */ } - DMACC.Config.E = false; + if (proc.is_active) { + auto &SSP = *proc.current_ssp; - DMACC.Config.ITC = false; - DMACC.Control.I = false; + // Disable the interrupt processing. + SSP.IMSC.TXIM = false; - // Cancel the process. - proc.is_active = false; - } - } -#endif + // Unregister the interrupt. + _spiDisableInterrupt(MarlinLPC::SPIGetBusIndex(SSP)); - sei(); - } + // Cancel the process. + proc.is_active = false; + } + } + #ifndef HALSPI_DISABLE_DMA + { + auto &proc = MarlinLPC::_dma_async_proc; - void spiAsyncJoin() { - _spiAsyncBarrier(); - } + if (proc.is_active) { + auto &DMACC = *proc.current_DMACC; - bool spiAsyncIsRunning() { - if (_ssp_async_proc.is_active) return true; - #ifndef HALSPI_DISABLE_DMA - if (MarlinLPC::_dma_async_proc.is_active) return true; - #endif - return false; - } + DMACC.Config.H = true; + while (DMACC.Config.A) { /* wait until the DMA channel has no more data to process */ } + DMACC.Config.E = false; + + DMACC.Config.ITC = false; + DMACC.Control.I = false; + + // Cancel the process. + proc.is_active = false; + } + } + #endif + + sei(); + } + + void spiAsyncJoin() { _spiAsyncBarrier(); } + + bool spiAsyncIsRunning() { + if (_ssp_async_proc.is_active) return true; + #ifndef HALSPI_DISABLE_DMA + if (MarlinLPC::_dma_async_proc.is_active) return true; + #endif + return false; + } -#endif + #endif // HAL_SPI_SUPPORTS_ASYNC -#endif +#endif // !SOFTWARE_SPI #endif // TARGET_LPC1768 From 9b6ffe188a22a766af424decd50b95c667a0442d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Dec 2022 12:06:35 -0600 Subject: [PATCH 42/83] misc. cleanup --- Marlin/src/HAL/AVR/HAL_SPI_shared.cpp | 2 +- Marlin/src/HAL/AVR/registers.cpp | 1596 ++--- Marlin/src/HAL/AVR/registers.h | 8933 ++++++++++++------------- 3 files changed, 5183 insertions(+), 5348 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp b/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp index 7f126b2c7175..d3bf47810b77 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_shared.cpp @@ -40,4 +40,4 @@ void spiSetupChipSelect(int pin) { _ATmega_digitalWrite(pin, HIGH); } -#endif //__AVR__ \ No newline at end of file +#endif //__AVR__ diff --git a/Marlin/src/HAL/AVR/registers.cpp b/Marlin/src/HAL/AVR/registers.cpp index 687705fc7e8e..9b1b9fe531ca 100644 --- a/Marlin/src/HAL/AVR/registers.cpp +++ b/Marlin/src/HAL/AVR/registers.cpp @@ -31,803 +31,803 @@ ATmegaPinFunctions _ATmega_getPinFunctions(int pin) { ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); -#if defined(__AVR_TRM01__) - if (info.port == eATmegaPort::PORT_A) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_C) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::TIMER3_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOC3C }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOC3B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC3A }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::USART0_CLK }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::USART0_TXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::PCI8 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_F) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_G) { - if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3 ) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_H) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4C }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4A }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_CLK }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_TXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_RXD }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_J) { - if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI15 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI13 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI12 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_CLK, eATmegaPinFunc::PCI11 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::PCI10 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_RXD, eATmegaPinFunc::PCI9 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_K) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC15, eATmegaPinFunc::PCI23 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC14, eATmegaPinFunc::PCI22 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC13, eATmegaPinFunc::PCI21 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC12, eATmegaPinFunc::PCI20 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC11, eATmegaPinFunc::PCI19 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC10, eATmegaPinFunc::PCI18 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC9, eATmegaPinFunc::PCI17 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC8, eATmegaPinFunc::PCI16 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_L) { - if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5C }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5A }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_ICP }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_ICP }; - return { funcs, countof(funcs) }; - } - } -#elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI7, eATmegaPinFunc::ADC7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI6, eATmegaPinFunc::ADC6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI5, eATmegaPinFunc::ADC5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI4, eATmegaPinFunc::ADC4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI3, eATmegaPinFunc::ADC3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI2, eATmegaPinFunc::ADC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI1, eATmegaPinFunc::ADC1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI0, eATmegaPinFunc::ADC0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::TOC3B, eATmegaPinFunc::PCI15 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::TOC3A, eATmegaPinFunc::PCI14 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::PCI13 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI12 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI11 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::EINT2, eATmegaPinFunc::PCI10 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI9 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::PCI8 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_C) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI23 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI22 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI21 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI20 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI19 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI18 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI17, eATmegaPinFunc::TWI_SDA }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI16 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI31 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI30 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI29 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::PCI27 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::PCI26 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI25 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI24, eATmegaPinFunc::TIMER3_ECI }; - return { funcs, countof(funcs) }; - } - } -#elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL2, eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL1, eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_C) { - if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI13 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::PCI12 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3, eATmegaPinFunc::PCI11 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2, eATmegaPinFunc::PCI10 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1, eATmegaPinFunc::PCI9 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0, eATmegaPinFunc::PCI8 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::PCI23 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI22 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI21 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_CLK, eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::PCI20 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI19 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::PCI18 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_TXD, eATmegaPinFunc::PCI17 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_RXD, eATmegaPinFunc::PCI16 }; - return { funcs, countof(funcs) }; - } - } -#elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_B) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_C) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::TOC3A }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::TOC3B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::TOC3C }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::TIMER3_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_D) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TOC2B }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TOC0B }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_E) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::AIN1, eATmegaPinFunc::UVCON }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::AIN0 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOSC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOSC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::UID }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; - return { funcs, countof(funcs) }; - } - } - else if (info.port == eATmegaPort::PORT_F) { - if (info.pinidx == 7) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 6) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 5) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 4) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 3) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 2) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 1) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; - return { funcs, countof(funcs) }; - } - else if (info.pinidx == 0) { - static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; - return { funcs, countof(funcs) }; - } - } -#endif + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::USART0_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::USART0_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_G) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3 ) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_H) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC4A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART2_RXD }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_J) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_CLK, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART3_RXD, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_K) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC15, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC14, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC13, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC12, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC11, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC10, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC9, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC8, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_L) { + if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC5A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER5_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER4_ICP }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI7, eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI6, eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI5, eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI4, eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI3, eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI2, eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI1, eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI0, eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::TOC3B, eATmegaPinFunc::PCI15 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::TOC3A, eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::EINT2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::USART0_CLK, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI17, eATmegaPinFunc::TWI_SDA }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI31 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI30 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI29 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::PCI28 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::PCI27 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::PCI26 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI25 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::PCI24, eATmegaPinFunc::TIMER3_ECI }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL2, eATmegaPinFunc::TOSC2, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::XTAL1, eATmegaPinFunc::TOSC1, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP, eATmegaPinFunc::CLK0, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PCI14 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::PCI13 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::PCI12 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3, eATmegaPinFunc::PCI11 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2, eATmegaPinFunc::PCI10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1, eATmegaPinFunc::PCI9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0, eATmegaPinFunc::PCI8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN1, eATmegaPinFunc::PCI23 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::AIN0, eATmegaPinFunc::TOC0A, eATmegaPinFunc::PCI22 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ECI, eATmegaPinFunc::TOC0B, eATmegaPinFunc::PCI21 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_CLK, eATmegaPinFunc::TIMER0_ECI, eATmegaPinFunc::PCI20 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TOC2B, eATmegaPinFunc::PCI19 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::PCI18 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_TXD, eATmegaPinFunc::PCI17 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART_RXD, eATmegaPinFunc::PCI16 }; + return { funcs, countof(funcs) }; + } + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_B) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC0A, eATmegaPinFunc::TOC1C, eATmegaPinFunc::PCI7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1B, eATmegaPinFunc::PCI6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC1A, eATmegaPinFunc::PCI5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TOC2A, eATmegaPinFunc::PCI4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDO, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::PCI3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::PDI, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::PCI2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::PCI1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::SPI_CS, eATmegaPinFunc::PCI0 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_C) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::TIMER3_ICP, eATmegaPinFunc::CLK0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::TOC3A }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::TOC3B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::TOC3C }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::TIMER3_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD10 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD9 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_AD8 }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_D) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER0_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_CLKI }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::USART1_CLK }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::TIMER1_ICP }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT3, eATmegaPinFunc::USART1_TXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT2, eATmegaPinFunc::USART1_RXD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT1, eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TOC2B }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT0, eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TOC0B }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_E) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT7, eATmegaPinFunc::AIN1, eATmegaPinFunc::UVCON }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT6, eATmegaPinFunc::AIN0 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT5, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EINT4, eATmegaPinFunc::TOSC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::UID }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_ALE }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_RD }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::EXTMEM_WR }; + return { funcs, countof(funcs) }; + } + } + else if (info.port == eATmegaPort::PORT_F) { + if (info.pinidx == 7) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC7 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 6) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC6 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 5) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC5 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 4) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC4 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 3) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC3 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 2) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC2 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 1) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC1 }; + return { funcs, countof(funcs) }; + } + else if (info.pinidx == 0) { + static const eATmegaPinFunc funcs[] = { eATmegaPinFunc::ADC0 }; + return { funcs, countof(funcs) }; + } + } + #endif return ATmegaPinFunctions(); // default and empty. -} \ No newline at end of file +} diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index b13809e178d1..a00c7d334681 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -51,25 +51,25 @@ // You need to adjust the eATmegaPort enumeration aswell. #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) -#error Fatal error: __AVR_TRMn__ already defined! (n: 01|02|03|04) + #error "Fatal error: __AVR_TRMn__ already defined! (n: 01|02|03|04)" #endif #if defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega640__) -// ATmega2560 technical reference manual date: 28th of November, 2022 -// ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf -#define __AVR_TRM01__ + // ATmega2560 technical reference manual date: 28th of November, 2022 + // ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf + #define __AVR_TRM01__ #elif defined(__AVR_ATmega164A__) || defined(__AVR_ATmega164PA__) || defined(__AVR_ATmega324A__) || defined(__AVR_ATmega324PA__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284__) || defined(__AVT_ATmega1284P__) -// ATmega1284 technical reference manual date: 29th of November, 2022 -// ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf -#define __AVR_TRM02__ + // ATmega1284 technical reference manual date: 29th of November, 2022 + // ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf + #define __AVR_TRM02__ #elif defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) -// ATmega328 technical reference manual date: 29th of November, 2022 -// ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf -#define __AVR_TRM03__ + // ATmega328 technical reference manual date: 29th of November, 2022 + // ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf + #define __AVR_TRM03__ #elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__) -// AT90USB1287 technical reference manual ID: 7593D–AVR–07/06 -// Preliminary. -#define __AVR_TRM04__ + // AT90USB1287 technical reference manual ID: 7593D–AVR–07/06 + // Preliminary. + #define __AVR_TRM04__ #endif // As old as the ATmega series of CPU is, the worse the actual libraries making @@ -84,3987 +84,3828 @@ struct _bit_reg_t { uint8_t val; bool getValue(uint8_t idx) const volatile { - return ( val & (1< + struct no_volatile { + typedef T type; + }; -#endif + template + struct no_volatile : public no_volatile {}; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + template + inline typename no_volatile ::type& dwrite( memRegType& V ) { return (typename no_volatile ::type&)V; } -struct PCICR_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) - uint8_t _PCIE0 : 1; - uint8_t _PCIE1 : 1; - uint8_t _PCIE2 : 1; - uint8_t reserved1 : 5; -#elif defined(__AVR_TRM02__) - uint8_t _PCIE0 : 1; - uint8_t _PCIE1 : 1; - uint8_t _PCIE2 : 1; - uint8_t _PCIE3 : 1; - uint8_t reserved1 : 4; -#elif defined(__AVR_TRM04__) - uint8_t _PCIE0 : 1; - uint8_t reserved1 : 7; -#endif -}; -static_assert(sizeof(PCICR_reg_t) == 1, "invalid size of ATmega2560 PCICR_reg_t"); +} // namespace AVRHelpers -struct EICRA_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - uint8_t _ISC0 : 2; - uint8_t _ISC1 : 2; - uint8_t _ISC2 : 2; - uint8_t _ISC3 : 2; -#elif defined(__AVR_TRM02__) - uint8_t _ISC0 : 2; - uint8_t _ISC1 : 2; - uint8_t _ISC2 : 2; - uint8_t reserved1 : 2; -#elif defined(__AVR_TRM03__) - uint8_t _ISC0 : 2; - uint8_t _ISC1 : 2; - uint8_t reserved1 : 4; -#endif -}; -static_assert(sizeof(EICRA_reg_t) == 1, "invalid size of ATmega2560 EICRA_reg_t"); +inline void _ATmega_resetperipherals() { + using namespace AVRHelpers; -#endif + // Due to BOOTLOADER or other board inconsistencies we could get launched into Marlin FW + // with configuration that does not match the reset state in the documentation. That is why + // we should clean-reset the entire device. + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + SREG_reg_t __SREG; + __SREG._C = false; + __SREG._Z = false; + __SREG._N = false; + __SREG._V = false; + __SREG._S = false; + __SREG._H = false; + __SREG._T = false; + __SREG._I = false; + dwrite(_SREG) = __SREG; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + _RAMPZ._RAMPZ = 0; + #endif + #ifdef __AVR_TRM01__ + _EIND._EIND0 = false; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) + _EEAR._EEAR = 0; + dwrite(_EEDR) = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + EECR_reg_t __EECR; + __EECR._EERE = false; + __EECR._EEPE = false; + __EECR._EEMPE = false; + __EECR._EERIE = false; + __EECR._EEPM0 = 0; + __EECR._EEPM1 = 0; + __EECR.reserved1 = 0; + dwrite(_EECR) = __EECR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + _GPIOR2.val = 0; + _GPIOR1.val = 0; + _GPIOR0.val = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + XMCRA_reg_t __XMCRA; + __XMCRA._SRW0 = 0; + __XMCRA._SRW1 = 0; + __XMCRA._SRL = 0; + __XMCRA._SRE = 0; + dwrite(_XMCRA) = __XMCRA; + + XMCRB_reg_t __XMCRB; + __XMCRB._XMM = 0; + __XMCRB.reserved1 = 0; + __XMCRB._XMBK = false; + dwrite(_XMCRB) = __XMCRB; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + SMCR_reg_t __SMCR; + __SMCR._SE = false; + __SMCR._SM = 0; + __SMCR.reserved1 = 0; + dwrite(_SMCR) = __SMCR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + PRR0_reg_t __PRR0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PRR0._PRADC = false; + __PRR0._PRUSART0 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0.reserved1 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #elif defined(__AVR_TRM02__) + __PRR0._PRADC = false; + __PRR0._PRUSART0 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0._PRUSART1 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #elif defined(__AVR_TRM04__) + __PRR0._PRADC = false; + __PRR0.reserved1 = false; + __PRR0._PRSPI = false; + __PRR0._PRTIM1 = false; + __PRR0.reserved2 = false; + __PRR0._PRTIM0 = false; + __PRR0._PRTIM2 = false; + __PRR0._PRTWI = false; + #endif + dwrite(_PRR0) = __PRR0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + PRR1_reg_t __PRR1; + #ifdef __AVR_TRM01__ + __PRR1._PRUSART1 = false; + __PRR1._PRUSART2 = false; + __PRR1._PRUSART3 = false; + __PRR1._PRTIM3 = false; + __PRR1._PRTIM4 = false; + __PRR1._PRTIM5 = false; + __PRR1.reserved1 = 0; + #elif defined(__AVR_TRM02__) + __PRR1._PRTIM3 = false; + __PRR1.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PRR1._PRUSART1 = false; + __PRR1.reserved1 = 0; + #endif + dwrite(_PRR1) = __PRR1; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + WDTCSR_reg_t __WDTCSR; + __WDTCSR._WDP0 = 0; + __WDTCSR._WDP1 = 0; + __WDTCSR._WDP2 = 0; + __WDTCSR._WDE = false; + __WDTCSR._WDCE = false; + __WDTCSR._WDP3 = 0; + __WDTCSR._WDIE = false; + __WDTCSR._WDIF = false; + dwrite(_WDTCSR) = __WDTCSR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + _MCUCR._PUD = false; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + PORT_dev_t __PORT; + __PORT._PIN.val = 0; + __PORT._DDR.val = 0; + __PORT._PORT.val = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + dwrite(_PORTA) = __PORT; + dwrite(_PORTC) = __PORT; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + dwrite(_PORTB) = __PORT; + dwrite(_PORTD) = __PORT; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + dwrite(_PORTE) = __PORT; + dwrite(_PORTF) = __PORT; + #endif + + #ifdef __AVR_TRM01__ + PORTG_dev_t __PORTG; + __PORTG._PIN.val = 0; + __PORTG._PIN.reserved1 = 0; + __PORTG._DDR.val = 0; + __PORTG._DDR.reserved1 = 0; + __PORTG._PORT.val = 0; + __PORTG._PORT.reserved1 = 0; + dwrite(_PORTG) = __PORTG; + #endif + + #ifdef __AVR_TRM03__ + PORTC_dev_t __PORTC; + __PORTC._PIN.val = 0; + __PORTC._PIN.reserved1 = 0; + __PORTC._DDR.val = 0; + __PORTC._DDR.reserved1 = 0; + __PORTC._PORT.val = 0; + __PORTC._PORT.reserved1 = 0; + dwrite(_PORTC) = __PORTC; + #endif + + #ifdef __AVR_TRM01__ + dwrite(_PORTH) = __PORT; + dwrite(_PORTJ) = __PORT; + dwrite(_PORTK) = __PORT; + dwrite(_PORTL) = __PORT; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + EICRA_reg_t __EICRA; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA._ISC2 = 0; + __EICRA._ISC3 = 0; + #elif defined(__AVR_TRM02__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA._ISC2 = 0; + __EICRA.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EICRA._ISC0 = 0; + __EICRA._ISC1 = 0; + __EICRA.reserved1 = 0; + #endif + dwrite(_EICRA) = __EICRA; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + EICRB_reg_t __EICRB; + __EICRB._ISC4 = 0; + __EICRB._ISC5 = 0; + __EICRB._ISC6 = 0; + __EICRB._ISC7 = 0; + dwrite(_EICRB) = __EICRB; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + EIMSK_reg_t __EIMSK; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK._INT2 = false; + __EIMSK._INT3 = false; + __EIMSK._INT4 = false; + __EIMSK._INT5 = false; + __EIMSK._INT6 = false; + __EIMSK._INT7 = false; + #elif defined(__AVR_TRM02__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK._INT2 = false; + __EIMSK.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EIMSK._INT0 = false; + __EIMSK._INT1 = false; + __EIMSK.reserved1 = 0; + #endif + dwrite(_EIMSK) = __EIMSK; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + EIFR_reg_t __EIFR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR._INTF2 = false; + __EIFR._INTF3 = false; + __EIFR._INTF4 = false; + __EIFR._INTF5 = false; + __EIFR._INTF6 = false; + __EIFR._INTF7 = false; + #elif defined(__AVR_TRM02__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR._INTF2 = false; + __EIFR.reserved1 = 0; + #elif defined(__AVR_TRM03__) + __EIFR._INTF0 = false; + __EIFR._INTF1 = false; + __EIFR.reserved1 = 0; + #endif + dwrite(_EIFR) = __EIFR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + PCICR_reg_t __PCICR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PCICR._PCIE0 = false; + __PCICR._PCIE1 = false; + __PCICR._PCIE2 = false; + __PCICR.reserved1 = 0; + #elif defined(__AVR_TRM02__) + __PCICR._PCIE0 = false; + __PCICR._PCIE1 = false; + __PCICR._PCIE2 = false; + __PCICR._PCIE3 = false; + __PCICR.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PCICR._PCIE0 = false; + __PCICR.reserved1 = 0; + #endif + dwrite(_PCICR) = __PCICR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + PCIFR_reg_t __PCIFR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) + __PCIFR._PCIF0 = false; + __PCIFR._PCIF1 = false; + __PCIFR._PCIF2 = false; + __PCIFR.reserved1 = 0; + #elif defined(__AVR_TRM02__) + __PCIFR._PCIF0 = false; + __PCIFR._PCIF1 = false; + __PCIFR._PCIF2 = false; + __PCIFR._PCIF3 = false; + __PCIFR.reserved1 = 0; + #elif defined(__AVR_TRM04__) + __PCIFR._PCIF0 = false; + __PCIFR.reserved1 = 0; + #endif + dwrite(_PCIFR) = __PCIFR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + _PCMSK0.val = 0; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) + _PCMSK1.val = 0; + _PCMSK2.val = 0; + #endif + #if defined(__AVR_TRM02__) + _PCMSK3.val = 0; + #endif + #if defined(__AVR_TRM03__) + _PCMSK1.reserved1 = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIMER_8bit_dev_t __TIMER_8bit; + __TIMER_8bit._TCCRnA._WGMn0 = 0; + __TIMER_8bit._TCCRnA._WGMn1 = 0; + __TIMER_8bit._TCCRnA.reserved1 = 0; + __TIMER_8bit._TCCRnA._COMnB = 0; + __TIMER_8bit._TCCRnA._COMnA = 0; + __TIMER_8bit._TCCRnB._CSn = 0; + __TIMER_8bit._TCCRnB._WGMn2 = 0; + __TIMER_8bit._TCCRnB.reserved1 = 0; + __TIMER_8bit._TCCRnB._FOCnB = false; + __TIMER_8bit._TCCRnB._FOCnA = false, + __TIMER_8bit._TCNTn = 0; + __TIMER_8bit._OCRnA = 0; + __TIMER_8bit._OCRnB = 0; + dwrite(TIMER0) = __TIMER_8bit; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIMSK0_reg_t __TIMSK0; + __TIMSK0._TOIE0 = false; + __TIMSK0._OCIE0A = false; + __TIMSK0._OCIE0B = false; + __TIMSK0.reserved1 = 0; + dwrite(_TIMSK0) = __TIMSK0; + + TIFR0_reg_t __TIFR0; + __TIFR0._TOV0 = false; + __TIFR0._OCF0A = false; + __TIFR0._OCF0B = false; + __TIFR0.reserved1 = 0; + dwrite(_TIFR0) = __TIFR0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIMER_dev_t TIMER; + TIMER._TCCRnA._WGMn0 = 0; + TIMER._TCCRnA._WGMn1 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._TCCRnA._COMnC = 0; + #endif + TIMER._TCCRnA._COMnB = 0; + TIMER._TCCRnA._COMnA = 0; + TIMER._TCCRnB._CSn = 0; + TIMER._TCCRnB._WGMn2 = 0; + TIMER._TCCRnB.reserved1 = 0; + TIMER._TCCRnB._ICESn = 0; + TIMER._TCCRnB._ICNCn = 0; + TIMER._TCCRnC.reserved1 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._TCCRnC._FOCnC = false; + #endif + TIMER._TCCRnC._FOCnB = false; + TIMER._TCCRnC._FOCnA = false; + TIMER._TCNTn = 0; + TIMER._OCRnA = 0; + TIMER._OCRnB = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + TIMER._OCRnC = 0; + #endif + TIMER._ICRn = 0; + dwrite(TIMER1) = TIMER; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + dwrite(TIMER3) = TIMER; + #endif + #ifdef __AVR_TRM01__ + dwrite(TIMER4) = TIMER; + dwrite(TIMER5) = TIMER; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIMSK1_reg_t __TIMSK1; + __TIMSK1._TOIE1 = false; + __TIMSK1._OCIE1A = false; + __TIMSK1._OCIE1B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIMSK1._OCIE1C = false; + #endif + __TIMSK1.reserved1 = 0; + __TIMSK1._ICIE1 = false; + __TIMSK1.reserved2 = 0; + dwrite(_TIMSK1) = __TIMSK1; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + TIMSK3_reg_t __TIMSK3; + __TIMSK3._TOIE3 = false; + __TIMSK3._OCIE3A = false; + __TIMSK3._OCIE3B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIMSK3._OCIE3C = false; + #endif + __TIMSK3.reserved1 = 0; + __TIMSK3._ICIE3 = false; + __TIMSK3.reserved2 = 0; + dwrite(_TIMSK3) = __TIMSK3; + #endif + + #ifdef __AVR_TRM01__ + TIMSK4_reg_t __TIMSK4; + __TIMSK4._TOIE4 = false; + __TIMSK4._OCIE4A = false; + __TIMSK4._OCIE4B = false; + __TIMSK4._OCIE4C = false; + __TIMSK4.reserved1 = false; + __TIMSK4._ICIE4 = false; + __TIMSK4.reserved2 = false; + dwrite(_TIMSK4) = __TIMSK4; + + TIMSK5_reg_t __TIMSK5; + __TIMSK5._TOIE5 = false; + __TIMSK5._OCIE5A = false; + __TIMSK5._OCIE5B = false; + __TIMSK5._OCIE5C = false; + __TIMSK5.reserved1 = 0; + __TIMSK5._ICIE5 = false; + __TIMSK5.reserved2 = 0; + dwrite(_TIMSK5) = __TIMSK5; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIFR1_reg_t __TIFR1; + __TIFR1._TOV1 = false; + __TIFR1._OCF1A = false; + __TIFR1._OCF1B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIFR1._OCF1C = false; + #endif + __TIFR1.reserved1 = 0; + __TIFR1._ICF1 = false; + __TIFR1.reserved2 = 0; + dwrite(_TIFR1) = __TIFR1; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + TIFR3_reg_t __TIFR3; + __TIFR3._TOV3 = false; + __TIFR3._OCF3A = false; + __TIFR3._OCF3B = false; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + __TIFR3._OCF3C = false; + #endif + __TIFR3.reserved1 = 0; + __TIFR3._ICF3 = false; + __TIFR3.reserved2 = 0; + dwrite(_TIFR3) = __TIFR3; + #endif + + #ifdef __AVR_TRM01__ + TIFR4_reg_t __TIFR4; + __TIFR4._TOV4 = false; + __TIFR4._OCF4A = false; + __TIFR4._OCF4B = false; + __TIFR4._OCF4C = false; + __TIFR4.reserved1 = 0; + __TIFR4._ICF4 = false; + __TIFR4.reserved2 = 0; + dwrite(_TIFR4) = __TIFR4; + + TIFR5_reg_t __TIFR5; + __TIFR5._TOV5 = false; + __TIFR5._OCF5A = false; + __TIFR5._OCF5B = false; + __TIFR5._OCF5C = false; + __TIFR5.reserved1 = 0; + __TIFR5._ICF5 = false; + __TIFR5.reserved2 = 0; + dwrite(_TIFR5) = __TIFR5; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + dwrite(_TIMER2) = __TIMER_8bit; + #endif + + #if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + ASSR_reg_t __ASSR; + __ASSR._TCR2BUB = false; + __ASSR._TCR2AUB = false; + __ASSR._OCR2BUB = false; + __ASSR._OCR2AUB = false; + __ASSR._TCN2UB = false; + __ASSR._AS2 = false; + __ASSR._EXCLK = false; + __ASSR.reserved1 = 0; + dwrite(_ASSR) = __ASSR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + TIMSK2_reg_t __TIMSK2; + __TIMSK2._TOIE2 = false; + __TIMSK2._OCIE2A = false; + __TIMSK2._OCIE2B = false; + __TIMSK2.reserved1 = 0; + dwrite(_TIMSK2) = __TIMSK2; + + TIFR2_reg_t __TIFR2; + __TIFR2._TOV2 = false; + __TIFR2._OCF2A = false; + __TIFR2._OCF2B = false; + __TIFR2.reserved1 = 0; + dwrite(_TIFR2) = __TIFR2; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + SPCR_reg_t __SPCR; + __SPCR._SPR = 0; + __SPCR._CPHA = 0; + __SPCR._CPOL = 0; + __SPCR._MSTR = 0; + __SPCR._DORD = 0; + __SPCR._SPE = false; + __SPCR._SPIE = false; + dwrite(_SPCR) = __SPCR; + + SPSR_reg_t __SPSR; + __SPSR._SPI2X = false; + __SPSR.reserved1 = 0; + __SPSR._WCOL = false; + __SPSR._SPIF = false; + dwrite(_SPSR) = __SPSR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + USART_dev_t USART; + USART._UDRn = 0; + USART._UCSRnA._MPCM = false; + USART._UCSRnA._U2X = false; + USART._UCSRnA._UPE = false; + USART._UCSRnA._DOR = false; + USART._UCSRnA._FE = false; + USART._UCSRnA._UDRE = true; + USART._UCSRnA._TXC = false; + USART._UCSRnA._RXC = false; + USART._UCSRnB._TXB8 = false; + USART._UCSRnB._RXB8 = false; + USART._UCSRnB._UCSZn2 = false; + USART._UCSRnB._TXEN = false; + USART._UCSRnB._RXEN = false; + USART._UCSRnB._UDRIE = false; + USART._UCSRnB._TXCIE = false; + USART._UCSRnB._RXCIE = false; + USART._UCSRnC._UCPOL = false; + USART._UCSRnC._UCSZn0 = 1; + USART._UCSRnC._UCSZn1 = 1; + USART._UCSRnC._USBS = false; + USART._UCSRnC._UPM = 0; + USART._UCSRnC._UPM = 0; + USART._UCSRnC._UMSEL = 0; + USART._UBRRn._UBRR = 0; + USART._UBRRn.reserved1 = 0; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) + dwrite(USART0) = USART; + #endif + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + dwrite(USART1) = USART; + #endif + #ifdef __AVR_TRM01__ + dwrite(USART2) = USART; + dwrite(USART3) = USART; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + dwrite(_TWBR) = 0; + + TWCR_reg_t __TWCR; + __TWCR._TWIE = false; + __TWCR.reserved1 = 0; + __TWCR._TWEN = false; + __TWCR._TWWC = false; + __TWCR._TWSTO = false; + __TWCR._TWSTA = false; + __TWCR._TWEA = false; + __TWCR._TWINT = false; + dwrite(_TWCR) = __TWCR; + + TWSR_reg_t __TWSR; + __TWSR._TWPS0 = false; + __TWSR._TWPS1 = false; + __TWSR.reserved1 = 0; + __TWSR._TWS3 = 1; + __TWSR._TWS4 = 1; + __TWSR._TWS5 = 1; + __TWSR._TWS6 = 1; + __TWSR._TWS7 = 1; + dwrite(_TWSR) = __TWSR; + + dwrite(_TWDR) = 0xFF; + + TWAR_reg_t __TWAR; + __TWAR._TWGCE = false; + __TWAR._TWA = 0x7F; + dwrite(_TWAR) = __TWAR; + + TWAMR_reg_t __TWAMR; + __TWAMR.reserved1 = false; + __TWAMR._TWAM = 0; + dwrite(_TWAMR) = __TWAMR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + ADCSRB_reg_t __ADCSRB; + __ADCSRB._ADTS = 0; + #ifdef __AVR_TRM01__ + __ADCSRB._MUX5 = 0; + #endif + __ADCSRB.reserved1 = 0; + __ADCSRB._ACME = false; + __ADCSRB.reserved2 = 0; + dwrite(_ADCSRB) = __ADCSRB; + + ACSR_reg_t __ACSR; + __ACSR._ACIS = 0; + __ACSR._ACIC = false; + __ACSR._ACIE = false; + __ACSR._ACI = false; + __ACSR._ACO = false; + __ACSR._ACBG = false; + __ACSR._ACD = false; + dwrite(_ACSR) = __ACSR; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + DIDR1_reg_t __DIDR1; + __DIDR1._AIN0D = false; + __DIDR1._AIN1D = false; + __DIDR1.reserved1 = false; + dwrite(_DIDR1) = __DIDR1; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + ADMUX_reg_t __ADMUX; + __ADMUX._MUX0 = 0; + __ADMUX._MUX1 = 0; + __ADMUX._MUX2 = 0; + __ADMUX._MUX3 = 0; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + __ADMUX._MUX4 = 0; + #elif defined(__AVR_TRM03__) + __ADMUX.reserved1 = 0; + #endif + __ADMUX._ADLAR = 0; + __ADMUX._REFS0 = 0; + __ADMUX._REFS1 = 0; + dwrite(_ADMUX) = __ADMUX; + + ADCSRA_reg_t __ADCSRA; + __ADCSRA._ADPS = 0; + __ADCSRA._ADIE = false; + __ADCSRA._ADIF = false; + __ADCSRA._ADATE = false; + __ADCSRA._ADSC = false; + __ADCSRA._ADEN = false; + dwrite(_ADCSRA) = __ADCSRA; + + dwrite(_ADC) = 0; + #endif + + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + SPMCSR_reg_t __SPMCSR; + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR._RWWSRE = false; + __SPMCSR._SIGRD = false; + __SPMCSR._RWWSB = false; + __SPMCSR._SPMIE = false; + #elif defined(__AVR_TRM03__) + #if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR._RWWSRE = false; + __SPMCSR._SIGRD = false; + __SPMCSR._RWWSB = false; + __SPMCSR._SPMIE = false; + #else + __SPMCSR._SPMEN = false; + __SPMCSR._PGERS = false; + __SPMCSR._PGWRT = false; + __SPMCSR._BLBSET = false; + __SPMCSR.reserved1 = false; + __SPMCSR._SIGRD = false; + __SPMCSR.reserved2 = false; + __SPMCSR._SPMIE = false; + #endif + #endif + dwrite(_SPMCSR) = __SPMCSR; + #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) +} -struct EICRB_reg_t { - uint8_t _ISC4 : 2; - uint8_t _ISC5 : 2; - uint8_t _ISC6 : 2; - uint8_t _ISC7 : 2; +struct pin_dev_state_t { + #ifdef __AVR_TRM01__ + uint8_t _SRE : 1; // port A + uint8_t _COM0B : 2; + uint8_t _COM1A : 2; + uint8_t _COM1B : 2; + uint8_t _COM1C : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _COM3A : 2; + uint8_t _COM3B : 2; + uint8_t _COM3C : 2; + uint8_t _COM4A : 2; + uint8_t _COM4B : 2; + uint8_t _COM4C : 2; + uint8_t _COM5A : 2; + uint8_t _COM5B : 2; + uint8_t _COM5C : 2; + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; // INTn + uint8_t _PCIE2 : 1; + uint8_t _SPE : 1; + uint8_t _USART0_RXEN : 1; + uint8_t _USART0_TXEN : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _USART2_RXEN : 1; + uint8_t _USART2_TXEN : 1; + uint8_t _USART3_RXEN : 1; + uint8_t _USART3_TXEN : 1; + //uint8_t _JTAGEN : 1; + uint8_t _AS2 : 1; + #elif defined(__AVR_TRM02__) + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _PCIE3 : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; + uint8_t _SPE : 1; + uint8_t _COM0A : 2; + uint8_t _COM0B : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _COM1A : 2; + uint8_t _COM1B : 2; + //uint8_t _JTAGEN : 1; + uint8_t _AS2 : 1; + uint8_t _TWEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART0_TXEN : 1; + uint8_t _USART0_RXEN : 1; + #elif defined(__AVR_TRM03__) + uint8_t _AS2 : 1; + uint8_t _PCIE0 : 1; + uint8_t _PCIE1 : 1; + uint8_t _PCIE2 : 1; + uint8_t _SPE : 1; + uint8_t _COM2B : 2; + uint8_t _COM2A : 2; + uint8_t _COM1B : 2; + uint8_t _COM1A : 2; + uint8_t _COM0A : 2; + uint8_t _COM0B : 2; + uint8_t _TWEN : 1; + uint8_t _ADC7D : 1; + uint8_t _ADC6D : 1; + uint8_t _ADC5D : 1; + uint8_t _ADC4D : 1; + uint8_t _ADC3D : 1; + uint8_t _ADC2D : 1; + uint8_t _ADC1D : 1; + uint8_t _ADC0D : 1; + uint8_t _UMSEL : 2; + uint8_t _USART0_TXEN : 1; + uint8_t _USART0_RXEN : 1; + #elif defined(__AVR_TRM04__) + uint8_t _SRE : 1; + uint8_t _SPE : 1; + uint8_t _COM0B : 2; + uint8_t _COM1C : 2; + uint8_t _COM1B : 2; + uint8_t _COM1A : 2; + uint8_t _COM2A : 2; + uint8_t _COM2B : 2; + uint8_t _PCIE0 : 1; + uint8_t _USART1_RXEN : 1; + uint8_t _USART1_TXEN : 1; + uint8_t _TWEN : 1; + uint8_t _INT7 : 1; + uint8_t _INT6 : 1; + uint8_t _INT5 : 1; + uint8_t _INT4 : 1; + uint8_t _INT3 : 1; + uint8_t _INT2 : 1; + uint8_t _INT1 : 1; + uint8_t _INT0; + uint8_t _UVCONE : 1; + uint8_t _UIDE : 1; + //uint8_t _JTAGEN : 1; + #endif }; -static_assert(sizeof(EICRB_reg_t) == 1, "invalid size of ATmega2560 EICRB_reg_t"); - -#endif -#if defined(__AVR_TRM03__) +// AVR ArduinoCore is written like a hack-job (random peripherals enabled all-the-time). -struct _bitPCMSK1_reg_t { - uint8_t val : 7; - uint8_t reserved1 : 1; +enum class eATmegaPort { + #ifdef __AVR_TRM01__ + PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F, PORT_G, PORT_H, PORT_J, PORT_K, PORT_L + #elif defined(__AVR_TRM02__) + PORT_A, PORT_B, PORT_C, PORT_D + #elif defined(__AVR_TRM03__) + PORT_B, PORT_C, PORT_D + #elif defined(__AVR_TRM04__) + PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F + #endif +}; - bool getValue(uint8_t idx) { - return ( val & (1< 0 + _SPA_DIOn_PORTRET(pin, 0) + #endif + #if DIO_NUM > 1 + _SPA_DIOn_PORTRET(pin, 1) + #endif + #if DIO_NUM > 2 + _SPA_DIOn_PORTRET(pin, 2) + #endif + #if DIO_NUM > 3 + _SPA_DIOn_PORTRET(pin, 3) + #endif + #if DIO_NUM > 4 + _SPA_DIOn_PORTRET(pin, 4) + #endif + #if DIO_NUM > 5 + _SPA_DIOn_PORTRET(pin, 5) + #endif + #if DIO_NUM > 6 + _SPA_DIOn_PORTRET(pin, 6) + #endif + #if DIO_NUM > 7 + _SPA_DIOn_PORTRET(pin, 7) + #endif + #if DIO_NUM > 8 + _SPA_DIOn_PORTRET(pin, 8) + #endif + #if DIO_NUM > 9 + _SPA_DIOn_PORTRET(pin, 9) + #endif + + #if DIO_NUM > 10 + _SPA_DIOn_PORTRET(pin, 10) + #endif + #if DIO_NUM > 11 + _SPA_DIOn_PORTRET(pin, 11) + #endif + #if DIO_NUM > 12 + _SPA_DIOn_PORTRET(pin, 12) + #endif + #if DIO_NUM > 13 + _SPA_DIOn_PORTRET(pin, 13) + #endif + #if DIO_NUM > 14 + _SPA_DIOn_PORTRET(pin, 14) + #endif + #if DIO_NUM > 15 + _SPA_DIOn_PORTRET(pin, 15) + #endif + #if DIO_NUM > 16 + _SPA_DIOn_PORTRET(pin, 16) + #endif + #if DIO_NUM > 17 + _SPA_DIOn_PORTRET(pin, 17) + #endif + #if DIO_NUM > 18 + _SPA_DIOn_PORTRET(pin, 18) + #endif + #if DIO_NUM > 19 + _SPA_DIOn_PORTRET(pin, 19) + #endif + + #if DIO_NUM > 20 + _SPA_DIOn_PORTRET(pin, 20) + #endif + #if DIO_NUM > 21 + _SPA_DIOn_PORTRET(pin, 21) + #endif + #if DIO_NUM > 22 + _SPA_DIOn_PORTRET(pin, 22) + #endif + #if DIO_NUM > 23 + _SPA_DIOn_PORTRET(pin, 23) + #endif + #if DIO_NUM > 24 + _SPA_DIOn_PORTRET(pin, 24) + #endif + #if DIO_NUM > 25 + _SPA_DIOn_PORTRET(pin, 25) + #endif + #if DIO_NUM > 26 + _SPA_DIOn_PORTRET(pin, 26) + #endif + #if DIO_NUM > 27 + _SPA_DIOn_PORTRET(pin, 27) + #endif + #if DIO_NUM > 28 + _SPA_DIOn_PORTRET(pin, 28) + #endif + #if DIO_NUM > 29 + _SPA_DIOn_PORTRET(pin, 29) + #endif + + #if DIO_NUM > 30 + _SPA_DIOn_PORTRET(pin, 30) + #endif + #if DIO_NUM > 31 + _SPA_DIOn_PORTRET(pin, 31) + #endif + #if DIO_NUM > 32 + _SPA_DIOn_PORTRET(pin, 32) + #endif + #if DIO_NUM > 33 + _SPA_DIOn_PORTRET(pin, 33) + #endif + #if DIO_NUM > 34 + _SPA_DIOn_PORTRET(pin, 34) + #endif + #if DIO_NUM > 35 + _SPA_DIOn_PORTRET(pin, 35) + #endif + #if DIO_NUM > 36 + _SPA_DIOn_PORTRET(pin, 36) + #endif + #if DIO_NUM > 37 + _SPA_DIOn_PORTRET(pin, 37) + #endif + #if DIO_NUM > 38 + _SPA_DIOn_PORTRET(pin, 38) + #endif + #if DIO_NUM > 39 + _SPA_DIOn_PORTRET(pin, 39) + #endif + + #if DIO_NUM > 40 + _SPA_DIOn_PORTRET(pin, 40) + #endif + #if DIO_NUM > 41 + _SPA_DIOn_PORTRET(pin, 41) + #endif + #if DIO_NUM > 42 + _SPA_DIOn_PORTRET(pin, 42) + #endif + #if DIO_NUM > 43 + _SPA_DIOn_PORTRET(pin, 43) + #endif + #if DIO_NUM > 44 + _SPA_DIOn_PORTRET(pin, 44) + #endif + #if DIO_NUM > 45 + _SPA_DIOn_PORTRET(pin, 45) + #endif + #if DIO_NUM > 46 + _SPA_DIOn_PORTRET(pin, 46) + #endif + #if DIO_NUM > 47 + _SPA_DIOn_PORTRET(pin, 47) + #endif + #if DIO_NUM > 48 + _SPA_DIOn_PORTRET(pin, 48) + #endif + #if DIO_NUM > 49 + _SPA_DIOn_PORTRET(pin, 49) + #endif + + #if DIO_NUM > 50 + _SPA_DIOn_PORTRET(pin, 50) + #endif + #if DIO_NUM > 51 + _SPA_DIOn_PORTRET(pin, 51) + #endif + #if DIO_NUM > 52 + _SPA_DIOn_PORTRET(pin, 52) + #endif + #if DIO_NUM > 53 + _SPA_DIOn_PORTRET(pin, 53) + #endif + #if DIO_NUM > 54 + _SPA_DIOn_PORTRET(pin, 54) + #endif + #if DIO_NUM > 55 + _SPA_DIOn_PORTRET(pin, 55) + #endif + #if DIO_NUM > 56 + _SPA_DIOn_PORTRET(pin, 56) + #endif + #if DIO_NUM > 57 + _SPA_DIOn_PORTRET(pin, 57) + #endif + #if DIO_NUM > 58 + _SPA_DIOn_PORTRET(pin, 58) + #endif + #if DIO_NUM > 59 + _SPA_DIOn_PORTRET(pin, 59) + #endif + + #if DIO_NUM > 60 + _SPA_DIOn_PORTRET(pin, 60) + #endif + #if DIO_NUM > 61 + _SPA_DIOn_PORTRET(pin, 61) + #endif + #if DIO_NUM > 62 + _SPA_DIOn_PORTRET(pin, 62) + #endif + #if DIO_NUM > 63 + _SPA_DIOn_PORTRET(pin, 63) + #endif + #if DIO_NUM > 64 + _SPA_DIOn_PORTRET(pin, 64) + #endif + #if DIO_NUM > 65 + _SPA_DIOn_PORTRET(pin, 65) + #endif + #if DIO_NUM > 66 + _SPA_DIOn_PORTRET(pin, 66) + #endif + #if DIO_NUM > 67 + _SPA_DIOn_PORTRET(pin, 67) + #endif + #if DIO_NUM > 68 + _SPA_DIOn_PORTRET(pin, 68) + #endif + #if DIO_NUM > 69 + _SPA_DIOn_PORTRET(pin, 69) + #endif + + #if DIO_NUM > 70 + _SPA_DIOn_PORTRET(pin, 70) + #endif + #if DIO_NUM > 71 + _SPA_DIOn_PORTRET(pin, 71) + #endif + #if DIO_NUM > 72 + _SPA_DIOn_PORTRET(pin, 72) + #endif + #if DIO_NUM > 73 + _SPA_DIOn_PORTRET(pin, 73) + #endif + #if DIO_NUM > 74 + _SPA_DIOn_PORTRET(pin, 74) + #endif + #if DIO_NUM > 75 + _SPA_DIOn_PORTRET(pin, 75) + #endif + #if DIO_NUM > 76 + _SPA_DIOn_PORTRET(pin, 76) + #endif + #if DIO_NUM > 77 + _SPA_DIOn_PORTRET(pin, 77) + #endif + #if DIO_NUM > 78 + _SPA_DIOn_PORTRET(pin, 78) + #endif + #if DIO_NUM > 79 + _SPA_DIOn_PORTRET(pin, 79) + #endif + + #if DIO_NUM > 80 + _SPA_DIOn_PORTRET(pin, 80) + #endif + #if DIO_NUM > 81 + _SPA_DIOn_PORTRET(pin, 81) + #endif + #if DIO_NUM > 82 + _SPA_DIOn_PORTRET(pin, 82) + #endif + #if DIO_NUM > 83 + _SPA_DIOn_PORTRET(pin, 83) + #endif + #if DIO_NUM > 84 + _SPA_DIOn_PORTRET(pin, 84) + #endif + #if DIO_NUM > 85 + _SPA_DIOn_PORTRET(pin, 85) + #endif + #if DIO_NUM > 86 + _SPA_DIOn_PORTRET(pin, 86) + #endif + #if DIO_NUM > 87 + _SPA_DIOn_PORTRET(pin, 87) + #endif + #if DIO_NUM > 88 + _SPA_DIOn_PORTRET(pin, 88) + #endif + #if DIO_NUM > 89 + _SPA_DIOn_PORTRET(pin, 89) + #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) + // Default. + #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) + return { eATmegaPort::PORT_A, 0 }; + #elif defined(__AVR_TRM03__) + return { eATmegaPort::PORT_B, 0 }; + #endif +} -struct XMCRA_reg_t { - uint8_t _SRW0 : 2; - uint8_t _SRW1 : 2; - uint8_t _SRL : 3; - uint8_t _SRE : 1; +enum class eATmegaPeripheral { + UNDEFINED, + #ifdef __AVR_TRM01__ + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PUSART2, PUSART3, PTIM3, PTIM4, PTIM5 + #elif defined(__AVR_TRM02__) + PADC, PUSART0, PSPI, PTIM1, PUSART1, PTIM0, PTIM2, PTWI, PTIM3 + #elif defined(__AVR_TRM03__) + PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI + #elif defined(__AVR_TRM04__) + PADC, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PTIM3, PUSB + #endif + , NUM_PERIPHERALS }; -static_assert(sizeof(XMCRA_reg_t) == 1, "invalid size of ATmega2560 XMCRA_reg_t"); -struct XMCRB_reg_t { - uint8_t _XMM : 3; - uint8_t reserved1 : 4; - uint8_t _XMBK : 1; +enum class eATmegaPinFunc : uint8_t { + #ifdef __AVR_TRM01__ + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, + PCI8, PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, + PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TOSC1, TOSC2, + TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, + TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, + USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, + TWI_SDA, TWI_CLK, + CLK0, PDO, PDI, + AIN0, AIN1, + ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 + #elif defined(__AVR_TRM02__) + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + EINT2, EINT1, EINT0, + TIMER3_ICP, + TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, + TIMER1_ICP, + TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, + AIN1, AIN0, + USART0_CLK, USART1_CLK, + USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, + CLK0, + TOSC2, TOSC1, + TWI_SDA, TWI_CLK + #elif defined(__AVR_TRM03__) + ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, + XTAL2, XTAL1, + TOSC2, TOSC1, + SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, + TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, + TIMER1_ICP, + TIMER1_ECI, TIMER0_ECI, + TWI_CLK, TWI_SDA, + PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, + PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + CLK0, + AIN1, AIN0, + USART_CLK, + USART_TXD, USART_RXD, + EINT1, EINT0 + #elif defined(__AVR_TRM04__) + EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, + EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, + EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, + TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, + CLK0, PDO, PDI, + SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, + TIMER3_ICP, TIMER1_ICP, + TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, + USART1_CLK, USART1_TXD, USART1_RXD, + EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, + PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, + TWI_SDA, TWI_CLK, + AIN1, AIN0, + TOSC2, + UID, UVCON, + ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 + #endif + , NUM_FUNCS }; -static_assert(sizeof(XMCRB_reg_t) == 1, "invalid size of ATmega2560 XMCRB_reg_t"); +#ifndef countof + #define countof(x) (sizeof(x) / sizeof(*x)) #endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) +struct ATmegaPinFunctions { + inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} + inline ATmegaPinFunctions() = default; + inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; -struct ADCSRA_reg_t { - uint8_t _ADPS : 3; - uint8_t _ADIE : 1; - uint8_t _ADIF : 1; - uint8_t _ADATE : 1; - uint8_t _ADSC : 1; - uint8_t _ADEN : 1; -}; -static_assert(sizeof(ADCSRA_reg_t) == 1, "invalid size of ATmega2560 ADCSRA_reg_t"); + const eATmegaPinFunc *funcs = nullptr; + uint8_t cnt = 0; -struct ADCSRB_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - uint8_t _ADTS : 3; - uint8_t _MUX5 : 1; - uint8_t reserved1 : 2; - uint8_t _ACME : 1; - uint8_t reserved2 : 1; -#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - uint8_t _ADTS : 3; - uint8_t reserved1 : 3; - uint8_t _ACME : 1; - uint8_t reserved2 : 1; -#endif -}; -static_assert(sizeof(ADCSRB_reg_t) == 1, "invalid size of ATmega2560 ADCSRB_reg_t"); - -struct ADMUX_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - uint8_t _MUX0 : 1; - uint8_t _MUX1 : 1; - uint8_t _MUX2 : 1; - uint8_t _MUX3 : 1; - uint8_t _MUX4 : 1; - uint8_t _ADLAR : 1; - uint8_t _REFS0 : 1; - uint8_t _REFS1 : 1; -#elif defined(__AVR_TRM03__) - uint8_t _MUX0 : 1; - uint8_t _MUX1 : 1; - uint8_t _MUX2 : 1; - uint8_t _MUX3 : 1; - uint8_t reserved1 : 1; - uint8_t _ADLAR : 1; - uint8_t _REFS0 : 1; - uint8_t _REFS1 : 1; -#endif -}; -static_assert(sizeof(ADMUX_reg_t) == 1, "invalid size of ATmega2560 ADMUX_reg_t"); - -#endif - -#if defined(__AVR_TRM01__) - -struct DIDR2_reg_t { - uint8_t _ADC8D : 1; - uint8_t _ADC9D : 1; - uint8_t _ADC10D : 1; - uint8_t _ADC11D : 1; - uint8_t _ADC12D : 1; - uint8_t _ADC13D : 1; - uint8_t _ADC14D : 1; - uint8_t _ADC15D : 1; -}; -static_assert(sizeof(DIDR2_reg_t) == 1, "invalid size of ATmega2560 DIDR2_reg_t"); - -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - -struct DIDR0_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - uint8_t _ADC0D : 1; - uint8_t _ADC1D : 1; - uint8_t _ADC2D : 1; - uint8_t _ADC3D : 1; - uint8_t _ADC4D : 1; - uint8_t _ADC5D : 1; - uint8_t _ADC6D : 1; - uint8_t _ADC7D : 1; -#elif defined(__AVR_TRM03__) - uint8_t _ADC0D : 1; - uint8_t _ADC1D : 1; - uint8_t _ADC2D : 1; - uint8_t _ADC3D : 1; - uint8_t _ADC4D : 1; - uint8_t _ADC5D : 1; - uint8_t reserved1 : 2; -#endif -}; -static_assert(sizeof(DIDR0_reg_t) == 1, "invalid size of ATmega2560 DIDR0_reg_t"); - -struct DIDR1_reg_t { - uint8_t _AIN0D : 1; - uint8_t _AIN1D : 1; - uint8_t reserved1 : 6; -}; -static_assert(sizeof(DIDR1_reg_t) == 1, "invalid size of ATmega2560 DIDR1_reg_t"); - -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - -struct TCCRnA_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - uint8_t _WGMn0 : 1; - uint8_t _WGMn1 : 1; - uint8_t _COMnC : 2; - uint8_t _COMnB : 2; - uint8_t _COMnA : 2; -#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - uint8_t _WGMn0 : 1; - uint8_t _WGMn1 : 1; - uint8_t reserved1 : 2; - uint8_t _COMnB : 2; - uint8_t _COMnA : 2; -#endif -}; -static_assert(sizeof(TCCRnA_reg_t) == 1, "invalid size of ATmega2560 TCCRnA_reg_t"); - -struct TCCRnB_reg_t { - uint8_t _CSn : 3; - uint8_t _WGMn2 : 1; - uint8_t _WGMn3 : 1; - uint8_t reserved1 : 1; - uint8_t _ICESn : 1; - uint8_t _ICNCn : 1; -}; -static_assert(sizeof(TCCRnB_reg_t) == 1, "invalid size of ATmega2560 TCCRnB_reg_t"); - -struct TCCRnC_reg_t { -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - uint8_t reserved1 : 5; - uint8_t _FOCnC : 1; - uint8_t _FOCnB : 1; - uint8_t _FOCnA : 1; -#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - uint8_t reserved1 : 6; - uint8_t _FOCnB : 1; - uint8_t _FOCnA : 1; -#endif -}; -static_assert(sizeof(TCCRnC_reg_t) == 1, "invalid size of ATmega2560 TCCRnC_reg_t"); - -struct TIMER_dev_t { - TCCRnA_reg_t _TCCRnA; - TCCRnB_reg_t _TCCRnB; - TCCRnC_reg_t _TCCRnC; - uint8_t reserved1; - uint16_t _TCNTn; - uint16_t _ICRn; - uint16_t _OCRnA; - uint16_t _OCRnB; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - uint16_t _OCRnC; -#endif -}; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) -static_assert(sizeof(TIMER_dev_t) == 14, "invalid size of ATmega2560 TIMER_dev_t"); -#elif defined(__AVR_TRM02__) || defined(__AVR_TRM03__) -static_assert(sizeof(TIMER_dev_t) == 12, "invalid size of ATmega1284 TIMER_dev_t"); -#endif - -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - -struct TCCRnA_8bit_reg_t { - uint8_t _WGMn0 : 1; - uint8_t _WGMn1 : 1; - uint8_t reserved1 : 2; - uint8_t _COMnB : 2; - uint8_t _COMnA : 2; -}; -static_assert(sizeof(TCCRnA_8bit_reg_t) == 1, "invalid size of ATmega2560 TCCRnA_8bit_reg_t"); - -struct TCCRnB_8bit_reg_t { - uint8_t _CSn : 3; - uint8_t _WGMn2 : 1; - uint8_t reserved1 : 2; - uint8_t _FOCnB : 1; - uint8_t _FOCnA : 1; -}; -static_assert(sizeof(TCCRnB_8bit_reg_t) == 1, "invalid size of ATmega2560 TCCRnB_8bit_reg_t"); - -struct TIMER_8bit_dev_t { - TCCRnA_8bit_reg_t _TCCRnA; - TCCRnB_8bit_reg_t _TCCRnB; - uint8_t _TCNTn; - uint8_t _OCRnA; - uint8_t _OCRnB; -}; -static_assert(sizeof(TIMER_8bit_dev_t) == 5, "invalid size of ATmega2560 TIMER_8bit_dev_t"); - -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - -struct ASSR_reg_t { - uint8_t _TCR2BUB : 1; - uint8_t _TCR2AUB : 1; - uint8_t _OCR2BUB : 1; - uint8_t _OCR2AUB : 1; - uint8_t _TCN2UB : 1; - uint8_t _AS2 : 1; - uint8_t _EXCLK : 1; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(ASSR_reg_t) == 1, "invalid size of ATmega2560 ASSR_reg_t"); - -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + inline bool hasFunc(eATmegaPinFunc query) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + if (func == query) return true; + } + return false; + } + template + inline bool hasFunc(eATmegaPinFunc func, otherItemType&&... items) const { + return hasFunc(func) || hasFunc(((otherItemType&&)items)...); + } -struct TWSR_reg_t { - uint8_t _TWPS0 : 1; - uint8_t _TWPS1 : 1; - uint8_t reserved1 : 1; - uint8_t _TWS3 : 1; - uint8_t _TWS4 : 1; - uint8_t _TWS5 : 1; - uint8_t _TWS6 : 1; - uint8_t _TWS7 : 1; + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 0; n < this->cnt; n++) { + eATmegaPinFunc func = this->funcs[n]; + cb(func); + } + } }; -static_assert(sizeof(TWSR_reg_t) == 1, "invalid size of ATmega2560 TWSR_reg_t"); -struct TWAR_reg_t { - uint8_t _TWGCE : 1; - uint8_t _TWA : 7; -}; -static_assert(sizeof(TWAR_reg_t) == 1, "invalid size of ATmega2560 TWAR_reg_t"); - -struct TWCR_reg_t { - uint8_t _TWIE : 1; - uint8_t reserved1 : 1; - uint8_t _TWEN : 1; - uint8_t _TWWC : 1; - uint8_t _TWSTO : 1; - uint8_t _TWSTA : 1; - uint8_t _TWEA : 1; - uint8_t _TWINT : 1; -}; -static_assert(sizeof(TWCR_reg_t) == 1, "invalid size of ATmega2560 TWCR_reg_t"); +ATmegaPinFunctions _ATmega_getPinFunctions(int pin); -struct TWAMR_reg_t { - uint8_t reserved1 : 1; - uint8_t _TWAM : 7; -}; -static_assert(sizeof(TWAMR_reg_t) == 1, "invalid size of ATmega2560 TWAMR_reg_t"); +struct ATmegaPinFuncSet { + inline ATmegaPinFuncSet() noexcept { + for (bool& f : this->funcs) f = false; + } + template + inline ATmegaPinFuncSet(eATmegaPinFunc func, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(func, ((funcItemType&&)items)...); + } + template + inline ATmegaPinFuncSet(int pin, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + addFromPin(pin, ((funcItemType&&)items)...); + } + inline ATmegaPinFuncSet(const ATmegaPinFuncSet&) = default; -#endif + inline void add(eATmegaPinFunc value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPinFunc value, funcItemType&&... items) { + add(value); + add(((eATmegaPinFunc&&)items)...); + } -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) + inline void addFromPin(int pin) noexcept { + ATmegaPinFunctions funcs = _ATmega_getPinFunctions(pin); + funcs.iterate( + [this]( eATmegaPinFunc func ) noexcept { this->add(func); } + ); + } + template + inline void addFromPin(int pin, itemType&&... items) noexcept { + addFromPin(pin); + addFromPin(((itemType&&)items)...); + } -struct UBRRn_reg_t { - uint16_t _UBRR : 12; - uint16_t reserved1 : 4; -}; -static_assert(sizeof(UBRRn_reg_t) == 2, "invalid size of ATmega2560 UBRRn_reg_t)"); - -struct UCSRnC_reg_t { - uint8_t _UCPOL : 1; - uint8_t _UCSZn0 : 1; - uint8_t _UCSZn1 : 1; - uint8_t _USBS : 1; - uint8_t _UPM : 2; - uint8_t _UMSEL : 2; -}; -static_assert(sizeof(UCSRnC_reg_t) == 1, "invalid size of ATmega2560 UCSRnC_reg_t"); - -struct UCSRnB_reg_t { - uint8_t _TXB8 : 1; - uint8_t _RXB8 : 1; - uint8_t _UCSZn2 : 1; - uint8_t _TXEN : 1; - uint8_t _RXEN : 1; - uint8_t _UDRIE : 1; - uint8_t _TXCIE : 1; - uint8_t _RXCIE : 1; -}; -static_assert(sizeof(UCSRnB_reg_t) == 1, "invalid size of ATmega2560 UCSRnB_reg_t"); - -struct UCSRnA_reg_t { - uint8_t _MPCM : 1; - uint8_t _U2X : 1; - uint8_t _UPE : 1; - uint8_t _DOR : 1; - uint8_t _FE : 1; - uint8_t _UDRE : 1; - uint8_t _TXC : 1; - uint8_t _RXC : 1; -}; -static_assert(sizeof(UCSRnA_reg_t) == 1, "invalid size of ATmega2560 UCSRnA_reg_t"); - -struct USART_dev_t { - UCSRnA_reg_t _UCSRnA; - UCSRnB_reg_t _UCSRnB; - UCSRnC_reg_t _UCSRnC; - uint8_t reserved1; - UBRRn_reg_t _UBRRn; - uint8_t _UDRn; -}; -static_assert(sizeof(USART_dev_t) == 7, "invalid size of ATmega2560 USART_dev_t"); + inline bool hasFunc(eATmegaPinFunc value) const noexcept { + return this->funcs[(uint8_t)value]; + } -#endif + inline bool hasAnyFunc() const noexcept { return false; } + template + inline bool hasAnyFunc(funcItem&& item, otherFuncItem&&... funcs) const noexcept { + return hasFunc(item) || hasAnyFunc(((otherFuncItem&&)funcs)...); + } -#if defined(__AVR_TRM04__) + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(this->funcs); n++) { + const bool& f = this->funcs[n]; + if (f) cb((eATmegaPinFunc)n); + } + } -struct UHCON_reg_t { - uint8_t _SOFEN : 1; - uint8_t _RESET : 1; - uint8_t _RESUME : 1; - uint8_t reserved1 : 5; -}; -static_assert(sizeof(UHCON_reg_t) == 1, "invalid size of ATUSB90 UHCON_reg_t"); - -struct UHINT_reg_t { - uint8_t _DCONNI : 1; - uint8_t _DDISCI : 1; - uint8_t _RSTI : 1; - uint8_t _RSMEDI : 1; - uint8_t _RXRSMI : 1; - uint8_t _HSOFI : 1; - uint8_t _HWUPI : 1; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UHINT_reg_t) == 1, "invalid size of ATUSB90 UHINT_reg_t"); - -struct UHIEN_reg_t { - uint8_t _SUSPE : 1; - uint8_t _MSOFE : 1; - uint8_t _SOFE : 1; - uint8_t _EORSTE : 1; - uint8_t _WAKEUPE : 1; - uint8_t _EORSME : 1; - uint8_t _UPRSME : 1; - uint8_t reserved1 : 1; +private: + bool funcs[(uint8_t)eATmegaPinFunc::NUM_FUNCS]; }; -static_assert(sizeof(UHIEN_reg_t) == 1, "invalid size of ATUSB90 UHIEN_reg_t"); -struct UHADDR_reg_t { - uint8_t _HADD : 7; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UHADDR_reg_t) == 1, "invalid size of ATUSB90 UHADDR_reg_t"); +inline void _ATmega_setPeripheralPower(eATmegaPeripheral peri, bool fullPower) { + bool reducePower = (fullPower == false); + switch(peri) { + #ifdef __AVR_TRM01__ + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PUSART2: _PRR1._PRUSART2 = reducePower; break; + case eATmegaPeripheral::PUSART3: _PRR1._PRUSART3 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PTIM4: _PRR1._PRTIM4 = reducePower; break; + case eATmegaPeripheral::PTIM5: _PRR1._PRTIM5 = reducePower; break; + #elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR0._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + #elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + #elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; + case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; + case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; + case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; + case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; + case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; + case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; + case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; + case eATmegaPeripheral::PUSB: _PRR1._PRUSB = reducePower; break; + #endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } +} -struct UHFNUM_reg_t { - uint16_t _FNUM : 11; - uint16_t reserved1 : 5; -}; -static_assert(sizeof(UHFNUM_reg_t) == 2, "invalid size of ATUSB90 UHFNUM_reg_t"); - -struct UPINTX_reg_t { - uint8_t _RXINI : 1; - uint8_t _RXSTALLI : 1; - uint8_t _TXOUTI : 1; - uint8_t _TXSTPI : 1; - uint8_t _PERRI : 1; - uint8_t _RWAL : 1; - uint8_t _NAKEDI : 1; - uint8_t _FIFOCON : 1; -}; -static_assert(sizeof(UPINTX_reg_t) == 1, "invalid size of ATUSB90 UPINTX_reg_t"); +inline bool _ATmega_getPeripheralPower(eATmegaPeripheral peri) { + switch(peri) { + #ifdef __AVR_TRM01__ + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PUSART2: return _PRR1._PRUSART2 == false; + case eATmegaPeripheral::PUSART3: return _PRR1._PRUSART3 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PTIM4: return _PRR1._PRTIM4 == false; + case eATmegaPeripheral::PTIM5: return _PRR1._PRTIM5 == false; + #elif defined(__AVR_TRM02__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PUSART1: return _PRR0._PRUSART1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + #elif defined(__AVR_TRM03__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + #elif defined(__AVR_TRM04__) + case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; + case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; + case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; + case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; + case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; + case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; + case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; + case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; + case eATmegaPeripheral::PUSB: return _PRR1._PRUSB == false; + #endif + case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; + } + return false; +} -struct UPNUM_reg_t { - uint8_t _PNUM : 3; - uint8_t reserved1 : 5; -}; -static_assert(sizeof(UPNUM_reg_t) == 1, "invalid size of ATUSB90 UPNUM_reg_t"); +inline eATmegaPeripheral _ATmega_getPeripheralForFunc( eATmegaPinFunc func ) { + // In C++20 there is the "using-enum" statement. I wish we had C++20 over here... + //using enum eATmegaPinFunc + switch(func) { + #ifdef __AVR_TRM01__ + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1C: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC4A: case eATmegaPinFunc::TOC4B: case eATmegaPinFunc::TOC4C: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TOC5A: case eATmegaPinFunc::TOC5B: case eATmegaPinFunc::TOC5C: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_CLKI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER3_CLKI: case eATmegaPinFunc::TIMER3_ICP: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER4_CLKI: case eATmegaPinFunc::TIMER4_ICP: return eATmegaPeripheral::PTIM4; + case eATmegaPinFunc::TIMER5_CLKI: case eATmegaPinFunc::TIMER5_ICP: return eATmegaPeripheral::PTIM5; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::USART2_CLK: case eATmegaPinFunc::USART2_TXD: case eATmegaPinFunc::USART2_RXD: return eATmegaPeripheral::PUSART2; + case eATmegaPinFunc::USART3_CLK: case eATmegaPinFunc::USART3_TXD: case eATmegaPinFunc::USART3_RXD: return eATmegaPeripheral::PUSART3; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::ADC15: case eATmegaPinFunc::ADC14: case eATmegaPinFunc::ADC13: case eATmegaPinFunc::ADC12: case eATmegaPinFunc::ADC11: case eATmegaPinFunc::ADC10: case eATmegaPinFunc::ADC9: case eATmegaPinFunc::ADC8: + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + #elif defined(__AVR_TRM02__) + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_ECI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ECI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3A: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + #elif defined(__AVR_TRM03__) + case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_ECI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TWI_CLK: case eATmegaPinFunc::TWI_SDA: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::USART_CLK: case eATmegaPinFunc::USART_TXD: case eATmegaPinFunc::USART_RXD: return eATmegaPeripheral::PUSART0; + #elif defined(__AVR_TRM04__) + case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::TOC1C: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; + case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; + case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_CLKI: return eATmegaPeripheral::PTIM3; + case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_CLKI: return eATmegaPeripheral::PTIM1; + case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; + case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; + case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; + case eATmegaPinFunc::UID: case eATmegaPinFunc::UVCON: return eATmegaPeripheral::PUSB; + case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: + return eATmegaPeripheral::PADC; + #endif + // There are quite some pin functions that have no peripheral assignment, and that is OK! + default: break; + } + return eATmegaPeripheral::UNDEFINED; +} -struct UPRST_reg_t { - uint8_t _PRST : 7; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UPRST_reg_t) == 1, "invalid size of ATUSB90 UPRST_reg_t"); - -struct UPCONX_reg_t { - uint8_t _PEN : 1; - uint8_t reserved1 : 2; - uint8_t _RSTDT : 1; - uint8_t _AUTOSW : 1; - uint8_t _INMODE : 1; - uint8_t _PFREEZE : 1; - uint8_t reserved2 : 1; -}; -static_assert(sizeof(UPCONX_reg_t) == 1, "invalid size of ATUSB90 UPCONX_reg_t"); +struct ATmegaPeripheralSet { + inline ATmegaPeripheralSet() noexcept { + for (bool& f : this->funcs) f = false; + } + template + inline ATmegaPeripheralSet(funcItemType&&... items) noexcept : ATmegaPinFuncSet() { + add(((eATmegaPinFunc&&)items)...); + } + inline ATmegaPeripheralSet(const ATmegaPeripheralSet&) = default; -struct UPCFG0X_reg_t { - uint8_t _PEPNUM : 4; - uint8_t _PTOKEN : 2; - uint8_t _PTYPE : 2; -}; -static_assert(sizeof(UPCFG0X_reg_t) == 1, "invalid size of ATUSB90 UPCFG0_reg_t"); - -struct UPCFG1X_reg_t { - uint8_t reserved1 : 1; - uint8_t _ALLOC : 1; - uint8_t _PBK : 2; - uint8_t _PSIZE : 3; - uint8_t reserved2 : 1; -}; -static_assert(sizeof(UPCFG1X_reg_t) == 1, "invalid size of ATUSB90 UPCFG1X_reg_t"); - -struct UPSTAX_reg_t { - uint8_t _NBUSYBK : 2; - uint8_t _DTSEQ : 2; - uint8_t reserved1 : 1; - uint8_t _UNDERFI : 1; - uint8_t _OVERFI : 1; - uint8_t _CFGOK : 1; -}; -static_assert(sizeof(UPSTAX_reg_t) == 1, "invalid size of ATUSB90 UPSTAX_reg_t"); - -struct UPIENX_reg_t { - uint8_t _RXINE : 1; - uint8_t _RXSTALLE : 1; - uint8_t _TXOUTE : 1; - uint8_t _TXSTPE : 1; - uint8_t _PERRE : 1; - uint8_t reserved1 : 1; - uint8_t _NAKEDE : 1; - uint8_t _FLERRE : 1; -}; -static_assert(sizeof(UPIENX_reg_t) == 1, "invalid size of ATUSB90 UPIENX_reg_t"); - -struct UHWCON_reg_t { - uint8_t _UVREGE : 1; - uint8_t reserved1 : 3; - uint8_t _UVCONE : 1; - uint8_t reserved2 : 1; - uint8_t _UIDE : 1; - uint8_t _UIMOD : 1; -}; -static_assert(sizeof(UHWCON_reg_t) == 1, "invalid size of ATUSB90 UHWCON_reg_t"); - -struct USBCON_reg_t { - uint8_t _VBUSTE : 1; - uint8_t _IDTE : 1; - uint8_t reserved1 : 2; - uint8_t _OTGPADE : 1; - uint8_t _FRZCLK : 1; - uint8_t _HOST : 1; - uint8_t _USBE : 1; -}; -static_assert(sizeof(USBCON_reg_t) == 1, "invalid size of ATUSB90 USBCON_reg_t"); - -struct USBSTA_reg_t { - uint8_t _VBUS : 1; - uint8_t _ID : 1; - uint8_t reserved1 : 1; - uint8_t _SPEED : 1; - uint8_t reserved2 : 4; -}; -static_assert(sizeof(USBSTA_reg_t) == 1, "invalid size of ATUSB90 USBSTA_reg_t"); + inline void add(eATmegaPeripheral value) noexcept { + this->funcs[(uint8_t)value] = true; + } + template + inline void add(eATmegaPeripheral value, funcItemType&&... items) noexcept { + add(value); + add(((funcItemType&&)items)...); + } -struct USBINT_reg_t { - uint8_t _VBUSTI : 1; - uint8_t _IDTI : 1; - uint8_t reserved1 : 6; -}; -static_assert(sizeof(USBINT_reg_t) == 1, "invalid size of ATUSB90 USBINT_reg_t"); + inline bool hasItem(eATmegaPeripheral value) const noexcept { + return this->funcs[(uint8_t)value]; + } + template + inline bool hasItem(eATmegaPeripheral&& item, otherFuncItem&&... funcs) const noexcept { + return hasItem(item) || hasItem(((otherFuncItem&&)funcs)...); + } -struct UDPADD_reg_t { - uint16_t _DPADD : 11; - uint16_t reserved1 : 4; - uint16_t _DPACC : 1; -}; -static_assert(sizeof(UDPADD_reg_t) == 2, "invalid size of ATUSB90 UDPADD_reg_t"); - -struct OTGCON_reg_t { - uint8_t _VBUSRQC : 1; - uint8_t _VBUSREQ : 1; - uint8_t _VBUSHWC : 1; - uint8_t _SRPSEL : 1; - uint8_t _SRPREQ : 1; - uint8_t _HNPREQ : 1; - uint8_t reserved1 : 1; - uint8_t _zero : 1; -}; -static_assert(sizeof(OTGCON_reg_t) == 1, "invalid size of ATUSB90 OTGCON_reg_t"); - -struct OTGIEN_reg_t { - uint8_t _SRPE : 1; - uint8_t _VBERRE : 1; - uint8_t _BCERRE : 1; - uint8_t _ROLEEXE : 1; - uint8_t _HNPERRE : 1; - uint8_t _STOE : 1; - uint8_t reserved1 : 2; -}; -static_assert(sizeof(OTGIEN_reg_t) == 1, "invalid size of ATUSB90 OTGIEN_reg_t"); - -struct OTGINT_reg_t { - uint8_t _SRPI : 1; - uint8_t _VBERRI : 1; - uint8_t _BCERRI : 1; - uint8_t _ROLEEXI : 1; - uint8_t _HNPERRI : 1; - uint8_t _STOI : 1; - uint8_t reserved1 : 2; -}; -static_assert(sizeof(OTGINT_reg_t) == 1, "invalid size of ATUSB90 OTGINT_reg_t"); + template + inline void iterate(callbackType&& cb) const { + for (uint8_t n = 1; n < countof(funcs); n++) { + const bool& f = this->funcs[n]; + if (f) cb( (eATmegaPeripheral)n ); + } + } -struct UDCON_reg_t { - uint8_t _DETACH : 1; - uint8_t _RMWKUP : 1; - uint8_t _LSM : 1; - uint8_t reserved1 : 5; -}; -static_assert(sizeof(UDCON_reg_t) == 1, "invalid size of ATUSB90 UDCON_reg_t"); - -struct UDINT_reg_t { - uint8_t _SUSPI : 1; - uint8_t _MSOFI : 1; - uint8_t _SOFI : 1; - uint8_t _EORSTI : 1; - uint8_t _WAKEUPI : 1; - uint8_t _EORSMI : 1; - uint8_t _UPRSMI : 1; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UDINT_reg_t) == 1, "invalid size of ATUSB90 UDINT_reg_t"); - -struct UDIEN_reg_t { - uint8_t _SUSPE : 1; - uint8_t _MSOFE : 1; - uint8_t _SOFE : 1; - uint8_t _EORSTE : 1; - uint8_t _WAKEUPE : 1; - uint8_t _EORSME : 1; - uint8_t _UPRSME : 1; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UDIEN_reg_t) == 1, "invalid size of ATUSB90 UDIEN_reg_t"); + inline void fromPinFuncs(const ATmegaPinFuncSet& funcSet) { + funcSet.iterate( + [this]( eATmegaPinFunc func ) noexcept { + this->add( _ATmega_getPeripheralForFunc(func) ); + } + ); + } -struct UDADDR_reg_t { - uint8_t _UADD : 7; - uint8_t _ADDEN : 1; +private: + bool funcs[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; }; -static_assert(sizeof(UDADDR_reg_t) == 1, "invalid size of ATUSB90 UADDR_reg_t"); -struct UDFNUM_reg_t { - uint16_t _FNUM : 11; - uint16_t reserved1 : 5; -}; -static_assert(sizeof(UDFNUM_reg_t) == 2, "invalid size of ATUSB90 UDFNUM_reg_t"); +struct ATmegaPeripheralPowerGate { + inline ATmegaPeripheralPowerGate(ATmegaPeripheralSet& periSet) noexcept : periSet(periSet) { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + this->states[(uint8_t)peri] = _ATmega_getPeripheralPower(peri); + _ATmega_setPeripheralPower(peri, true); + } + ); + } + inline ATmegaPeripheralPowerGate(const ATmegaPeripheralPowerGate&) = delete; -struct UDMFN_reg_t { - uint8_t reserved1 : 4; - uint8_t _FNCERR : 1; - uint8_t reserved2 : 3; -}; -static_assert(sizeof(UDMFN_reg_t) == 1, "invalid size of ATUSB90 UDMFN_reg_t"); - -struct UDTST_reg_t { - uint8_t reserved1 : 2; - uint8_t _TSTJ : 1; - uint8_t _TSTK : 1; - uint8_t _TSTPCKT : 1; - uint8_t _OPMODE2 : 1; - uint8_t reserved2 : 2; -}; -static_assert(sizeof(UDTST_reg_t) == 1, "invalid size of ATUSB90 UDTST_reg_t"); - -struct UEINTX_reg_t { - uint8_t _TXINI : 1; - uint8_t _STALLEDI : 1; - uint8_t _RXOUTI : 1; - uint8_t _RXSTPI : 1; - uint8_t _NAKOUTI : 1; - uint8_t _RWAL : 1; - uint8_t _NAKINI : 1; - uint8_t _FIFOCON : 1; -}; -static_assert(sizeof(UEINTX_reg_t) == 1, "invalid size of ATUSB90 UEINTX_reg_t"); + inline ~ATmegaPeripheralPowerGate() { + periSet.iterate( + [this]( eATmegaPeripheral peri ) noexcept { + _ATmega_setPeripheralPower(peri, this->states[(uint8_t)peri]); + } + ); + } -struct UENUM_reg_t { - uint8_t _EPNUM : 3; - uint8_t reserved1 : 5; -}; -static_assert(sizeof(UENUM_reg_t) == 1, "invalid size of ATUSB90 UENUM_reg_t"); + inline ATmegaPeripheralPowerGate& operator = (const ATmegaPeripheralPowerGate&) = delete; -struct UERST_reg_t { - uint8_t _EPRST : 7; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UERST_reg_t) == 1, "invalid size of ATUSB90 UERST_reg_t"); - -struct UECONX_reg_t { - uint8_t _EPEN : 1; - uint8_t reserved1 : 2; - uint8_t _RSTDT : 1; - uint8_t _STALLRQC : 1; - uint8_t _STALLRQ : 1; - uint8_t reserved2 : 2; -}; -static_assert(sizeof(UECONX_reg_t) == 1, "invalid size of ATUSB90 UECONX_reg_t"); - -struct UECFG0X_reg_t { - uint8_t _EPDIR : 1; - uint8_t _NYETSDIS : 1; - uint8_t _AUTOSW : 1; - uint8_t _ISOSW : 1; - uint8_t reserved1 : 2; - uint8_t _EPTYPE : 2; -}; -static_assert(sizeof(UECFG0X_reg_t) == 1, "invalid size of ATUSB90 UECFG0X_reg_t"); - -struct UECFG1X_reg_t { - uint8_t reserved1 : 1; - uint8_t _ALLOC : 1; - uint8_t _EPBK : 2; - uint8_t _EPSIZE : 3; - uint8_t reserved2 : 1; -}; -static_assert(sizeof(UECFG1X_reg_t) == 1, "invalid size of ATUSB90 UECFG1X_reg_t"); - -struct UESTA0X_reg_t { - uint8_t _NBUSYBK : 2; - uint8_t _DTSEQ : 2; - uint8_t _ZLPSEEN : 1; - uint8_t _UNDERFI : 1; - uint8_t _OVERFI : 1; - uint8_t _CFGOK : 1; +private: + ATmegaPeripheralSet& periSet; + bool states[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; }; -static_assert(sizeof(UESTA0X_reg_t) == 1, "invalid size of ATUSB90 UESTA0X_reg_t"); -struct UESTA1X_reg_t { - uint8_t _CURRBK : 2; - uint8_t _CTRLDIR : 1; - uint8_t reserved1 : 5; -}; -static_assert(sizeof(UESTA1X_reg_t) == 1, "invalid size of ATUSB90 UESTA1X_reg_t"); - -struct UEIENX_reg_t { - uint8_t _TXINE : 1; - uint8_t _STALLEDE : 1; - uint8_t _RXOUTE : 1; - uint8_t _RXSTPE : 1; - uint8_t _NAKOUTE : 1; - uint8_t reserved1 : 1; - uint8_t _NAKINE : 1; - uint8_t _FLERRE : 1; -}; -static_assert(sizeof(UEIENX_reg_t) == 1, "invalid size of ATUSB90 UEIENX_reg_t"); +inline pin_dev_state_t _ATmega_savePinAlternates(const ATmegaPinFuncSet& funcSet) { + // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that + // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should + // add power-reduction awareness to this logic! -struct UEBCX_reg_t { - uint16_t _BYCT : 11; - uint16_t reserved1 : 5; -}; -static_assert(sizeof(UEBCX_reg_t) == 2, "invalid size of ATUSB90 UEBCX_reg_t"); + pin_dev_state_t state; -struct UEINT_reg_t { - uint8_t _EPINT : 7; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UEINT_reg_t) == 1, "invalid size of ATUSB90 UEINT_reg_t"); - -struct UPERRX_reg_t { - uint8_t _DATATGL : 1; - uint8_t _DATAPID : 1; - uint8_t _PID : 1; - uint8_t _TIMEOUT : 1; - uint8_t _CRC16 : 1; - uint8_t _COUNTER : 2; - uint8_t reserved1 : 1; -}; -static_assert(sizeof(UPERRX_reg_t) == 1, "invalid size of ATUSB90 UPERRX_reg_t"); + ATmegaPeripheralSet periSet; + periSet.fromPinFuncs(funcSet); -struct UPBCX_reg_t { - uint16_t _PBYCT : 11; - uint16_t reserved1 : 5; -}; -static_assert(sizeof(UPBCX_reg_t) == 2, "invalid size of ATUSB90 UPBCX_reg_t"); + ATmegaPeripheralPowerGate pgate(periSet); -struct OTGTCON_reg_t { - uint8_t _VALUE : 2; - uint8_t reserved1 : 3; - uint8_t _PAGE : 2; - uint8_t _one : 1; -}; -static_assert(sizeof(OTGTCON_reg_t) == 1, "invalid size of ATUSB90 OTGTCON_reg_t"); - -struct PLLCSR_reg_t { - uint8_t _PLOCK : 1; - uint8_t _PLLE : 1; - uint8_t _PLLP : 3; - uint8_t reserved1 : 3; -}; -static_assert(sizeof(PLLCSR_reg_t) == 1, "invalid size of ATUSB90 PLLCSR_reg_t"); - -#endif - -/* - REGISTER MEMORY MAP -*/ - -#define __AVR_DEFREG(tn,n,a) static volatile tn& n = *(tn*)a -#define _AVR_DEFREG(n,a) __AVR_DEFREG(n##_reg_t, _##n, a) - -#if defined(__AVR_TRM01__) -// page 399ff of ATmega640-1280-1281-2560-2561-Datasheet-DS40002211A.pdf - -__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); -__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); -__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); -__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); -__AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); -__AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); -__AVR_DEFREG(PORTG_dev_t, _PORTG, 0x32); -__AVR_DEFREG(PORT_dev_t, _PORTH, 0x100); -__AVR_DEFREG(PORT_dev_t, _PORTJ, 0x103); -__AVR_DEFREG(PORT_dev_t, _PORTK, 0x106); -__AVR_DEFREG(PORT_dev_t, _PORTL, 0x109); -__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); -__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); -__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); -__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); -__AVR_DEFREG(TIFR4_reg_t, _TIFR4, 0x39); -__AVR_DEFREG(TIFR5_reg_t, _TIFR5, 0x3A); -__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); -__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); -__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); -__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); -__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); -__AVR_DEFREG(uint8_t, _EEDR, 0x40); -__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); -__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); -__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); -__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); -__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); -__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); -__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); -__AVR_DEFREG(uint8_t, _SPDR, 0x4E); -__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); -__AVR_DEFREG(_bit_reg_t, _OCDR, 0x51); -__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); -__AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); -__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); -__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); -__AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); -__AVR_DEFREG(EIND_reg_t, _EIND, 0x5C); -__AVR_DEFREG(SP_reg_t, _SP, 0x5D); -__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); -__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); -__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); -__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); -__AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); -__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); -__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); -__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); -__AVR_DEFREG(EICRB_reg_t, _EICRB, 0x6A); -__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); -__AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); -__AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); -__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); -__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); -__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); -__AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); -__AVR_DEFREG(TIMSK4_reg_t, _TIMSK4, 0x72); -__AVR_DEFREG(TIMSK5_reg_t, _TIMSK5, 0x73); -__AVR_DEFREG(XMCRA_reg_t, _XMCRA, 0x74); -__AVR_DEFREG(XMCRB_reg_t, _XMCRB, 0x75); -__AVR_DEFREG(uint16_t, _ADC, 0x78); -__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); -__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); -__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); -__AVR_DEFREG(DIDR2_reg_t, _DIDR2, 0x7D); -__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); -__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); -__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); -__AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); -__AVR_DEFREG(TIMER_dev_t, TIMER4, 0xA0); -__AVR_DEFREG(TIMER_dev_t, TIMER5, 0x120); -__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); -__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); -__AVR_DEFREG(uint8_t, _TWBR, 0xB8); -__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); -__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); -__AVR_DEFREG(uint8_t, _TWDR, 0xBB); -__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); -__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); -__AVR_DEFREG(USART_dev_t, USART0, 0xC0); -__AVR_DEFREG(USART_dev_t, USART1, 0xC8); -__AVR_DEFREG(USART_dev_t, USART2, 0xD0); -__AVR_DEFREG(USART_dev_t, USART3, 0x130); - -#elif defined(__AVR_TRM02__) -// page 637ff of ATmega164A_PA-324A_PA-644A_PA-1284_P_Data-Sheet-40002070B.pdf -__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); -__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); -__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); -__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); -__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); -__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); -__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); -__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); -__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); -__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); -__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); -__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); -__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); -__AVR_DEFREG(uint8_t, _EEDR, 0x40); -__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); -__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); -__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); -__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); -__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); -__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); -__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); -__AVR_DEFREG(uint8_t, _SPDR, 0x4E); -__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); -__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); -__AVR_DEFREG(MCUSR_reg_t, _MSUSR, 0x54); -__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); -__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); -__AVR_DEFREG(SP_reg_t, _SP, 0x5D); -__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); -__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); -__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); -__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); -__AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); -__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); -__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); -__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); -__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); -__AVR_DEFREG(_bit_reg_t, _PCMSK1, 0x6C); -__AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); -__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); -__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); -__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); -__AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); -__AVR_DEFREG(_bit_reg_t, _PCMSK3, 0x73); -__AVR_DEFREG(uint16_t, _ADC, 0x78); -__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); -__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); -__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); -__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); -__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); -__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); -__AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); -__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); -__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); -__AVR_DEFREG(uint8_t, _TWBR, 0xB8); -__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); -__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); -__AVR_DEFREG(uint8_t, _TWDR, 0xBB); -__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); -__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); -__AVR_DEFREG(USART_dev_t, USART0, 0xC0); -__AVR_DEFREG(USART_dev_t, USART1, 0xC8); - -#elif defined(__AVR_TRM03__) -// page 621ff of ATmega48A-PA-88A-PA-168A-PA-328-P-DS-DS40002061B.pdf -__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); -__AVR_DEFREG(PORTC_dev_t, _PORTC, 0x26); -__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); -__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); -__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); -__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); -__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); -__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); -__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); -__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); -__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); -__AVR_DEFREG(uint8_t, _EEDR, 0x40); -__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); -__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); -__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); -__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); -__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); -__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); -__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); -__AVR_DEFREG(uint8_t, _SPDR, 0x4E); -__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); -__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); -__AVR_DEFREG(MCUSR_reg_t, _MSUCR, 0x54); -__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); -__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); -__AVR_DEFREG(SP_reg_t, _SP, 0x5D); -__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); -__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); -__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); -__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); -__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); -__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); -__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); -__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); -__AVR_DEFREG(_bitPCMSK1_reg_t, _PCMSK1, 0x6C); -__AVR_DEFREG(_bit_reg_t, _PCMSK2, 0x6D); -__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); -__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); -__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); -__AVR_DEFREG(uint16_t, _ADC, 0x78); -__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); -__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); -__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); -__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); -__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); -__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); -__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); -__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); -__AVR_DEFREG(uint8_t, _TWBR, 0xB8); -__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); -__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); -__AVR_DEFREG(uint8_t, _TWDR, 0xBB); -__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); -__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); -__AVR_DEFREG(USART_dev_t, USART0, 0xC0); - -#elif defined(__AVR_TRM04__) -__AVR_DEFREG(PORT_dev_t, _PORTA, 0x20); -__AVR_DEFREG(PORT_dev_t, _PORTB, 0x23); -__AVR_DEFREG(PORT_dev_t, _PORTC, 0x26); -__AVR_DEFREG(PORT_dev_t, _PORTD, 0x29); -__AVR_DEFREG(PORT_dev_t, _PORTE, 0x2C); -__AVR_DEFREG(PORT_dev_t, _PORTF, 0x2F); -__AVR_DEFREG(TIFR0_reg_t, _TIFR0, 0x35); -__AVR_DEFREG(TIFR1_reg_t, _TIFR1, 0x36); -__AVR_DEFREG(TIFR2_reg_t, _TIFR2, 0x37); -__AVR_DEFREG(TIFR3_reg_t, _TIFR3, 0x38); -__AVR_DEFREG(PCIFR_reg_t, _PCIFR, 0x3B); -__AVR_DEFREG(EIFR_reg_t, _EIFR, 0x3C); -__AVR_DEFREG(EIMSK_reg_t, _EIMSK, 0x3D); -__AVR_DEFREG(_bit_reg_t, _GPIOR0, 0x3E); -__AVR_DEFREG(EECR_reg_t, _EECR, 0x3F); -__AVR_DEFREG(uint8_t, _EEDR, 0x40); -__AVR_DEFREG(EEAR_reg_t, _EEAR, 0x41); -__AVR_DEFREG(GTCCR_reg_t, _GTCCR, 0x43); -__AVR_DEFREG(TIMER_8bit_dev_t, TIMER0, 0x44); -__AVR_DEFREG(PLLCSR_reg_t, _PLLCSR, 0x49); -__AVR_DEFREG(_bit_reg_t, _GPIOR1, 0x4A); -__AVR_DEFREG(_bit_reg_t, _GPIOR2, 0x4B); -__AVR_DEFREG(SPCR_reg_t, _SPCR, 0x4C); -__AVR_DEFREG(SPSR_reg_t, _SPSR, 0x4D); -__AVR_DEFREG(uint8_t, _SPDR, 0x4E); -__AVR_DEFREG(ACSR_reg_t, _ACSR, 0x50); -__AVR_DEFREG(uint8_t, _OCDR, 0x51); -__AVR_DEFREG(SMCR_reg_t, _SMCR, 0x53); -__AVR_DEFREG(MCUSR_reg_t, _MCUSR, 0x54); -__AVR_DEFREG(MCUCR_reg_t, _MCUCR, 0x55); -__AVR_DEFREG(SPMCSR_reg_t, _SPMCSR, 0x57); -__AVR_DEFREG(RAMPZ_reg_t, _RAMPZ, 0x5B); -__AVR_DEFREG(SP_reg_t, _SP, 0x5D); -__AVR_DEFREG(SREG_reg_t, _SREG, 0x5F); -__AVR_DEFREG(WDTCSR_reg_t, _WDTCSR, 0x60); -__AVR_DEFREG(CLKPR_reg_t, _CLKPR, 0x61); -__AVR_DEFREG(PRR0_reg_t, _PRR0, 0x64); -__AVR_DEFREG(PRR1_reg_t, _PRR1, 0x65); -__AVR_DEFREG(uint8_t, _OSCCAL, 0x66); -__AVR_DEFREG(PCICR_reg_t, _PCICR, 0x68); -__AVR_DEFREG(EICRA_reg_t, _EICRA, 0x69); -__AVR_DEFREG(EICRB_reg_t, _EICRB, 0x6A); -__AVR_DEFREG(_bit_reg_t, _PCMSK0, 0x6B); -__AVR_DEFREG(TIMSK0_reg_t, _TIMSK0, 0x6E); -__AVR_DEFREG(TIMSK1_reg_t, _TIMSK1, 0x6F); -__AVR_DEFREG(TIMSK2_reg_t, _TIMSK2, 0x70); -__AVR_DEFREG(TIMSK3_reg_t, _TIMSK3, 0x71); -__AVR_DEFREG(XMCRA_reg_t, _XMCRA, 0x74); -__AVR_DEFREG(XMCRB_reg_t, _XMCRB, 0x75); -__AVR_DEFREG(uint16_t, _ADC, 0x78); -__AVR_DEFREG(ADCSRA_reg_t, _ADCSRA, 0x7A); -__AVR_DEFREG(ADCSRB_reg_t, _ADCSRB, 0x7B); -__AVR_DEFREG(ADMUX_reg_t, _ADMUX, 0x7C); -__AVR_DEFREG(DIDR0_reg_t, _DIDR0, 0x7E); -__AVR_DEFREG(DIDR1_reg_t, _DIDR1, 0x7F); -__AVR_DEFREG(TIMER_dev_t, TIMER1, 0x80); -__AVR_DEFREG(TIMER_dev_t, TIMER3, 0x90); -__AVR_DEFREG(UHCON_reg_t, _UHCON, 0x9E); -__AVR_DEFREG(UHINT_reg_t, _UHINT, 0x9F); -__AVR_DEFREG(UHIEN_reg_t, _UHIEN, 0xA0); -__AVR_DEFREG(UHADDR_reg_t, _UHADDR, 0xA1); -__AVR_DEFREG(UHFNUM_reg_t, _UHFNUM, 0xA2); -__AVR_DEFREG(uint8_t, _UHFLEN, 0xA4); -__AVR_DEFREG(uint8_t, _UPINRQX, 0xA5); -__AVR_DEFREG(UPINTX_reg_t, _UPINTX, 0xA6); -__AVR_DEFREG(UPNUM_reg_t, _UPNUM, 0xA7); -__AVR_DEFREG(UPRST_reg_t, _UPRST, 0xA8); -__AVR_DEFREG(UPCONX_reg_t, _UPCONX, 0xA9); -_AVR_DEFREG(UPCFG0X, 0xAA); -_AVR_DEFREG(UPCFG1X, 0xAB); -_AVR_DEFREG(UPSTAX, 0xAC); -__AVR_DEFREG(uint8_t, _UPCFG2X, 0xAD); -_AVR_DEFREG(UPIENX, 0xAE); -__AVR_DEFREG(uint8_t, _UPDATX, 0xAF); -__AVR_DEFREG(TIMER_8bit_dev_t, _TIMER2, 0xB0); -__AVR_DEFREG(ASSR_reg_t, _ASSR, 0xB6); -__AVR_DEFREG(uint8_t, _TWBR, 0xB8); -__AVR_DEFREG(TWSR_reg_t, _TWSR, 0xB9); -__AVR_DEFREG(TWAR_reg_t, _TWAR, 0xBA); -__AVR_DEFREG(uint8_t, _TWDR, 0xBB); -__AVR_DEFREG(TWCR_reg_t, _TWCR, 0xBC); -__AVR_DEFREG(TWAMR_reg_t, _TWAMR, 0xBD); -__AVR_DEFREG(USART_dev_t, USART1, 0xC8); -_AVR_DEFREG(UHWCON, 0xD7); -_AVR_DEFREG(USBCON, 0xD8); -_AVR_DEFREG(USBSTA, 0xD9); -_AVR_DEFREG(USBINT, 0xDA); -_AVR_DEFREG(UDPADD, 0xDB); -_AVR_DEFREG(OTGCON, 0xDD); -_AVR_DEFREG(OTGIEN, 0xDE); -_AVR_DEFREG(OTGINT, 0xDF); -_AVR_DEFREG(UDCON, 0xE0); -_AVR_DEFREG(UDINT, 0xE1); -_AVR_DEFREG(UDIEN, 0xE2); -_AVR_DEFREG(UDADDR, 0xE3); -_AVR_DEFREG(UDFNUM, 0xE4); -_AVR_DEFREG(UDMFN, 0xE6); -_AVR_DEFREG(UDTST, 0xE7); -_AVR_DEFREG(UEINTX, 0xE8); -_AVR_DEFREG(UENUM, 0xE9); -_AVR_DEFREG(UERST, 0xEA); -_AVR_DEFREG(UECONX, 0xEB); -_AVR_DEFREG(UECFG0X, 0xEC); -_AVR_DEFREG(UECFG1X, 0xED); -_AVR_DEFREG(UESTA0X, 0xEE); -_AVR_DEFREG(UESTA1X, 0xEF); -_AVR_DEFREG(UEIENX, 0xF0); -__AVR_DEFREG(uint8_t, _UEDATx, 0xF1); -_AVR_DEFREG(UEBCX, 0xF2); -_AVR_DEFREG(UEINT, 0xF4); -_AVR_DEFREG(UPERRX, 0xF5); -_AVR_DEFREG(UPBCX, 0xF6); -__AVR_DEFREG(uint8_t, _UPINT, 0xF8); -_AVR_DEFREG(OTGTCON, 0xF9); -#endif - -/* - HELPER FUNCTIONS -*/ -namespace AVRHelpers { - -template -struct no_volatile { - typedef T type; -}; - -template -struct no_volatile : public no_volatile {}; - -template -inline typename no_volatile ::type& dwrite( memRegType& V ) { return (typename no_volatile ::type&)V; } - -} // namespace AVRHelpers - -inline void _ATmega_resetperipherals() { - using namespace AVRHelpers; - - // Due to BOOTLOADER or other board inconsistencies we could get launched into Marlin FW - // with configuration that does not match the reset state in the documentation. That is why - // we should clean-reset the entire device. -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - SREG_reg_t __SREG; - __SREG._C = false; - __SREG._Z = false; - __SREG._N = false; - __SREG._V = false; - __SREG._S = false; - __SREG._H = false; - __SREG._T = false; - __SREG._I = false; - dwrite(_SREG) = __SREG; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - _RAMPZ._RAMPZ = 0; -#endif -#if defined(__AVR_TRM01__) - _EIND._EIND0 = false; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - _EEAR._EEAR = 0; - dwrite(_EEDR) = 0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - EECR_reg_t __EECR; - __EECR._EERE = false; - __EECR._EEPE = false; - __EECR._EEMPE = false; - __EECR._EERIE = false; - __EECR._EEPM0 = 0; - __EECR._EEPM1 = 0; - __EECR.reserved1 = 0; - dwrite(_EECR) = __EECR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _GPIOR2.val = 0; - _GPIOR1.val = 0; - _GPIOR0.val = 0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - XMCRA_reg_t __XMCRA; - __XMCRA._SRW0 = 0; - __XMCRA._SRW1 = 0; - __XMCRA._SRL = 0; - __XMCRA._SRE = 0; - dwrite(_XMCRA) = __XMCRA; - - XMCRB_reg_t __XMCRB; - __XMCRB._XMM = 0; - __XMCRB.reserved1 = 0; - __XMCRB._XMBK = false; - dwrite(_XMCRB) = __XMCRB; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - SMCR_reg_t __SMCR; - __SMCR._SE = false; - __SMCR._SM = 0; - __SMCR.reserved1 = 0; - dwrite(_SMCR) = __SMCR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - PRR0_reg_t __PRR0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) - __PRR0._PRADC = false; - __PRR0._PRUSART0 = false; - __PRR0._PRSPI = false; - __PRR0._PRTIM1 = false; - __PRR0.reserved1 = false; - __PRR0._PRTIM0 = false; - __PRR0._PRTIM2 = false; - __PRR0._PRTWI = false; -#elif defined(__AVR_TRM02__) - __PRR0._PRADC = false; - __PRR0._PRUSART0 = false; - __PRR0._PRSPI = false; - __PRR0._PRTIM1 = false; - __PRR0._PRUSART1 = false; - __PRR0._PRTIM0 = false; - __PRR0._PRTIM2 = false; - __PRR0._PRTWI = false; -#elif defined(__AVR_TRM04__) - __PRR0._PRADC = false; - __PRR0.reserved1 = false; - __PRR0._PRSPI = false; - __PRR0._PRTIM1 = false; - __PRR0.reserved2 = false; - __PRR0._PRTIM0 = false; - __PRR0._PRTIM2 = false; - __PRR0._PRTWI = false; -#endif - dwrite(_PRR0) = __PRR0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - PRR1_reg_t __PRR1; -#if defined(__AVR_TRM01__) - __PRR1._PRUSART1 = false; - __PRR1._PRUSART2 = false; - __PRR1._PRUSART3 = false; - __PRR1._PRTIM3 = false; - __PRR1._PRTIM4 = false; - __PRR1._PRTIM5 = false; - __PRR1.reserved1 = 0; -#elif defined(__AVR_TRM02__) - __PRR1._PRTIM3 = false; - __PRR1.reserved1 = 0; -#elif defined(__AVR_TRM04__) - __PRR1._PRUSART1 = false; - __PRR1.reserved1 = 0; -#endif - dwrite(_PRR1) = __PRR1; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - WDTCSR_reg_t __WDTCSR; - __WDTCSR._WDP0 = 0; - __WDTCSR._WDP1 = 0; - __WDTCSR._WDP2 = 0; - __WDTCSR._WDE = false; - __WDTCSR._WDCE = false; - __WDTCSR._WDP3 = 0; - __WDTCSR._WDIE = false; - __WDTCSR._WDIF = false; - dwrite(_WDTCSR) = __WDTCSR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _MCUCR._PUD = false; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - PORT_dev_t __PORT; - __PORT._PIN.val = 0; - __PORT._DDR.val = 0; - __PORT._PORT.val = 0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(_PORTA) = __PORT; - dwrite(_PORTC) = __PORT; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_PORTB) = __PORT; - dwrite(_PORTD) = __PORT; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - dwrite(_PORTE) = __PORT; - dwrite(_PORTF) = __PORT; -#endif - -#if defined(__AVR_TRM01__) - PORTG_dev_t __PORTG; - __PORTG._PIN.val = 0; - __PORTG._PIN.reserved1 = 0; - __PORTG._DDR.val = 0; - __PORTG._DDR.reserved1 = 0; - __PORTG._PORT.val = 0; - __PORTG._PORT.reserved1 = 0; - dwrite(_PORTG) = __PORTG; -#endif - -#if defined(__AVR_TRM03__) - PORTC_dev_t __PORTC; - __PORTC._PIN.val = 0; - __PORTC._PIN.reserved1 = 0; - __PORTC._DDR.val = 0; - __PORTC._DDR.reserved1 = 0; - __PORTC._PORT.val = 0; - __PORTC._PORT.reserved1 = 0; - dwrite(_PORTC) = __PORTC; -#endif - -#if defined(__AVR_TRM01__) - dwrite(_PORTH) = __PORT; - dwrite(_PORTJ) = __PORT; - dwrite(_PORTK) = __PORT; - dwrite(_PORTL) = __PORT; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - EICRA_reg_t __EICRA; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __EICRA._ISC0 = 0; - __EICRA._ISC1 = 0; - __EICRA._ISC2 = 0; - __EICRA._ISC3 = 0; -#elif defined(__AVR_TRM02__) - __EICRA._ISC0 = 0; - __EICRA._ISC1 = 0; - __EICRA._ISC2 = 0; - __EICRA.reserved1 = 0; -#elif defined(__AVR_TRM03__) - __EICRA._ISC0 = 0; - __EICRA._ISC1 = 0; - __EICRA.reserved1 = 0; -#endif - dwrite(_EICRA) = __EICRA; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - EICRB_reg_t __EICRB; - __EICRB._ISC4 = 0; - __EICRB._ISC5 = 0; - __EICRB._ISC6 = 0; - __EICRB._ISC7 = 0; - dwrite(_EICRB) = __EICRB; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - EIMSK_reg_t __EIMSK; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __EIMSK._INT0 = false; - __EIMSK._INT1 = false; - __EIMSK._INT2 = false; - __EIMSK._INT3 = false; - __EIMSK._INT4 = false; - __EIMSK._INT5 = false; - __EIMSK._INT6 = false; - __EIMSK._INT7 = false; -#elif defined(__AVR_TRM02__) - __EIMSK._INT0 = false; - __EIMSK._INT1 = false; - __EIMSK._INT2 = false; - __EIMSK.reserved1 = 0; -#elif defined(__AVR_TRM03__) - __EIMSK._INT0 = false; - __EIMSK._INT1 = false; - __EIMSK.reserved1 = 0; -#endif - dwrite(_EIMSK) = __EIMSK; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - EIFR_reg_t __EIFR; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __EIFR._INTF0 = false; - __EIFR._INTF1 = false; - __EIFR._INTF2 = false; - __EIFR._INTF3 = false; - __EIFR._INTF4 = false; - __EIFR._INTF5 = false; - __EIFR._INTF6 = false; - __EIFR._INTF7 = false; -#elif defined(__AVR_TRM02__) - __EIFR._INTF0 = false; - __EIFR._INTF1 = false; - __EIFR._INTF2 = false; - __EIFR.reserved1 = 0; -#elif defined(__AVR_TRM03__) - __EIFR._INTF0 = false; - __EIFR._INTF1 = false; - __EIFR.reserved1 = 0; -#endif - dwrite(_EIFR) = __EIFR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - PCICR_reg_t __PCICR; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) - __PCICR._PCIE0 = false; - __PCICR._PCIE1 = false; - __PCICR._PCIE2 = false; - __PCICR.reserved1 = 0; -#elif defined(__AVR_TRM02__) - __PCICR._PCIE0 = false; - __PCICR._PCIE1 = false; - __PCICR._PCIE2 = false; - __PCICR._PCIE3 = false; - __PCICR.reserved1 = 0; -#elif defined(__AVR_TRM04__) - __PCICR._PCIE0 = false; - __PCICR.reserved1 = 0; -#endif - dwrite(_PCICR) = __PCICR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - PCIFR_reg_t __PCIFR; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM03__) - __PCIFR._PCIF0 = false; - __PCIFR._PCIF1 = false; - __PCIFR._PCIF2 = false; - __PCIFR.reserved1 = 0; -#elif defined(__AVR_TRM02__) - __PCIFR._PCIF0 = false; - __PCIFR._PCIF1 = false; - __PCIFR._PCIF2 = false; - __PCIFR._PCIF3 = false; - __PCIFR.reserved1 = 0; -#elif defined(__AVR_TRM04__) - __PCIFR._PCIF0 = false; - __PCIFR.reserved1 = 0; -#endif - dwrite(_PCIFR) = __PCIFR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - _PCMSK0.val = 0; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - _PCMSK1.val = 0; - _PCMSK2.val = 0; -#endif -#if defined(__AVR_TRM02__) - _PCMSK3.val = 0; -#endif -#if defined(__AVR_TRM03__) - _PCMSK1.reserved1 = 0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIMER_8bit_dev_t __TIMER_8bit; - __TIMER_8bit._TCCRnA._WGMn0 = 0; - __TIMER_8bit._TCCRnA._WGMn1 = 0; - __TIMER_8bit._TCCRnA.reserved1 = 0; - __TIMER_8bit._TCCRnA._COMnB = 0; - __TIMER_8bit._TCCRnA._COMnA = 0; - __TIMER_8bit._TCCRnB._CSn = 0; - __TIMER_8bit._TCCRnB._WGMn2 = 0; - __TIMER_8bit._TCCRnB.reserved1 = 0; - __TIMER_8bit._TCCRnB._FOCnB = false; - __TIMER_8bit._TCCRnB._FOCnA = false, - __TIMER_8bit._TCNTn = 0; - __TIMER_8bit._OCRnA = 0; - __TIMER_8bit._OCRnB = 0; - dwrite(TIMER0) = __TIMER_8bit; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIMSK0_reg_t __TIMSK0; - __TIMSK0._TOIE0 = false; - __TIMSK0._OCIE0A = false; - __TIMSK0._OCIE0B = false; - __TIMSK0.reserved1 = 0; - dwrite(_TIMSK0) = __TIMSK0; - - TIFR0_reg_t __TIFR0; - __TIFR0._TOV0 = false; - __TIFR0._OCF0A = false; - __TIFR0._OCF0B = false; - __TIFR0.reserved1 = 0; - dwrite(_TIFR0) = __TIFR0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIMER_dev_t TIMER; - TIMER._TCCRnA._WGMn0 = 0; - TIMER._TCCRnA._WGMn1 = 0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - TIMER._TCCRnA._COMnC = 0; -#endif - TIMER._TCCRnA._COMnB = 0; - TIMER._TCCRnA._COMnA = 0; - TIMER._TCCRnB._CSn = 0; - TIMER._TCCRnB._WGMn2 = 0; - TIMER._TCCRnB.reserved1 = 0; - TIMER._TCCRnB._ICESn = 0; - TIMER._TCCRnB._ICNCn = 0; - TIMER._TCCRnC.reserved1 = 0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - TIMER._TCCRnC._FOCnC = false; -#endif - TIMER._TCCRnC._FOCnB = false; - TIMER._TCCRnC._FOCnA = false; - TIMER._TCNTn = 0; - TIMER._OCRnA = 0; - TIMER._OCRnB = 0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - TIMER._OCRnC = 0; -#endif - TIMER._ICRn = 0; - dwrite(TIMER1) = TIMER; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(TIMER3) = TIMER; -#endif -#if defined(__AVR_TRM01__) - dwrite(TIMER4) = TIMER; - dwrite(TIMER5) = TIMER; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIMSK1_reg_t __TIMSK1; - __TIMSK1._TOIE1 = false; - __TIMSK1._OCIE1A = false; - __TIMSK1._OCIE1B = false; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __TIMSK1._OCIE1C = false; -#endif - __TIMSK1.reserved1 = 0; - __TIMSK1._ICIE1 = false; - __TIMSK1.reserved2 = 0; - dwrite(_TIMSK1) = __TIMSK1; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - TIMSK3_reg_t __TIMSK3; - __TIMSK3._TOIE3 = false; - __TIMSK3._OCIE3A = false; - __TIMSK3._OCIE3B = false; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __TIMSK3._OCIE3C = false; -#endif - __TIMSK3.reserved1 = 0; - __TIMSK3._ICIE3 = false; - __TIMSK3.reserved2 = 0; - dwrite(_TIMSK3) = __TIMSK3; -#endif - -#if defined(__AVR_TRM01__) - TIMSK4_reg_t __TIMSK4; - __TIMSK4._TOIE4 = false; - __TIMSK4._OCIE4A = false; - __TIMSK4._OCIE4B = false; - __TIMSK4._OCIE4C = false; - __TIMSK4.reserved1 = false; - __TIMSK4._ICIE4 = false; - __TIMSK4.reserved2 = false; - dwrite(_TIMSK4) = __TIMSK4; - - TIMSK5_reg_t __TIMSK5; - __TIMSK5._TOIE5 = false; - __TIMSK5._OCIE5A = false; - __TIMSK5._OCIE5B = false; - __TIMSK5._OCIE5C = false; - __TIMSK5.reserved1 = 0; - __TIMSK5._ICIE5 = false; - __TIMSK5.reserved2 = 0; - dwrite(_TIMSK5) = __TIMSK5; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIFR1_reg_t __TIFR1; - __TIFR1._TOV1 = false; - __TIFR1._OCF1A = false; - __TIFR1._OCF1B = false; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __TIFR1._OCF1C = false; -#endif - __TIFR1.reserved1 = 0; - __TIFR1._ICF1 = false; - __TIFR1.reserved2 = 0; - dwrite(_TIFR1) = __TIFR1; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - TIFR3_reg_t __TIFR3; - __TIFR3._TOV3 = false; - __TIFR3._OCF3A = false; - __TIFR3._OCF3B = false; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - __TIFR3._OCF3C = false; -#endif - __TIFR3.reserved1 = 0; - __TIFR3._ICF3 = false; - __TIFR3.reserved2 = 0; - dwrite(_TIFR3) = __TIFR3; -#endif - -#if defined(__AVR_TRM01__) - TIFR4_reg_t __TIFR4; - __TIFR4._TOV4 = false; - __TIFR4._OCF4A = false; - __TIFR4._OCF4B = false; - __TIFR4._OCF4C = false; - __TIFR4.reserved1 = 0; - __TIFR4._ICF4 = false; - __TIFR4.reserved2 = 0; - dwrite(_TIFR4) = __TIFR4; - - TIFR5_reg_t __TIFR5; - __TIFR5._TOV5 = false; - __TIFR5._OCF5A = false; - __TIFR5._OCF5B = false; - __TIFR5._OCF5C = false; - __TIFR5.reserved1 = 0; - __TIFR5._ICF5 = false; - __TIFR5.reserved2 = 0; - dwrite(_TIFR5) = __TIFR5; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_TIMER2) = __TIMER_8bit; -#endif - -#if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - ASSR_reg_t __ASSR; - __ASSR._TCR2BUB = false; - __ASSR._TCR2AUB = false; - __ASSR._OCR2BUB = false; - __ASSR._OCR2AUB = false; - __ASSR._TCN2UB = false; - __ASSR._AS2 = false; - __ASSR._EXCLK = false; - __ASSR.reserved1 = 0; - dwrite(_ASSR) = __ASSR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - TIMSK2_reg_t __TIMSK2; - __TIMSK2._TOIE2 = false; - __TIMSK2._OCIE2A = false; - __TIMSK2._OCIE2B = false; - __TIMSK2.reserved1 = 0; - dwrite(_TIMSK2) = __TIMSK2; - - TIFR2_reg_t __TIFR2; - __TIFR2._TOV2 = false; - __TIFR2._OCF2A = false; - __TIFR2._OCF2B = false; - __TIFR2.reserved1 = 0; - dwrite(_TIFR2) = __TIFR2; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - SPCR_reg_t __SPCR; - __SPCR._SPR = 0; - __SPCR._CPHA = 0; - __SPCR._CPOL = 0; - __SPCR._MSTR = 0; - __SPCR._DORD = 0; - __SPCR._SPE = false; - __SPCR._SPIE = false; - dwrite(_SPCR) = __SPCR; - - SPSR_reg_t __SPSR; - __SPSR._SPI2X = false; - __SPSR.reserved1 = 0; - __SPSR._WCOL = false; - __SPSR._SPIF = false; - dwrite(_SPSR) = __SPSR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - USART_dev_t USART; - USART._UDRn = 0; - USART._UCSRnA._MPCM = false; - USART._UCSRnA._U2X = false; - USART._UCSRnA._UPE = false; - USART._UCSRnA._DOR = false; - USART._UCSRnA._FE = false; - USART._UCSRnA._UDRE = true; - USART._UCSRnA._TXC = false; - USART._UCSRnA._RXC = false; - USART._UCSRnB._TXB8 = false; - USART._UCSRnB._RXB8 = false; - USART._UCSRnB._UCSZn2 = false; - USART._UCSRnB._TXEN = false; - USART._UCSRnB._RXEN = false; - USART._UCSRnB._UDRIE = false; - USART._UCSRnB._TXCIE = false; - USART._UCSRnB._RXCIE = false; - USART._UCSRnC._UCPOL = false; - USART._UCSRnC._UCSZn0 = 1; - USART._UCSRnC._UCSZn1 = 1; - USART._UCSRnC._USBS = false; - USART._UCSRnC._UPM = 0; - USART._UCSRnC._UPM = 0; - USART._UCSRnC._UMSEL = 0; - USART._UBRRn._UBRR = 0; - USART._UBRRn.reserved1 = 0; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - dwrite(USART0) = USART; -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(USART1) = USART; -#endif -#if defined(__AVR_TRM01__) - dwrite(USART2) = USART; - dwrite(USART3) = USART; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_TWBR) = 0; - - TWCR_reg_t __TWCR; - __TWCR._TWIE = false; - __TWCR.reserved1 = 0; - __TWCR._TWEN = false; - __TWCR._TWWC = false; - __TWCR._TWSTO = false; - __TWCR._TWSTA = false; - __TWCR._TWEA = false; - __TWCR._TWINT = false; - dwrite(_TWCR) = __TWCR; - - TWSR_reg_t __TWSR; - __TWSR._TWPS0 = false; - __TWSR._TWPS1 = false; - __TWSR.reserved1 = 0; - __TWSR._TWS3 = 1; - __TWSR._TWS4 = 1; - __TWSR._TWS5 = 1; - __TWSR._TWS6 = 1; - __TWSR._TWS7 = 1; - dwrite(_TWSR) = __TWSR; - - dwrite(_TWDR) = 0xFF; - - TWAR_reg_t __TWAR; - __TWAR._TWGCE = false; - __TWAR._TWA = 0x7F; - dwrite(_TWAR) = __TWAR; - - TWAMR_reg_t __TWAMR; - __TWAMR.reserved1 = false; - __TWAMR._TWAM = 0; - dwrite(_TWAMR) = __TWAMR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - ADCSRB_reg_t __ADCSRB; - __ADCSRB._ADTS = 0; -#if defined(__AVR_TRM01__) - __ADCSRB._MUX5 = 0; -#endif - __ADCSRB.reserved1 = 0; - __ADCSRB._ACME = false; - __ADCSRB.reserved2 = 0; - dwrite(_ADCSRB) = __ADCSRB; - - ACSR_reg_t __ACSR; - __ACSR._ACIS = 0; - __ACSR._ACIC = false; - __ACSR._ACIE = false; - __ACSR._ACI = false; - __ACSR._ACO = false; - __ACSR._ACBG = false; - __ACSR._ACD = false; - dwrite(_ACSR) = __ACSR; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - DIDR1_reg_t __DIDR1; - __DIDR1._AIN0D = false; - __DIDR1._AIN1D = false; - __DIDR1.reserved1 = false; - dwrite(_DIDR1) = __DIDR1; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - ADMUX_reg_t __ADMUX; - __ADMUX._MUX0 = 0; - __ADMUX._MUX1 = 0; - __ADMUX._MUX2 = 0; - __ADMUX._MUX3 = 0; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - __ADMUX._MUX4 = 0; -#elif defined(__AVR_TRM03__) - __ADMUX.reserved1 = 0; -#endif - __ADMUX._ADLAR = 0; - __ADMUX._REFS0 = 0; - __ADMUX._REFS1 = 0; - dwrite(_ADMUX) = __ADMUX; - - ADCSRA_reg_t __ADCSRA; - __ADCSRA._ADPS = 0; - __ADCSRA._ADIE = false; - __ADCSRA._ADIF = false; - __ADCSRA._ADATE = false; - __ADCSRA._ADSC = false; - __ADCSRA._ADEN = false; - dwrite(_ADCSRA) = __ADCSRA; - - dwrite(_ADC) = 0; -#endif - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - SPMCSR_reg_t __SPMCSR; -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - __SPMCSR._SPMEN = false; - __SPMCSR._PGERS = false; - __SPMCSR._PGWRT = false; - __SPMCSR._BLBSET = false; - __SPMCSR._RWWSRE = false; - __SPMCSR._SIGRD = false; - __SPMCSR._RWWSB = false; - __SPMCSR._SPMIE = false; -#elif defined(__AVR_TRM03__) -#if defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) || defined(__AVR_ATmega328P__) - __SPMCSR._SPMEN = false; - __SPMCSR._PGERS = false; - __SPMCSR._PGWRT = false; - __SPMCSR._BLBSET = false; - __SPMCSR._RWWSRE = false; - __SPMCSR._SIGRD = false; - __SPMCSR._RWWSB = false; - __SPMCSR._SPMIE = false; -#else - __SPMCSR._SPMEN = false; - __SPMCSR._PGERS = false; - __SPMCSR._PGWRT = false; - __SPMCSR._BLBSET = false; - __SPMCSR.reserved1 = false; - __SPMCSR._SIGRD = false; - __SPMCSR.reserved2 = false; - __SPMCSR._SPMIE = false; -#endif -#endif - dwrite(_SPMCSR) = __SPMCSR; -#endif - - // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) -} - -struct pin_dev_state_t { -#if defined(__AVR_TRM01__) - uint8_t _SRE : 1; // port A - uint8_t _COM0B : 2; - uint8_t _COM1A : 2; - uint8_t _COM1B : 2; - uint8_t _COM1C : 2; - uint8_t _COM2A : 2; - uint8_t _COM2B : 2; - uint8_t _COM3A : 2; - uint8_t _COM3B : 2; - uint8_t _COM3C : 2; - uint8_t _COM4A : 2; - uint8_t _COM4B : 2; - uint8_t _COM4C : 2; - uint8_t _COM5A : 2; - uint8_t _COM5B : 2; - uint8_t _COM5C : 2; - uint8_t _PCIE0 : 1; - uint8_t _PCIE1 : 1; // INTn - uint8_t _PCIE2 : 1; - uint8_t _SPE : 1; - uint8_t _USART0_RXEN : 1; - uint8_t _USART0_TXEN : 1; - uint8_t _USART1_RXEN : 1; - uint8_t _USART1_TXEN : 1; - uint8_t _USART2_RXEN : 1; - uint8_t _USART2_TXEN : 1; - uint8_t _USART3_RXEN : 1; - uint8_t _USART3_TXEN : 1; - //uint8_t _JTAGEN : 1; - uint8_t _AS2 : 1; -#elif defined(__AVR_TRM02__) - uint8_t _PCIE0 : 1; - uint8_t _PCIE1 : 1; - uint8_t _PCIE2 : 1; - uint8_t _PCIE3 : 1; - uint8_t _ADC7D : 1; - uint8_t _ADC6D : 1; - uint8_t _ADC5D : 1; - uint8_t _ADC4D : 1; - uint8_t _ADC3D : 1; - uint8_t _ADC2D : 1; - uint8_t _ADC1D : 1; - uint8_t _ADC0D : 1; - uint8_t _SPE : 1; - uint8_t _COM0A : 2; - uint8_t _COM0B : 2; - uint8_t _COM2A : 2; - uint8_t _COM2B : 2; - uint8_t _COM1A : 2; - uint8_t _COM1B : 2; - //uint8_t _JTAGEN : 1; - uint8_t _AS2 : 1; - uint8_t _TWEN : 1; - uint8_t _USART1_TXEN : 1; - uint8_t _USART1_RXEN : 1; - uint8_t _USART0_TXEN : 1; - uint8_t _USART0_RXEN : 1; -#elif defined(__AVR_TRM03__) - uint8_t _AS2 : 1; - uint8_t _PCIE0 : 1; - uint8_t _PCIE1 : 1; - uint8_t _PCIE2 : 1; - uint8_t _SPE : 1; - uint8_t _COM2B : 2; - uint8_t _COM2A : 2; - uint8_t _COM1B : 2; - uint8_t _COM1A : 2; - uint8_t _COM0A : 2; - uint8_t _COM0B : 2; - uint8_t _TWEN : 1; - uint8_t _ADC7D : 1; - uint8_t _ADC6D : 1; - uint8_t _ADC5D : 1; - uint8_t _ADC4D : 1; - uint8_t _ADC3D : 1; - uint8_t _ADC2D : 1; - uint8_t _ADC1D : 1; - uint8_t _ADC0D : 1; - uint8_t _UMSEL : 2; - uint8_t _USART0_TXEN : 1; - uint8_t _USART0_RXEN : 1; -#elif defined(__AVR_TRM04__) - uint8_t _SRE : 1; - uint8_t _SPE : 1; - uint8_t _COM0B : 2; - uint8_t _COM1C : 2; - uint8_t _COM1B : 2; - uint8_t _COM1A : 2; - uint8_t _COM2A : 2; - uint8_t _COM2B : 2; - uint8_t _PCIE0 : 1; - uint8_t _USART1_RXEN : 1; - uint8_t _USART1_TXEN : 1; - uint8_t _TWEN : 1; - uint8_t _INT7 : 1; - uint8_t _INT6 : 1; - uint8_t _INT5 : 1; - uint8_t _INT4 : 1; - uint8_t _INT3 : 1; - uint8_t _INT2 : 1; - uint8_t _INT1 : 1; - uint8_t _INT0; - uint8_t _UVCONE : 1; - uint8_t _UIDE : 1; - //uint8_t _JTAGEN : 1; -#endif -}; - -// AVR ArduinoCore is written like a hack-job (random peripherals enabled all-the-time). - -enum class eATmegaPort { -#if defined(__AVR_TRM01__) - PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F, PORT_G, PORT_H, PORT_J, PORT_K, PORT_L -#elif defined(__AVR_TRM02__) - PORT_A, PORT_B, PORT_C, PORT_D -#elif defined(__AVR_TRM03__) - PORT_B, PORT_C, PORT_D -#elif defined(__AVR_TRM04__) - PORT_A, PORT_B, PORT_C, PORT_D, PORT_E, PORT_F -#endif -}; - -struct ATmegaPinInfo { - eATmegaPort port; - uint8_t pinidx; -}; - -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) -#define _SPA_DIO_DDRA (eATmegaPort::PORT_A) -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) -#define _SPA_DIO_DDRB (eATmegaPort::PORT_B) -#define _SPA_DIO_DDRC (eATmegaPort::PORT_C) -#define _SPA_DIO_DDRD (eATmegaPort::PORT_D) -#endif -#if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) -#define _SPA_DIO_DDRE (eATmegaPort::PORT_E) -#define _SPA_DIO_DDRF (eATmegaPort::PORT_F) -#endif -#if defined(__AVR_TRM01__) -#define _SPA_DIO_DDRG (eATmegaPort::PORT_G) -#define _SPA_DIO_DDRH (eATmegaPort::PORT_H) -#define _SPA_DIO_DDRJ (eATmegaPort::PORT_J) -#define _SPA_DIO_DDRK (eATmegaPort::PORT_K) -#define _SPA_DIO_DDRL (eATmegaPort::PORT_L) -#endif - -#define __SPA_IFPORT_STMT(dr) if (ddrp == &D##dr) port = _SPA_DIO_D##dr; - -#ifdef _SPA_DIO_DDRA -#define _SPA_IFPORT_PORTA __SPA_IFPORT_STMT(DRA) -#else -#define _SPA_IFPORT_PORTA -#endif -#ifdef _SPA_DIO_DDRB -#define _SPA_IFPORT_PORTB __SPA_IFPORT_STMT(DRB) -#else -#define _SPA_IFPORT_PORTB -#endif -#ifdef _SPA_DIO_DDRC -#define _SPA_IFPORT_PORTC __SPA_IFPORT_STMT(DRC) -#else -#define _SPA_IFPORT_PORTC -#endif -#ifdef _SPA_DIO_DDRD -#define _SPA_IFPORT_PORTD __SPA_IFPORT_STMT(DRD) -#else -#define _SPA_IFPORT_PORTD -#endif -#ifdef _SPA_DIO_DDRE -#define _SPA_IFPORT_PORTE __SPA_IFPORT_STMT(DRE) -#else -#define _SPA_IFPORT_PORTE -#endif -#ifdef _SPA_DIO_DDRF -#define _SPA_IFPORT_PORTF __SPA_IFPORT_STMT(DRF) -#else -#define _SPA_IFPORT_PORTF -#endif -#ifdef _SPA_DIO_DDRG -#define _SPA_IFPORT_PORTG __SPA_IFPORT_STMT(DRG) -#else -#define _SPA_IFPORT_PORTG -#endif -#ifdef _SPA_DIO_DDRH -#define _SPA_IFPORT_PORTH __SPA_IFPORT_STMT(DRH) -#else -#define _SPA_IFPORT_PORTH -#endif -#ifdef _SPA_DIO_DDRJ -#define _SPA_IFPORT_PORTJ __SPA_IFPORT_STMT(DRJ) -#else -#define _SPA_IFPORT_PORTJ -#endif -#ifdef _SPA_DIO_DDRK -#define _SPA_IFPORT_PORTK __SPA_IFPORT_STMT(DRK) -#else -#define _SPA_IFPORT_PORTK -#endif -#ifdef _SPA_DIO_DDRL -#define _SPA_IFPORT_PORTL __SPA_IFPORT_STMT(DRL) -#else -#define _SPA_IFPORT_PORTL -#endif - -#define _SPA_RESOLVE_DIO(ddr) _SPA_DIO_##ddr -#define _SPA_DIOn_PORTRET(val, n) if (val == n) { \ - auto *ddrp = &DIO##n##_DDR; \ - eATmegaPort port; \ - _SPA_IFPORT_PORTA \ - _SPA_IFPORT_PORTB \ - _SPA_IFPORT_PORTC \ - _SPA_IFPORT_PORTD \ - _SPA_IFPORT_PORTE \ - _SPA_IFPORT_PORTF \ - _SPA_IFPORT_PORTG \ - _SPA_IFPORT_PORTH \ - _SPA_IFPORT_PORTJ \ - _SPA_IFPORT_PORTK \ - _SPA_IFPORT_PORTL \ - return { port, DIO##n##_PIN }; \ - } - -inline ATmegaPinInfo _ATmega_getPinInfo(uint8_t pin) { -#if DIO_NUM > 0 - _SPA_DIOn_PORTRET(pin, 0) -#endif -#if DIO_NUM > 1 - _SPA_DIOn_PORTRET(pin, 1) -#endif -#if DIO_NUM > 2 - _SPA_DIOn_PORTRET(pin, 2) -#endif -#if DIO_NUM > 3 - _SPA_DIOn_PORTRET(pin, 3) -#endif -#if DIO_NUM > 4 - _SPA_DIOn_PORTRET(pin, 4) -#endif -#if DIO_NUM > 5 - _SPA_DIOn_PORTRET(pin, 5) -#endif -#if DIO_NUM > 6 - _SPA_DIOn_PORTRET(pin, 6) -#endif -#if DIO_NUM > 7 - _SPA_DIOn_PORTRET(pin, 7) -#endif -#if DIO_NUM > 8 - _SPA_DIOn_PORTRET(pin, 8) -#endif -#if DIO_NUM > 9 - _SPA_DIOn_PORTRET(pin, 9) -#endif - -#if DIO_NUM > 10 - _SPA_DIOn_PORTRET(pin, 10) -#endif -#if DIO_NUM > 11 - _SPA_DIOn_PORTRET(pin, 11) -#endif -#if DIO_NUM > 12 - _SPA_DIOn_PORTRET(pin, 12) -#endif -#if DIO_NUM > 13 - _SPA_DIOn_PORTRET(pin, 13) -#endif -#if DIO_NUM > 14 - _SPA_DIOn_PORTRET(pin, 14) -#endif -#if DIO_NUM > 15 - _SPA_DIOn_PORTRET(pin, 15) -#endif -#if DIO_NUM > 16 - _SPA_DIOn_PORTRET(pin, 16) -#endif -#if DIO_NUM > 17 - _SPA_DIOn_PORTRET(pin, 17) -#endif -#if DIO_NUM > 18 - _SPA_DIOn_PORTRET(pin, 18) -#endif -#if DIO_NUM > 19 - _SPA_DIOn_PORTRET(pin, 19) -#endif - -#if DIO_NUM > 20 - _SPA_DIOn_PORTRET(pin, 20) -#endif -#if DIO_NUM > 21 - _SPA_DIOn_PORTRET(pin, 21) -#endif -#if DIO_NUM > 22 - _SPA_DIOn_PORTRET(pin, 22) -#endif -#if DIO_NUM > 23 - _SPA_DIOn_PORTRET(pin, 23) -#endif -#if DIO_NUM > 24 - _SPA_DIOn_PORTRET(pin, 24) -#endif -#if DIO_NUM > 25 - _SPA_DIOn_PORTRET(pin, 25) -#endif -#if DIO_NUM > 26 - _SPA_DIOn_PORTRET(pin, 26) -#endif -#if DIO_NUM > 27 - _SPA_DIOn_PORTRET(pin, 27) -#endif -#if DIO_NUM > 28 - _SPA_DIOn_PORTRET(pin, 28) -#endif -#if DIO_NUM > 29 - _SPA_DIOn_PORTRET(pin, 29) -#endif - -#if DIO_NUM > 30 - _SPA_DIOn_PORTRET(pin, 30) -#endif -#if DIO_NUM > 31 - _SPA_DIOn_PORTRET(pin, 31) -#endif -#if DIO_NUM > 32 - _SPA_DIOn_PORTRET(pin, 32) -#endif -#if DIO_NUM > 33 - _SPA_DIOn_PORTRET(pin, 33) -#endif -#if DIO_NUM > 34 - _SPA_DIOn_PORTRET(pin, 34) -#endif -#if DIO_NUM > 35 - _SPA_DIOn_PORTRET(pin, 35) -#endif -#if DIO_NUM > 36 - _SPA_DIOn_PORTRET(pin, 36) -#endif -#if DIO_NUM > 37 - _SPA_DIOn_PORTRET(pin, 37) -#endif -#if DIO_NUM > 38 - _SPA_DIOn_PORTRET(pin, 38) -#endif -#if DIO_NUM > 39 - _SPA_DIOn_PORTRET(pin, 39) -#endif - -#if DIO_NUM > 40 - _SPA_DIOn_PORTRET(pin, 40) -#endif -#if DIO_NUM > 41 - _SPA_DIOn_PORTRET(pin, 41) -#endif -#if DIO_NUM > 42 - _SPA_DIOn_PORTRET(pin, 42) -#endif -#if DIO_NUM > 43 - _SPA_DIOn_PORTRET(pin, 43) -#endif -#if DIO_NUM > 44 - _SPA_DIOn_PORTRET(pin, 44) -#endif -#if DIO_NUM > 45 - _SPA_DIOn_PORTRET(pin, 45) -#endif -#if DIO_NUM > 46 - _SPA_DIOn_PORTRET(pin, 46) -#endif -#if DIO_NUM > 47 - _SPA_DIOn_PORTRET(pin, 47) -#endif -#if DIO_NUM > 48 - _SPA_DIOn_PORTRET(pin, 48) -#endif -#if DIO_NUM > 49 - _SPA_DIOn_PORTRET(pin, 49) -#endif - -#if DIO_NUM > 50 - _SPA_DIOn_PORTRET(pin, 50) -#endif -#if DIO_NUM > 51 - _SPA_DIOn_PORTRET(pin, 51) -#endif -#if DIO_NUM > 52 - _SPA_DIOn_PORTRET(pin, 52) -#endif -#if DIO_NUM > 53 - _SPA_DIOn_PORTRET(pin, 53) -#endif -#if DIO_NUM > 54 - _SPA_DIOn_PORTRET(pin, 54) -#endif -#if DIO_NUM > 55 - _SPA_DIOn_PORTRET(pin, 55) -#endif -#if DIO_NUM > 56 - _SPA_DIOn_PORTRET(pin, 56) -#endif -#if DIO_NUM > 57 - _SPA_DIOn_PORTRET(pin, 57) -#endif -#if DIO_NUM > 58 - _SPA_DIOn_PORTRET(pin, 58) -#endif -#if DIO_NUM > 59 - _SPA_DIOn_PORTRET(pin, 59) -#endif - -#if DIO_NUM > 60 - _SPA_DIOn_PORTRET(pin, 60) -#endif -#if DIO_NUM > 61 - _SPA_DIOn_PORTRET(pin, 61) -#endif -#if DIO_NUM > 62 - _SPA_DIOn_PORTRET(pin, 62) -#endif -#if DIO_NUM > 63 - _SPA_DIOn_PORTRET(pin, 63) -#endif -#if DIO_NUM > 64 - _SPA_DIOn_PORTRET(pin, 64) -#endif -#if DIO_NUM > 65 - _SPA_DIOn_PORTRET(pin, 65) -#endif -#if DIO_NUM > 66 - _SPA_DIOn_PORTRET(pin, 66) -#endif -#if DIO_NUM > 67 - _SPA_DIOn_PORTRET(pin, 67) -#endif -#if DIO_NUM > 68 - _SPA_DIOn_PORTRET(pin, 68) -#endif -#if DIO_NUM > 69 - _SPA_DIOn_PORTRET(pin, 69) -#endif - -#if DIO_NUM > 70 - _SPA_DIOn_PORTRET(pin, 70) -#endif -#if DIO_NUM > 71 - _SPA_DIOn_PORTRET(pin, 71) -#endif -#if DIO_NUM > 72 - _SPA_DIOn_PORTRET(pin, 72) -#endif -#if DIO_NUM > 73 - _SPA_DIOn_PORTRET(pin, 73) -#endif -#if DIO_NUM > 74 - _SPA_DIOn_PORTRET(pin, 74) -#endif -#if DIO_NUM > 75 - _SPA_DIOn_PORTRET(pin, 75) -#endif -#if DIO_NUM > 76 - _SPA_DIOn_PORTRET(pin, 76) -#endif -#if DIO_NUM > 77 - _SPA_DIOn_PORTRET(pin, 77) -#endif -#if DIO_NUM > 78 - _SPA_DIOn_PORTRET(pin, 78) -#endif -#if DIO_NUM > 79 - _SPA_DIOn_PORTRET(pin, 79) -#endif - -#if DIO_NUM > 80 - _SPA_DIOn_PORTRET(pin, 80) -#endif -#if DIO_NUM > 81 - _SPA_DIOn_PORTRET(pin, 81) -#endif -#if DIO_NUM > 82 - _SPA_DIOn_PORTRET(pin, 82) -#endif -#if DIO_NUM > 83 - _SPA_DIOn_PORTRET(pin, 83) -#endif -#if DIO_NUM > 84 - _SPA_DIOn_PORTRET(pin, 84) -#endif -#if DIO_NUM > 85 - _SPA_DIOn_PORTRET(pin, 85) -#endif -#if DIO_NUM > 86 - _SPA_DIOn_PORTRET(pin, 86) -#endif -#if DIO_NUM > 87 - _SPA_DIOn_PORTRET(pin, 87) -#endif -#if DIO_NUM > 88 - _SPA_DIOn_PORTRET(pin, 88) -#endif -#if DIO_NUM > 89 - _SPA_DIOn_PORTRET(pin, 89) -#endif - - // Default. -#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - return { eATmegaPort::PORT_A, 0 }; -#elif defined(__AVR_TRM03__) - return { eATmegaPort::PORT_B, 0 }; -#endif -} - -enum class eATmegaPeripheral { - UNDEFINED, -#if defined(__AVR_TRM01__) - PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PUSART2, PUSART3, PTIM3, PTIM4, PTIM5 -#elif defined(__AVR_TRM02__) - PADC, PUSART0, PSPI, PTIM1, PUSART1, PTIM0, PTIM2, PTWI, PTIM3 -#elif defined(__AVR_TRM03__) - PADC, PUSART0, PSPI, PTIM1, PTIM0, PTIM2, PTWI -#elif defined(__AVR_TRM04__) - PADC, PSPI, PTIM1, PTIM0, PTIM2, PTWI, PUSART1, PTIM3, PUSB -#endif - , NUM_PERIPHERALS -}; - -enum class eATmegaPinFunc : uint8_t { -#if defined(__AVR_TRM01__) - EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, - EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, - EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - TOC0A, TOC0B, TOC1A, TOC1B, TOC1C, TOC2A, TOC2B, TOC3C, TOC3B, TOC3A, TOC4C, TOC4B, TOC4A, TOC5C, TOC5B, TOC5A, - EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, - PCI0, PCI1, PCI2, PCI3, PCI4, PCI5, PCI6, PCI7, - PCI8, PCI9, PCI10, PCI11, PCI12, PCI13, PCI14, PCI15, - PCI16, PCI17, PCI18, PCI19, PCI20, PCI21, PCI22, PCI23, - SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, - TOSC1, TOSC2, - TIMER0_CLKI, TIMER1_CLKI, TIMER3_CLKI, TIMER4_CLKI, TIMER5_CLKI, - TIMER1_ICP, TIMER3_ICP, TIMER5_ICP, TIMER4_ICP, - USART0_CLK, USART1_CLK, USART2_CLK, USART3_CLK, - USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, USART2_TXD, USART2_RXD, USART3_TXD, USART3_RXD, - TWI_SDA, TWI_CLK, - CLK0, PDO, PDI, - AIN0, AIN1, - ADC15, ADC14, ADC13, ADC12, ADC11, ADC10, ADC9, ADC8, - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 -#elif defined(__AVR_TRM02__) - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, - SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, - PCI31, PCI30, PCI29, PCI28, PCI27, PCI26, PCI25, PCI24, - PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, - PCI15, PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, - PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, - EINT2, EINT1, EINT0, - TIMER3_ICP, - TIMER3_ECI, TIMER1_ECI, TIMER0_ECI, - TIMER1_ICP, - TOC3B, TOC3A, TOC2A, TOC2B, TOC1A, TOC1B, TOC0B, TOC0A, - AIN1, AIN0, - USART0_CLK, USART1_CLK, - USART0_TXD, USART0_RXD, USART1_TXD, USART1_RXD, - CLK0, - TOSC2, TOSC1, - TWI_SDA, TWI_CLK -#elif defined(__AVR_TRM03__) - ADC5, ADC4, ADC3, ADC2, ADC1, ADC0, - XTAL2, XTAL1, - TOSC2, TOSC1, - SPI_SCK, SPI_MISO, SPI_MOSI, SPI_CS, - TOC2B, TOC2A, TOC1B, TOC1A, TOC0A, TOC0B, - TIMER1_ICP, - TIMER1_ECI, TIMER0_ECI, - TWI_CLK, TWI_SDA, - PCI23, PCI22, PCI21, PCI20, PCI19, PCI18, PCI17, PCI16, - PCI14, PCI13, PCI12, PCI11, PCI10, PCI9, PCI8, - PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, - CLK0, - AIN1, AIN0, - USART_CLK, - USART_TXD, USART_RXD, - EINT1, EINT0 -#elif defined(__AVR_TRM04__) - EXTMEM_AD15, EXTMEM_AD14, EXTMEM_AD13, EXTMEM_AD12, EXTMEM_AD11, EXTMEM_AD10, EXTMEM_AD9, EXTMEM_AD8, - EXTMEM_AD7, EXTMEM_AD6, EXTMEM_AD5, EXTMEM_AD4, EXTMEM_AD3, EXTMEM_AD2, EXTMEM_AD1, EXTMEM_AD0, - EXTMEM_ALE, EXTMEM_RD, EXTMEM_WR, - TOC0B, TOC0A, TOC1C, TOC1B, TOC1A, TOC2B, TOC2A, TOC3A, TOC3B, TOC3C, - CLK0, PDO, PDI, - SPI_MISO, SPI_MOSI, SPI_SCK, SPI_CS, - TIMER3_ICP, TIMER1_ICP, - TIMER3_CLKI, TIMER0_CLKI, TIMER1_CLKI, - USART1_CLK, USART1_TXD, USART1_RXD, - EINT7, EINT6, EINT5, EINT4, EINT3, EINT2, EINT1, EINT0, - PCI7, PCI6, PCI5, PCI4, PCI3, PCI2, PCI1, PCI0, - TWI_SDA, TWI_CLK, - AIN1, AIN0, - TOSC2, - UID, UVCON, - ADC7, ADC6, ADC5, ADC4, ADC3, ADC2, ADC1, ADC0 -#endif - , NUM_FUNCS -}; - -#ifndef countof -#define countof(x) (sizeof(x) / sizeof(*x)) -#endif - -struct ATmegaPinFunctions { - inline ATmegaPinFunctions(const eATmegaPinFunc *funcs, uint8_t cnt) noexcept : funcs(funcs), cnt(cnt) {} - inline ATmegaPinFunctions() = default; - inline ATmegaPinFunctions(const ATmegaPinFunctions&) = default; - - const eATmegaPinFunc *funcs = nullptr; - uint8_t cnt = 0; - - inline bool hasFunc(eATmegaPinFunc query) const { - for (uint8_t n = 0; n < this->cnt; n++) { - eATmegaPinFunc func = this->funcs[n]; - - if (func == query) - return true; - } - return false; - } - template - inline bool hasFunc(eATmegaPinFunc func, otherItemType&&... items) const { - return hasFunc(func) || hasFunc(((otherItemType&&)items)...); - } - - template - inline void iterate(callbackType&& cb) const { - for (uint8_t n = 0; n < this->cnt; n++) { - eATmegaPinFunc func = this->funcs[n]; - - cb(func); - } - } -}; - -ATmegaPinFunctions _ATmega_getPinFunctions(int pin); - -struct ATmegaPinFuncSet { - inline ATmegaPinFuncSet() noexcept { - for (bool& f : this->funcs) - f = false; - } - template - inline ATmegaPinFuncSet(eATmegaPinFunc func, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { - add(func, ((funcItemType&&)items)...); - } - template - inline ATmegaPinFuncSet(int pin, funcItemType&&... items) noexcept : ATmegaPinFuncSet() { - addFromPin(pin, ((funcItemType&&)items)...); - } - inline ATmegaPinFuncSet(const ATmegaPinFuncSet&) = default; - - inline void add(eATmegaPinFunc value) noexcept { - this->funcs[(uint8_t)value] = true; - } - template - inline void add(eATmegaPinFunc value, funcItemType&&... items) { - add(value); - add(((eATmegaPinFunc&&)items)...); - } - - inline void addFromPin(int pin) noexcept { - ATmegaPinFunctions funcs = _ATmega_getPinFunctions(pin); - - funcs.iterate( - [this]( eATmegaPinFunc func ) noexcept { - this->add(func); - } - ); - } - template - inline void addFromPin(int pin, itemType&&... items) noexcept { - addFromPin(pin); - addFromPin(((itemType&&)items)...); - } - - inline bool hasFunc(eATmegaPinFunc value) const noexcept { - return this->funcs[(uint8_t)value]; - } - - inline bool hasAnyFunc() const noexcept { - return false; - } - template - inline bool hasAnyFunc(funcItem&& item, otherFuncItem&&... funcs) const noexcept { - return hasFunc(item) || hasAnyFunc(((otherFuncItem&&)funcs)...); - } - - template - inline void iterate(callbackType&& cb) const { - for (uint8_t n = 1; n < countof(this->funcs); n++) { - const bool& f = this->funcs[n]; - if (f) { - cb((eATmegaPinFunc)n); - } - } - } - -private: - bool funcs[(uint8_t)eATmegaPinFunc::NUM_FUNCS]; -}; - -inline void _ATmega_setPeripheralPower(eATmegaPeripheral peri, bool fullPower) { - bool reducePower = (fullPower == false); - switch(peri) { -#if defined(__AVR_TRM01__) - case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; - case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; - case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; - case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; - case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; - case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; - case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; - case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; - case eATmegaPeripheral::PUSART2: _PRR1._PRUSART2 = reducePower; break; - case eATmegaPeripheral::PUSART3: _PRR1._PRUSART3 = reducePower; break; - case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; - case eATmegaPeripheral::PTIM4: _PRR1._PRTIM4 = reducePower; break; - case eATmegaPeripheral::PTIM5: _PRR1._PRTIM5 = reducePower; break; -#elif defined(__AVR_TRM02__) - case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; - case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; - case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; - case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; - case eATmegaPeripheral::PUSART1: _PRR0._PRUSART1 = reducePower; break; - case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; - case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; - case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; - case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; -#elif defined(__AVR_TRM03__) - case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; - case eATmegaPeripheral::PUSART0: _PRR0._PRUSART0 = reducePower; break; - case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; - case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; - case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; - case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; - case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; -#elif defined(__AVR_TRM04__) - case eATmegaPeripheral::PADC: _PRR0._PRADC = reducePower; break; - case eATmegaPeripheral::PSPI: _PRR0._PRSPI = reducePower; break; - case eATmegaPeripheral::PTIM1: _PRR0._PRTIM1 = reducePower; break; - case eATmegaPeripheral::PTIM0: _PRR0._PRTIM0 = reducePower; break; - case eATmegaPeripheral::PTIM2: _PRR0._PRTIM2 = reducePower; break; - case eATmegaPeripheral::PTWI: _PRR0._PRTWI = reducePower; break; - case eATmegaPeripheral::PUSART1: _PRR1._PRUSART1 = reducePower; break; - case eATmegaPeripheral::PTIM3: _PRR1._PRTIM3 = reducePower; break; - case eATmegaPeripheral::PUSB: _PRR1._PRUSB = reducePower; break; -#endif - case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; - } -} - -inline bool _ATmega_getPeripheralPower(eATmegaPeripheral peri) { - switch(peri) { -#if defined(__AVR_TRM01__) - case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; - case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; - case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; - case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; - case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; - case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; - case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; - case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; - case eATmegaPeripheral::PUSART2: return _PRR1._PRUSART2 == false; - case eATmegaPeripheral::PUSART3: return _PRR1._PRUSART3 == false; - case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; - case eATmegaPeripheral::PTIM4: return _PRR1._PRTIM4 == false; - case eATmegaPeripheral::PTIM5: return _PRR1._PRTIM5 == false; -#elif defined(__AVR_TRM02__) - case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; - case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; - case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; - case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; - case eATmegaPeripheral::PUSART1: return _PRR0._PRUSART1 == false; - case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; - case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; - case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; - case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; -#elif defined(__AVR_TRM03__) - case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; - case eATmegaPeripheral::PUSART0: return _PRR0._PRUSART0 == false; - case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; - case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; - case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; - case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; - case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; -#elif defined(__AVR_TRM04__) - case eATmegaPeripheral::PADC: return _PRR0._PRADC == false; - case eATmegaPeripheral::PSPI: return _PRR0._PRSPI == false; - case eATmegaPeripheral::PTIM1: return _PRR0._PRTIM1 == false; - case eATmegaPeripheral::PTIM0: return _PRR0._PRTIM0 == false; - case eATmegaPeripheral::PTIM2: return _PRR0._PRTIM2 == false; - case eATmegaPeripheral::PTWI: return _PRR0._PRTWI == false; - case eATmegaPeripheral::PUSART1: return _PRR1._PRUSART1 == false; - case eATmegaPeripheral::PTIM3: return _PRR1._PRTIM3 == false; - case eATmegaPeripheral::PUSB: return _PRR1._PRUSB == false; -#endif - case eATmegaPeripheral::UNDEFINED: case eATmegaPeripheral::NUM_PERIPHERALS: break; - } - return false; -} - -inline eATmegaPeripheral _ATmega_getPeripheralForFunc( eATmegaPinFunc func ) { - // In C++20 there is the "using-enum" statement. I wish we had C++20 over here... - //using enum eATmegaPinFunc - switch(func) { -#if defined(__AVR_TRM01__) - case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1C: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; - case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::TOC4A: case eATmegaPinFunc::TOC4B: case eATmegaPinFunc::TOC4C: return eATmegaPeripheral::PTIM4; - case eATmegaPinFunc::TOC5A: case eATmegaPinFunc::TOC5B: case eATmegaPinFunc::TOC5C: return eATmegaPeripheral::PTIM5; - case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; - case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TIMER1_CLKI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TIMER3_CLKI: case eATmegaPinFunc::TIMER3_ICP: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::TIMER4_CLKI: case eATmegaPinFunc::TIMER4_ICP: return eATmegaPeripheral::PTIM4; - case eATmegaPinFunc::TIMER5_CLKI: case eATmegaPinFunc::TIMER5_ICP: return eATmegaPeripheral::PTIM5; - case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; - case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; - case eATmegaPinFunc::USART2_CLK: case eATmegaPinFunc::USART2_TXD: case eATmegaPinFunc::USART2_RXD: return eATmegaPeripheral::PUSART2; - case eATmegaPinFunc::USART3_CLK: case eATmegaPinFunc::USART3_TXD: case eATmegaPinFunc::USART3_RXD: return eATmegaPeripheral::PUSART3; - case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; - case eATmegaPinFunc::ADC15: case eATmegaPinFunc::ADC14: case eATmegaPinFunc::ADC13: case eATmegaPinFunc::ADC12: case eATmegaPinFunc::ADC11: case eATmegaPinFunc::ADC10: case eATmegaPinFunc::ADC9: case eATmegaPinFunc::ADC8: - case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: - return eATmegaPeripheral::PADC; -#elif defined(__AVR_TRM02__) - case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: - return eATmegaPeripheral::PADC; - case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; - case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_ECI: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::TIMER1_ECI: case eATmegaPinFunc::TIMER1_ICP: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3A: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::TOC2A: case eATmegaPinFunc::TOC2B: return eATmegaPeripheral::PTIM2; - case eATmegaPinFunc::TOC1A: case eATmegaPinFunc::TOC1B: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::USART0_CLK: case eATmegaPinFunc::USART0_TXD: case eATmegaPinFunc::USART0_RXD: return eATmegaPeripheral::PUSART0; - case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; - case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; -#elif defined(__AVR_TRM03__) - case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: - return eATmegaPeripheral::PADC; - case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; - case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; - case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TOC0A: case eATmegaPinFunc::TOC0B: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_ECI: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TIMER0_ECI: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TWI_CLK: case eATmegaPinFunc::TWI_SDA: return eATmegaPeripheral::PTWI; - case eATmegaPinFunc::USART_CLK: case eATmegaPinFunc::USART_TXD: case eATmegaPinFunc::USART_RXD: return eATmegaPeripheral::PUSART0; -#elif defined(__AVR_TRM04__) - case eATmegaPinFunc::TOC0B: case eATmegaPinFunc::TOC0A: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::TOC1C: case eATmegaPinFunc::TOC1B: case eATmegaPinFunc::TOC1A: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TOC2B: case eATmegaPinFunc::TOC2A: return eATmegaPeripheral::PTIM2; - case eATmegaPinFunc::TOC3A: case eATmegaPinFunc::TOC3B: case eATmegaPinFunc::TOC3C: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::SPI_MISO: case eATmegaPinFunc::SPI_MOSI: case eATmegaPinFunc::SPI_SCK: case eATmegaPinFunc::SPI_CS: return eATmegaPeripheral::PSPI; - case eATmegaPinFunc::TIMER3_ICP: case eATmegaPinFunc::TIMER3_CLKI: return eATmegaPeripheral::PTIM3; - case eATmegaPinFunc::TIMER1_ICP: case eATmegaPinFunc::TIMER1_CLKI: return eATmegaPeripheral::PTIM1; - case eATmegaPinFunc::TIMER0_CLKI: return eATmegaPeripheral::PTIM0; - case eATmegaPinFunc::USART1_CLK: case eATmegaPinFunc::USART1_TXD: case eATmegaPinFunc::USART1_RXD: return eATmegaPeripheral::PUSART1; - case eATmegaPinFunc::TWI_SDA: case eATmegaPinFunc::TWI_CLK: return eATmegaPeripheral::PTWI; - case eATmegaPinFunc::UID: case eATmegaPinFunc::UVCON: return eATmegaPeripheral::PUSB; - case eATmegaPinFunc::ADC7: case eATmegaPinFunc::ADC6: case eATmegaPinFunc::ADC5: case eATmegaPinFunc::ADC4: case eATmegaPinFunc::ADC3: case eATmegaPinFunc::ADC2: case eATmegaPinFunc::ADC1: case eATmegaPinFunc::ADC0: - return eATmegaPeripheral::PADC; -#endif - // There are quite some pin functions that have no peripheral assignment, and that is OK! - default: break; - } - return eATmegaPeripheral::UNDEFINED; -} - -struct ATmegaPeripheralSet { - inline ATmegaPeripheralSet() noexcept { - for (bool& f : this->funcs) - f = false; - } - template - inline ATmegaPeripheralSet(funcItemType&&... items) noexcept : ATmegaPinFuncSet() { - add(((eATmegaPinFunc&&)items)...); - } - inline ATmegaPeripheralSet(const ATmegaPeripheralSet&) = default; - - inline void add(eATmegaPeripheral value) noexcept { - this->funcs[(uint8_t)value] = true; - } - template - inline void add(eATmegaPeripheral value, funcItemType&&... items) noexcept { - add(value); - add(((funcItemType&&)items)...); - } - - inline bool hasItem(eATmegaPeripheral value) const noexcept { - return this->funcs[(uint8_t)value]; - } - template - inline bool hasItem(eATmegaPeripheral&& item, otherFuncItem&&... funcs) const noexcept { - return hasItem(item) || hasItem(((otherFuncItem&&)funcs)...); - } - - template - inline void iterate(callbackType&& cb) const { - for (uint8_t n = 1; n < countof(funcs); n++) { - const bool& f = this->funcs[n]; - if (f) { - cb( (eATmegaPeripheral)n ); - } - } - } - - inline void fromPinFuncs(const ATmegaPinFuncSet& funcSet) { - funcSet.iterate( - [this]( eATmegaPinFunc func ) noexcept { - this->add( _ATmega_getPeripheralForFunc(func) ); - } - ); - } - -private: - bool funcs[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; -}; - -struct ATmegaPeripheralPowerGate { - inline ATmegaPeripheralPowerGate(ATmegaPeripheralSet& periSet) noexcept : periSet(periSet) { - periSet.iterate( - [this]( eATmegaPeripheral peri ) noexcept { - this->states[(uint8_t)peri] = _ATmega_getPeripheralPower(peri); - _ATmega_setPeripheralPower(peri, true); - } - ); - } - inline ATmegaPeripheralPowerGate(const ATmegaPeripheralPowerGate&) = delete; - - inline ~ATmegaPeripheralPowerGate() { - periSet.iterate( - [this]( eATmegaPeripheral peri ) noexcept { - _ATmega_setPeripheralPower(peri, this->states[(uint8_t)peri]); - } - ); - } - - inline ATmegaPeripheralPowerGate& operator = (const ATmegaPeripheralPowerGate&) = delete; - -private: - ATmegaPeripheralSet& periSet; - bool states[(uint8_t)eATmegaPeripheral::NUM_PERIPHERALS]; -}; - -inline pin_dev_state_t _ATmega_savePinAlternates(const ATmegaPinFuncSet& funcSet) { - // TODO: the manual states that registers of power-reduced peripherals cannot be read or written, and that - // the resources (GPIO pins) remain occupied during power-reduction. This is a serious problem and we should - // add power-reduction awareness to this logic! - - pin_dev_state_t state; - - ATmegaPeripheralSet periSet; - periSet.fromPinFuncs(funcSet); - - ATmegaPeripheralPowerGate pgate(periSet); - -#if defined(__AVR_TRM01__) - // See page 75ff of ATmega2560 technical reference manual. - if (funcSet.hasAnyFunc( - eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, - eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, - eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR - )) { - state._SRE = _XMCRA._SRE; - - _XMCRA._SRE = false; - } - if (funcSet.hasAnyFunc( - eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 - )) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { - state._COM1C = TIMER1._TCCRnA._COMnC; - - TIMER1._TCCRnA._COMnC = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - state._COM1B = TIMER1._TCCRnA._COMnB; - - TIMER1._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - state._COM1A = TIMER1._TCCRnA._COMnA; - - TIMER1._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - state._COM2A = _TIMER2._TCCRnA._COMnA; - - _TIMER2._TCCRnA._COMnA = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; - - USART1._UCSRnB._TXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; - - USART1._UCSRnB._RXEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { - state._COM3C = TIMER3._TCCRnA._COMnC; - - TIMER3._TCCRnA._COMnC = 0; - } - // There is an error in the technical reference manual signal mapping table - // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list - // says OC3A. - if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { - state._COM3B = TIMER3._TCCRnA._COMnB; - - TIMER3._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { - state._COM3A = TIMER3._TCCRnA._COMnA; - - TIMER3._TCCRnA._COMnA = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { - state._USART0_RXEN = USART0._UCSRnB._RXEN; - - USART0._UCSRnB._RXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; - - USART0._UCSRnB._TXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - state._PCIE1 = _PCICR._PCIE1; - - _PCICR._PCIE1 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { - state._COM0B = TIMER0._TCCRnA._COMnB; - - TIMER0._TCCRnA._COMnB = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - state._AS2 = _ASSR._AS2; - - _ASSR._AS2 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - state._COM2B = _TIMER2._TCCRnA._COMnB; - - _TIMER2._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { - state._COM4C = TIMER4._TCCRnA._COMnC; - - TIMER4._TCCRnA._COMnC = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { - state._COM4B = TIMER4._TCCRnA._COMnB; - - TIMER4._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { - state._COM4A = TIMER4._TCCRnA._COMnA; - - TIMER4._TCCRnA._COMnA = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { - state._USART2_RXEN = USART2._UCSRnB._RXEN; - - USART2._UCSRnB._RXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { - state._USART2_TXEN = USART2._UCSRnB._TXEN; - - USART2._UCSRnB._TXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { - state._USART3_RXEN = USART3._UCSRnB._RXEN; - - USART3._UCSRnB._RXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { - state._USART3_TXEN = USART3._UCSRnB._TXEN; - - USART3._UCSRnB._TXEN = false; - } - if (funcSet.hasAnyFunc( - eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 - )) { - state._PCIE2 = _PCICR._PCIE2; - - _PCICR._PCIE2 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { - state._COM5C = TIMER5._TCCRnA._COMnC; - - TIMER5._TCCRnA._COMnC = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { - state._COM5B = TIMER5._TCCRnA._COMnB; - - TIMER5._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { - state._COM5A = TIMER5._TCCRnA._COMnA; - - TIMER5._TCCRnA._COMnA = 0; - } -#elif defined(__AVR_TRM02__) - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { - state._ADC7D = _DIDR0._ADC7D; - - _DIDR0._ADC7D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { - state._ADC6D = _DIDR0._ADC6D; - - _DIDR0._ADC6D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { - state._ADC5D = _DIDR0._ADC5D; - - _DIDR0._ADC5D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { - state._ADC4D = _DIDR0._ADC4D; - - _DIDR0._ADC4D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { - state._ADC3D = _DIDR0._ADC3D; - - _DIDR0._ADC3D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { - state._ADC2D = _DIDR0._ADC2D; - - _DIDR0._ADC2D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { - state._ADC1D = _DIDR0._ADC1D; - - _DIDR0._ADC1D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { - state._ADC0D = _DIDR0._ADC0D; - - _DIDR0._ADC0D = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - state._PCIE1 = _PCICR._PCIE1; - - _PCICR._PCIE1 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { - state._SPE = _SPCR._SPE; - - _SPCR._SPE = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { - state._COM0A = TIMER0._TCCRnA._COMnA; - - TIMER0._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - state._COM0B = TIMER0._TCCRnA._COMnB; - - TIMER0._TCCRnA._COMnB = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - state._AS2 = _ASSR._AS2; - - _ASSR._AS2 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { - state._PCIE2 = _PCICR._PCIE2; - - _PCICR._PCIE2 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { - state._PCIE3 = _PCICR._PCIE3; - - _PCICR._PCIE3 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - state._COM2A = _TIMER2._TCCRnA._COMnA; - - _TIMER2._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - state._COM2B = _TIMER2._TCCRnA._COMnB; - - _TIMER2._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - state._COM1A = TIMER1._TCCRnA._COMnA; - - TIMER1._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - state._COM1B = TIMER1._TCCRnA._COMnB; - - TIMER1._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; - - USART1._UCSRnB._TXEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; - - USART1._UCSRnB._RXEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; - - USART0._UCSRnB._TXEN = false; - } - // There is a bug in the ATmega164A technical reference manual where - // it says that pin 0 is mapped to USART1 RXD in the signal mapping table - // but the associated list says USART0 RXD. - if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { - state._USART0_RXEN = USART0._UCSRnB._RXEN; - - USART0._UCSRnB._RXEN = false; - } -#elif defined(__AVR_TRM03__) - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - state._AS2 = _ASSR._AS2; - - _ASSR._AS2 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { - state._SPE = _SPCR._SPE; - - _SPCR._SPE = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - state._COM2A = _TIMER2._TCCRnA._COMnA; - - _TIMER2._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - state._COM1B = TIMER1._TCCRnA._COMnB; - - TIMER1._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - state._COM1A = TIMER1._TCCRnA._COMnA; - - TIMER1._TCCRnA._COMnA = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - state._PCIE1 = _PCICR._PCIE1; - - _PCICR._PCIE1 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { - state._TWEN = _TWCR._TWEN; - - _TWCR._TWEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { - state._ADC5D = _DIDR0._ADC5D; - - _DIDR0._ADC5D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { - state._ADC4D = _DIDR0._ADC4D; - - _DIDR0._ADC4D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { - state._ADC3D = _DIDR0._ADC3D; - - _DIDR0._ADC3D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { - state._ADC2D = _DIDR0._ADC2D; - - _DIDR0._ADC2D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { - state._ADC1D = _DIDR0._ADC1D; - - _DIDR0._ADC1D = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { - state._ADC0D = _DIDR0._ADC0D; - - _DIDR0._ADC0D = false; - } - // There is a bug in the ATmega48A technical reference manual where pin 2 - // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. - // The real mapping can be read in the documentation of the PCICR register. - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { - state._PCIE2 = _PCICR._PCIE2; - - _PCICR._PCIE2 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { - state._COM0A = TIMER0._TCCRnA._COMnA; - - TIMER0._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - state._COM0B = TIMER0._TCCRnA._COMnB; - - TIMER0._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { - state._UMSEL = USART0._UCSRnC._UMSEL; - - USART0._UCSRnC._UMSEL = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - state._COM2B = _TIMER2._TCCRnA._COMnB; - - _TIMER2._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { - state._USART0_TXEN = USART0._UCSRnB._TXEN; - - USART0._UCSRnB._TXEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { - state._USART0_RXEN = USART0._UCSRnB._RXEN; - - USART0._UCSRnB._RXEN = false; - } -#elif defined(__AVR_TRM04__) - if (funcSet.hasAnyFunc( - eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, - eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, - eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR - )) { - state._SRE = _XMCRA._SRE; - - _XMCRA._SRE = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { - state._COM1C = TIMER1._TCCRnA._COMnC; - - TIMER1._TCCRnA._COMnC = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - state._COM1B = TIMER1._TCCRnA._COMnB; - - TIMER1._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - state._COM1A = TIMER1._TCCRnA._COMnA; - - TIMER1._TCCRnA._COMnA = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - state._COM2A = _TIMER2._TCCRnA._COMnA; - - _TIMER2._TCCRnA._COMnA = 0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { - state._SPE = _SPCR._SPE; - - _SPCR._SPE = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - state._PCIE0 = _PCICR._PCIE0; - - _PCICR._PCIE0 = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { - state._USART1_TXEN = USART1._UCSRnB._TXEN; - - USART1._UCSRnB._TXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { - state._USART1_RXEN = USART1._UCSRnB._RXEN; - - USART1._UCSRnB._RXEN = false; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { - state._TWEN = _TWCR._TWEN; - - _TWCR._TWEN = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - state._COM2B = _TIMER2._TCCRnA._COMnB; - - _TIMER2._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - state._COM0B = TIMER0._TCCRnA._COMnB; - - TIMER0._TCCRnA._COMnB = 0; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { - state._INT3 = _EIMSK._INT3; - - _EIMSK._INT3 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { - state._INT2 = _EIMSK._INT2; - - _EIMSK._INT2 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { - state._INT1 = _EIMSK._INT1; - - _EIMSK._INT1 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { - state._INT0 = _EIMSK._INT0; - - _EIMSK._INT0 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { - state._UVCONE = _UHWCON._UVCONE; - - _UHWCON._UVCONE = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::UID)) { - state._UIDE = _UHWCON._UIDE; - - _UHWCON._UIDE = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { - state._INT7 = _EIMSK._INT7; - - _EIMSK._INT7 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { - state._INT6 = _EIMSK._INT6; - - _EIMSK._INT6 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { - state._INT5 = _EIMSK._INT5; - - _EIMSK._INT5 = false; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { - state._INT4 = _EIMSK._INT4; - - _EIMSK._INT4 = false; - } -#endif + #ifdef __AVR_TRM01__ + // See page 75ff of ATmega2560 technical reference manual. + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + state._SRE = _XMCRA._SRE; + _XMCRA._SRE = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + state._COM3C = TIMER3._TCCRnA._COMnC; + TIMER3._TCCRnA._COMnC = 0; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + state._COM3B = TIMER3._TCCRnA._COMnB; + TIMER3._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + state._COM3A = TIMER3._TCCRnA._COMnA; + TIMER3._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + state._COM4C = TIMER4._TCCRnA._COMnC; + TIMER4._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + state._COM4B = TIMER4._TCCRnA._COMnB; + TIMER4._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + state._COM4A = TIMER4._TCCRnA._COMnA; + TIMER4._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_RXEN = USART2._UCSRnB._RXEN; + USART2._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + state._USART2_TXEN = USART2._UCSRnB._TXEN; + USART2._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_RXEN = USART3._UCSRnB._RXEN; + USART3._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + state._USART3_TXEN = USART3._UCSRnB._TXEN; + USART3._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + state._COM5C = TIMER5._TCCRnA._COMnC; + TIMER5._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + state._COM5B = TIMER5._TCCRnA._COMnB; + TIMER5._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + state._COM5A = TIMER5._TCCRnA._COMnA; + TIMER5._TCCRnA._COMnA = 0; + } + #elif defined(__AVR_TRM02__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + state._ADC7D = _DIDR0._ADC7D; + _DIDR0._ADC7D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + state._ADC6D = _DIDR0._ADC6D; + _DIDR0._ADC6D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; + _DIDR0._ADC2D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; + _DIDR0._ADC1D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + _DIDR0._ADC0D = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + state._PCIE3 = _PCICR._PCIE3; + _PCICR._PCIE3 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + #elif defined(__AVR_TRM03__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + state._AS2 = _ASSR._AS2; + _ASSR._AS2 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + state._PCIE1 = _PCICR._PCIE1; + _PCICR._PCIE1 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + state._TWEN = _TWCR._TWEN; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + state._ADC5D = _DIDR0._ADC5D; + _DIDR0._ADC5D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + state._ADC4D = _DIDR0._ADC4D; + _DIDR0._ADC4D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + state._ADC3D = _DIDR0._ADC3D; + _DIDR0._ADC3D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + state._ADC2D = _DIDR0._ADC2D; + _DIDR0._ADC2D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + state._ADC1D = _DIDR0._ADC1D; + _DIDR0._ADC1D = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + state._ADC0D = _DIDR0._ADC0D; + _DIDR0._ADC0D = false; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + state._PCIE2 = _PCICR._PCIE2; + _PCICR._PCIE2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + state._COM0A = TIMER0._TCCRnA._COMnA; + TIMER0._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + state._UMSEL = USART0._UCSRnC._UMSEL; + USART0._UCSRnC._UMSEL = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + state._USART0_TXEN = USART0._UCSRnB._TXEN; + USART0._UCSRnB._TXEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + state._USART0_RXEN = USART0._UCSRnB._RXEN; + USART0._UCSRnB._RXEN = false; + } + #elif defined(__AVR_TRM04__) + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + state._SRE = _XMCRA._SRE; + _XMCRA._SRE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + state._COM1C = TIMER1._TCCRnA._COMnC; + TIMER1._TCCRnA._COMnC = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + state._COM1B = TIMER1._TCCRnA._COMnB; + TIMER1._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + state._COM1A = TIMER1._TCCRnA._COMnA; + TIMER1._TCCRnA._COMnA = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + state._COM2A = _TIMER2._TCCRnA._COMnA; + _TIMER2._TCCRnA._COMnA = 0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + state._SPE = _SPCR._SPE; + _SPCR._SPE = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + state._PCIE0 = _PCICR._PCIE0; + _PCICR._PCIE0 = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + state._USART1_TXEN = USART1._UCSRnB._TXEN; + USART1._UCSRnB._TXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + state._USART1_RXEN = USART1._UCSRnB._RXEN; + USART1._UCSRnB._RXEN = false; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + state._TWEN = _TWCR._TWEN; + _TWCR._TWEN = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + state._COM2B = _TIMER2._TCCRnA._COMnB; + _TIMER2._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + state._COM0B = TIMER0._TCCRnA._COMnB; + TIMER0._TCCRnA._COMnB = 0; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + state._INT3 = _EIMSK._INT3; + _EIMSK._INT3 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + state._INT2 = _EIMSK._INT2; + _EIMSK._INT2 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + state._INT1 = _EIMSK._INT1; + _EIMSK._INT1 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + state._INT0 = _EIMSK._INT0; + _EIMSK._INT0 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + state._UVCONE = _UHWCON._UVCONE; + _UHWCON._UVCONE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + state._UIDE = _UHWCON._UIDE; + _UHWCON._UIDE = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + state._INT7 = _EIMSK._INT7; + _EIMSK._INT7 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + state._INT6 = _EIMSK._INT6; + _EIMSK._INT6 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + state._INT5 = _EIMSK._INT5; + _EIMSK._INT5 = false; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + state._INT4 = _EIMSK._INT4; + _EIMSK._INT4 = false; + } + #endif return state; } @@ -4075,318 +3916,318 @@ inline void _ATmega_restorePinAlternates(const ATmegaPinFuncSet& funcSet, const ATmegaPeripheralPowerGate pgate(periSet); -#if defined(__AVR_TRM01__) - // See page 75ff of ATmega2560 technical reference manual. - if (funcSet.hasAnyFunc( - eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, - eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, - eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR - )) { - _XMCRA._SRE = state._SRE; - } - if (funcSet.hasAnyFunc( - eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 - )) { - _PCICR._PCIE0 = state._PCIE0; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { - TIMER1._TCCRnA._COMnC = state._COM1C; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { - TIMER3._TCCRnA._COMnC = state._COM3C; - } - // There is an error in the technical reference manual signal mapping table - // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list - // says OC3A. - if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { - TIMER3._TCCRnA._COMnB = state._COM3B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { - TIMER3._TCCRnA._COMnA = state._COM3A; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { - USART0._UCSRnB._RXEN = state._USART0_RXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - _PCICR._PCIE1 = state._PCIE1; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - _ASSR._AS2 = state._AS2; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { - TIMER4._TCCRnA._COMnC = state._COM4C; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { - TIMER4._TCCRnA._COMnB = state._COM4B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { - TIMER4._TCCRnA._COMnA = state._COM4A; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { - USART2._UCSRnB._RXEN = state._USART2_RXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { - USART2._UCSRnB._TXEN = state._USART2_TXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { - USART3._UCSRnB._RXEN = state._USART3_RXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { - USART3._UCSRnB._TXEN = state._USART3_TXEN; - } - if (funcSet.hasAnyFunc( - eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 - )) { - _PCICR._PCIE2 = state._PCIE2; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { - TIMER5._TCCRnA._COMnC = state._COM5C; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { - TIMER5._TCCRnA._COMnB = state._COM5B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { - TIMER5._TCCRnA._COMnA = state._COM5A; - } -#elif defined(__AVR_TRM02__) - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - _PCICR._PCIE0 = state._PCIE0; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { - _DIDR0._ADC7D = state._ADC7D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { - _DIDR0._ADC6D = state._ADC6D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { - _DIDR0._ADC5D = state._ADC5D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { - _DIDR0._ADC4D = state._ADC4D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { - _DIDR0._ADC3D = state._ADC3D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { - _DIDR0._ADC2D = state._ADC2D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { - _DIDR0._ADC1D = state._ADC1D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { - _DIDR0._ADC0D = state._ADC0D; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - _PCICR._PCIE1 = state._PCIE1; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { - _SPCR._SPE = state._SPE; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { - TIMER0._TCCRnA._COMnA = state._COM0A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - _ASSR._AS2 = state._AS2; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { - _PCICR._PCIE2 = state._PCIE2; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { - _PCICR._PCIE3 = state._PCIE3; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } - // There is a bug in the ATmega164A technical reference manual where - // it says that pin 0 is mapped to USART1 RXD in the signal mapping table - // but the associated list says USART0 RXD. - if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { - USART0._UCSRnB._RXEN = state._USART0_RXEN; - } -#elif defined(__AVR_TRM03__) - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - _PCICR._PCIE0 = state._PCIE0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { - _ASSR._AS2 = state._AS2; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { - _SPCR._SPE = state._SPE; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { - _PCICR._PCIE1 = state._PCIE1; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { - _TWCR._TWEN = state._TWEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { - _DIDR0._ADC5D = state._ADC5D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { - _DIDR0._ADC4D = state._ADC4D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { - _DIDR0._ADC3D = state._ADC3D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { - _DIDR0._ADC2D = state._ADC2D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { - _DIDR0._ADC1D = state._ADC1D; - } - if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { - _DIDR0._ADC0D = state._ADC0D; - } - // There is a bug in the ATmega48A technical reference manual where pin 2 - // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. - // The real mapping can be read in the documentation of the PCICR register. - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { - _PCICR._PCIE2 = state._PCIE2; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { - TIMER0._TCCRnA._COMnA = state._COM0A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { - USART0._UCSRnC._UMSEL = state._UMSEL; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { - USART0._UCSRnB._TXEN = state._USART0_TXEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { - USART0._UCSRnB._RXEN = state._USART0_RXEN; - } -#elif defined(__AVR_TRM04__) - if (funcSet.hasAnyFunc( - eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, - eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, - eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR - )) { - _XMCRA._SRE = state._SRE; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { - TIMER1._TCCRnA._COMnC = state._COM1C; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { - TIMER1._TCCRnA._COMnB = state._COM1B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { - TIMER1._TCCRnA._COMnA = state._COM1A; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { - _TIMER2._TCCRnA._COMnA = state._COM2A; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { - _SPCR._SPE = state._SPE; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { - _PCICR._PCIE0 = state._PCIE0; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { - USART1._UCSRnB._TXEN = state._USART1_TXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { - USART1._UCSRnB._RXEN = state._USART1_RXEN; - } - if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { - _TWCR._TWEN = state._TWEN; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { - _TIMER2._TCCRnA._COMnB = state._COM2B; - } - if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { - TIMER0._TCCRnA._COMnB = state._COM0B; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { - _EIMSK._INT3 = state._INT3; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { - _EIMSK._INT2 = state._INT2; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { - _EIMSK._INT1 = state._INT1; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { - _EIMSK._INT0 = state._INT0; - } - if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { - _UHWCON._UVCONE = state._UVCONE; - } - if (funcSet.hasFunc(eATmegaPinFunc::UID)) { - _UHWCON._UIDE = state._UIDE; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { - _EIMSK._INT7 = state._INT7; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { - _EIMSK._INT6 = state._INT6; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { - _EIMSK._INT5 = state._INT5; - } - if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { - _EIMSK._INT4 = state._INT4; - } -#endif + #ifdef __AVR_TRM01__ + // See page 75ff of ATmega2560 technical reference manual. + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + _XMCRA._SRE = state._SRE; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI0, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI7 + )) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_TXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_RXD, eATmegaPinFunc::USART1_CLK)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3C)) { + TIMER3._TCCRnA._COMnC = state._COM3C; + } + // There is an error in the technical reference manual signal mapping table + // of ATmega2560 where is says that pin 3 is mapped to OC3B, but the list + // says OC3A. + if (funcSet.hasFunc(eATmegaPinFunc::TOC3B)) { + TIMER3._TCCRnA._COMnB = state._COM3B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC3A)) { + TIMER3._TCCRnA._COMnA = state._COM3A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_RXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART0_TXD, eATmegaPinFunc::USART0_CLK)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4C)) { + TIMER4._TCCRnA._COMnC = state._COM4C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4B)) { + TIMER4._TCCRnA._COMnB = state._COM4B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC4A)) { + TIMER4._TCCRnA._COMnA = state._COM4A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_RXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._RXEN = state._USART2_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART2_TXD, eATmegaPinFunc::USART2_CLK)) { + USART2._UCSRnB._TXEN = state._USART2_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._RXEN = state._USART3_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART3_TXD, eATmegaPinFunc::USART3_CLK)) { + USART3._UCSRnB._TXEN = state._USART3_TXEN; + } + if (funcSet.hasAnyFunc( + eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16 + )) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5C)) { + TIMER5._TCCRnA._COMnC = state._COM5C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5B)) { + TIMER5._TCCRnA._COMnB = state._COM5B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC5A)) { + TIMER5._TCCRnA._COMnA = state._COM5A; + } + #elif defined(__AVR_TRM02__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC7)) { + _DIDR0._ADC7D = state._ADC7D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC6)) { + _DIDR0._ADC6D = state._ADC6D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI15, eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI31, eATmegaPinFunc::PCI30, eATmegaPinFunc::PCI29, eATmegaPinFunc::PCI28, eATmegaPinFunc::PCI27, eATmegaPinFunc::PCI26, eATmegaPinFunc::PCI25, eATmegaPinFunc::PCI24)) { + _PCICR._PCIE3 = state._PCIE3; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART0_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + // There is a bug in the ATmega164A technical reference manual where + // it says that pin 0 is mapped to USART1 RXD in the signal mapping table + // but the associated list says USART0 RXD. + if (funcSet.hasFunc(eATmegaPinFunc::USART0_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + #elif defined(__AVR_TRM03__) + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TOSC1, eATmegaPinFunc::TOSC2)) { + _ASSR._AS2 = state._AS2; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI14, eATmegaPinFunc::PCI13, eATmegaPinFunc::PCI12, eATmegaPinFunc::PCI11, eATmegaPinFunc::PCI10, eATmegaPinFunc::PCI9, eATmegaPinFunc::PCI8)) { + _PCICR._PCIE1 = state._PCIE1; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_CLK, eATmegaPinFunc::TWI_SDA)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC5)) { + _DIDR0._ADC5D = state._ADC5D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC4)) { + _DIDR0._ADC4D = state._ADC4D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC3)) { + _DIDR0._ADC3D = state._ADC3D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC2)) { + _DIDR0._ADC2D = state._ADC2D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC1)) { + _DIDR0._ADC1D = state._ADC1D; + } + if (funcSet.hasFunc(eATmegaPinFunc::ADC0)) { + _DIDR0._ADC0D = state._ADC0D; + } + // There is a bug in the ATmega48A technical reference manual where pin 2 + // is said to be mapped to PCIE1 but logically it should be PCIE2 instead. + // The real mapping can be read in the documentation of the PCICR register. + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI23, eATmegaPinFunc::PCI22, eATmegaPinFunc::PCI21, eATmegaPinFunc::PCI20, eATmegaPinFunc::PCI19, eATmegaPinFunc::PCI18, eATmegaPinFunc::PCI17, eATmegaPinFunc::PCI16)) { + _PCICR._PCIE2 = state._PCIE2; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0A)) { + TIMER0._TCCRnA._COMnA = state._COM0A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_CLK)) { + USART0._UCSRnC._UMSEL = state._UMSEL; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_TXD)) { + USART0._UCSRnB._TXEN = state._USART0_TXEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::USART_RXD)) { + USART0._UCSRnB._RXEN = state._USART0_RXEN; + } + #elif defined(__AVR_TRM04__) + if (funcSet.hasAnyFunc( + eATmegaPinFunc::EXTMEM_AD15, eATmegaPinFunc::EXTMEM_AD14, eATmegaPinFunc::EXTMEM_AD13, eATmegaPinFunc::EXTMEM_AD12, eATmegaPinFunc::EXTMEM_AD11, eATmegaPinFunc::EXTMEM_AD10, eATmegaPinFunc::EXTMEM_AD9, eATmegaPinFunc::EXTMEM_AD8, + eATmegaPinFunc::EXTMEM_AD7, eATmegaPinFunc::EXTMEM_AD6, eATmegaPinFunc::EXTMEM_AD5, eATmegaPinFunc::EXTMEM_AD4, eATmegaPinFunc::EXTMEM_AD3, eATmegaPinFunc::EXTMEM_AD2, eATmegaPinFunc::EXTMEM_AD1, eATmegaPinFunc::EXTMEM_AD0, + eATmegaPinFunc::EXTMEM_ALE, eATmegaPinFunc::EXTMEM_RD, eATmegaPinFunc::EXTMEM_WR + )) { + _XMCRA._SRE = state._SRE; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1C)) { + TIMER1._TCCRnA._COMnC = state._COM1C; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1B)) { + TIMER1._TCCRnA._COMnB = state._COM1B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC1A)) { + TIMER1._TCCRnA._COMnA = state._COM1A; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2A)) { + _TIMER2._TCCRnA._COMnA = state._COM2A; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::SPI_MISO, eATmegaPinFunc::SPI_MOSI, eATmegaPinFunc::SPI_SCK, eATmegaPinFunc::SPI_CS)) { + _SPCR._SPE = state._SPE; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::PCI7, eATmegaPinFunc::PCI6, eATmegaPinFunc::PCI5, eATmegaPinFunc::PCI4, eATmegaPinFunc::PCI3, eATmegaPinFunc::PCI2, eATmegaPinFunc::PCI1, eATmegaPinFunc::PCI0)) { + _PCICR._PCIE0 = state._PCIE0; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_TXD)) { + USART1._UCSRnB._TXEN = state._USART1_TXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::USART1_CLK, eATmegaPinFunc::USART1_RXD)) { + USART1._UCSRnB._RXEN = state._USART1_RXEN; + } + if (funcSet.hasAnyFunc(eATmegaPinFunc::TWI_SDA, eATmegaPinFunc::TWI_CLK)) { + _TWCR._TWEN = state._TWEN; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC2B)) { + _TIMER2._TCCRnA._COMnB = state._COM2B; + } + if (funcSet.hasFunc(eATmegaPinFunc::TOC0B)) { + TIMER0._TCCRnA._COMnB = state._COM0B; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT3)) { + _EIMSK._INT3 = state._INT3; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT2)) { + _EIMSK._INT2 = state._INT2; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT1)) { + _EIMSK._INT1 = state._INT1; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT0)) { + _EIMSK._INT0 = state._INT0; + } + if (funcSet.hasFunc(eATmegaPinFunc::UVCON)) { + _UHWCON._UVCONE = state._UVCONE; + } + if (funcSet.hasFunc(eATmegaPinFunc::UID)) { + _UHWCON._UIDE = state._UIDE; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT7)) { + _EIMSK._INT7 = state._INT7; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT6)) { + _EIMSK._INT6 = state._INT6; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT5)) { + _EIMSK._INT5 = state._INT5; + } + if (funcSet.hasFunc(eATmegaPinFunc::EINT4)) { + _EIMSK._INT4 = state._INT4; + } + #endif } inline pin_dev_state_t _ATmega_savePinAlternate(uint8_t pin) { @@ -4398,10 +4239,10 @@ inline void _ATmega_restorePinAlternate(uint8_t pin, const pin_dev_state_t& stat } #ifndef LOW -#define LOW 0 + #define LOW 0 #endif #ifndef HIGH -#define HIGH 1 + #define HIGH 1 #endif inline void _ATmega_digitalWrite(int pin, int state) { @@ -4409,83 +4250,83 @@ inline void _ATmega_digitalWrite(int pin, int state) { ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); -#if defined(__AVR_TRM01__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_E) { - _PORTE._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_F) { - _PORTF._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_G) { - _PORTG._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_H) { - _PORTH._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_J) { - _PORTJ._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_K) { - _PORTK._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_L) { - _PORTL._PORT.setValue(info.pinidx, state == HIGH); - } -#elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._PORT.setValue(info.pinidx, state == HIGH); - } -#elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { - _PORTB._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._PORT.setValue(info.pinidx, state == HIGH); - } -#elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_E) { - _PORTE._PORT.setValue(info.pinidx, state == HIGH); - } - else if (info.port == eATmegaPort::PORT_F) { - _PORTF._PORT.setValue(info.pinidx, state == HIGH); - } -#endif + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._PORT.setValue(info.pinidx, state == HIGH); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._PORT.setValue(info.pinidx, state == HIGH); + } + #endif } inline int _ATmega_digitalRead(int pin) { @@ -4495,92 +4336,92 @@ inline int _ATmega_digitalRead(int pin) { ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); -#if defined(__AVR_TRM01__) - if (info.port == eATmegaPort::PORT_A) { - value = _PORTA._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_B) { - value = _PORTB._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_C) { - value = _PORTC._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_D) { - value = _PORTD._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_E) { - value = _PORTE._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_F) { - value = _PORTF._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_G) { - value = _PORTG._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_H) { - value = _PORTH._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_J) { - value = _PORTJ._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_K) { - value = _PORTK._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_L) { - value = _PORTL._PIN.getValue(info.pinidx); - } -#elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { - value = _PORTA._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_B) { - value = _PORTB._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_C) { - value = _PORTC._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_D) { - value = _PORTD._PIN.getValue(info.pinidx); - } -#elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { - value = _PORTB._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_C) { - value = _PORTC._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_D) { - value = _PORTD._PIN.getValue(info.pinidx); - } -#elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { - value = _PORTA._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_B) { - value = _PORTB._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_C) { - value = _PORTC._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_D) { - value = _PORTD._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_E) { - value = _PORTE._PIN.getValue(info.pinidx); - } - else if (info.port == eATmegaPort::PORT_F) { - value = _PORTF._PIN.getValue(info.pinidx); - } -#endif + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_G) { + value = _PORTG._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_H) { + value = _PORTH._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_J) { + value = _PORTJ._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_K) { + value = _PORTK._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_L) { + value = _PORTL._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + value = _PORTA._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_B) { + value = _PORTB._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_C) { + value = _PORTC._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_D) { + value = _PORTD._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_E) { + value = _PORTE._PIN.getValue(info.pinidx); + } + else if (info.port == eATmegaPort::PORT_F) { + value = _PORTF._PIN.getValue(info.pinidx); + } + #endif return value; } #ifndef OUTPUT -#define OUTPUT 1 + #define OUTPUT 1 #endif #ifndef INPUT -#define INPUT 0 + #define INPUT 0 #endif inline void _ATmega_pinMode(int pin, int mode) { @@ -4588,249 +4429,243 @@ inline void _ATmega_pinMode(int pin, int mode) { ATmegaPinInfo info = _ATmega_getPinInfo((unsigned int)pin); -#if defined(__AVR_TRM01__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_E) { - _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_F) { - _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_G) { - _PORTG._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_H) { - _PORTH._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_J) { - _PORTJ._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_K) { - _PORTK._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_L) { - _PORTL._DDR.setValue(info.pinidx, mode == OUTPUT); - } -#elif defined(__AVR_TRM02__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); - } -#elif defined(__AVR_TRM03__) - if (info.port == eATmegaPort::PORT_B) { - _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); - } -#elif defined(__AVR_TRM04__) - if (info.port == eATmegaPort::PORT_A) { - _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_B) { - _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_C) { - _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_D) { - _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_E) { - _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); - } - else if (info.port == eATmegaPort::PORT_F) { - _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); - } -#endif + #ifdef __AVR_TRM01__ + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_G) { + _PORTG._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_H) { + _PORTH._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_J) { + _PORTJ._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_K) { + _PORTK._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_L) { + _PORTL._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM02__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM03__) + if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #elif defined(__AVR_TRM04__) + if (info.port == eATmegaPort::PORT_A) { + _PORTA._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_B) { + _PORTB._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_C) { + _PORTC._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_D) { + _PORTD._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_E) { + _PORTE._DDR.setValue(info.pinidx, mode == OUTPUT); + } + else if (info.port == eATmegaPort::PORT_F) { + _PORTF._DDR.setValue(info.pinidx, mode == OUTPUT); + } + #endif } #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) -struct _ATmega_efuse { - uint8_t _BODLEVEL : 3; - uint8_t reserved1 : 5; -}; - -struct _ATmega_hfuse { - uint8_t _BOOTRST : 1; - uint8_t _BOOTSZ : 2; - uint8_t _EESAVE : 1; - uint8_t _WDTON : 1; - uint8_t _SPIEN : 1; - uint8_t _JTAGEN : 1; - uint8_t _OCDEN : 1; -}; - -struct _ATmega_lfuse { - uint8_t _CKSEL : 4; - uint8_t _SUT0 : 1; - uint8_t _SUT1 : 1; - uint8_t _CKOUT : 1; - uint8_t _CKDIV8 : 1; -}; - -#ifndef AVR_DEFAULT_LFUSE_VALUE -#define AVR_DEFAULT_LFUSE_VALUE 0xFF -#endif -#ifndef AVR_DEFAULT_HFUSE_VALUE -#define AVR_DEFAULT_HFUSE_VALUE 0x99 -#endif -#ifndef AVR_DEFAULT_LFUSE_VALUE -#define AVR_DEFAULT_LFUSE_VALUE 0x62 -#endif + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; + }; + + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; + }; + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0xFF + #endif + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0x99 + #endif + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0x62 + #endif #elif defined(__AVR_TRM03__) -#if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) -struct _ATmega_efuse { - uint8_t _SELFPRGEN : 1; - uint8_t reserved1 : 7; -}; - -#ifndef AVR_DEFAULT_EFUSE_VALUE -#define AVR_DEFAULT_EFUSE_VALUE 0xFF -#endif - -#elif defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) -struct _ATmega_efuse { - uint8_t _BOOTRST : 1; - uint8_t _BOOTSZ : 2; - uint8_t reserved1 : 5; -}; - -#ifndef AVR_DEFAULT_EFUSE_VALUE -#define AVR_DEFAULT_EFUSE_VALUE 0xF9 -#endif - -#else //if defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) -struct _ATmega_efuse { - uint8_t _BODLEVEL : 3; - uint8_t reserved1 : 5; -}; - -#ifndef AVR_DEFAULT_EFUSE_VALUE -#define AVR_DEFAULT_EFUSE_VALUE 0xFF -#endif - -#endif - -#if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) -struct _ATmega_hfuse { - uint8_t _BODLEVEL : 3; - uint8_t _EESAVE : 1; - uint8_t _WDTON : 1; - uint8_t _SPIEN : 1; - uint8_t _DWEN : 1; - uint8_t _RSTDISBL : 1; -}; - -#ifndef AVR_DEFAULT_HFUSE_VALUE -#define AVR_DEFAULT_HFUSE_VALUE 0xCF -#endif - -#else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) -struct _ATmega_hfuse { - uint8_t _BOOTRST : 1; - uint8_t _BOOTSZ : 2; - uint8_t _EESAVE : 1; - uint8_t _WDTON : 1; - uint8_t _SPIEN : 1; - uint8_t _DWEN : 1; - uint8_t _RSTDISBL : 1; -}; - -#ifndef AVR_DEFAULT_HFUSE_VALUE -#define AVR_DEFAULT_HFUSE_VALUE 0xC9 -#endif - -#endif - -struct _ATmega_lfuse { - uint8_t _CKSEL : 4; - uint8_t _SUT0 : 1; - uint8_t _SUT1 : 1; - uint8_t _CKOUT : 1; - uint8_t _CKDIV8 : 1; -}; - -#ifndef AVR_DEFAULT_LFUSE_VALUE -#define AVR_DEFAULT_LFUSE_VALUE 0xC9 -#endif + #if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) + struct _ATmega_efuse { + uint8_t _SELFPRGEN : 1; + uint8_t reserved1 : 7; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xFF + #endif + + #elif defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) + struct _ATmega_efuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t reserved1 : 5; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xF9 + #endif + + #else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t reserved1 : 5; + }; + + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xFF + #endif + + #endif + + #if defined(__AVR_ATmega48A__) || defined(__AVR_ATmega48PA__) || defined(__AVR_ATmega88A__) || defined(__AVR_ATmega88PA__) || defined(__AVR_ATmega168A__) || defined(__AVR_ATmega168PA__) + struct _ATmega_hfuse { + uint8_t _BODLEVEL : 3; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; + }; + + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0xCF + #endif + + #else // defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _DWEN : 1; + uint8_t _RSTDISBL : 1; + }; + + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0xC9 + #endif + + #endif + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0xC9 + #endif #elif defined(__AVR_TRM04__) -struct _ATmega_efuse { - uint8_t _BODLEVEL : 3; - uint8_t _HWBE : 1; - uint8_t reserved1 : 4; -}; - -struct _ATmega_hfuse { - uint8_t _BOOTRST : 1; - uint8_t _BOOTSZ : 2; - uint8_t _EESAVE : 1; - uint8_t _WDTON : 1; - uint8_t _SPIEN : 1; - uint8_t _JTAGEN : 1; - uint8_t _OCDEN : 1; -}; - -struct _ATmega_lfuse { - uint8_t _CKSEL : 4; - uint8_t _SUT0 : 1; - uint8_t _SUT1 : 1; - uint8_t _CKOUT : 1; - uint8_t _CKDIV8 : 1; -}; - -// Default values if not already defined. -#ifndef AVR_DEFAULT_EFUSE_VALUE -#define AVR_DEFAULT_EFUSE_VALUE 0xF3 -#endif -#ifndef AVR_DEFAULT_HFUSE_VALUE -#define AVR_DEFAULT_HFUSE_VALUE 0x99 -#endif -#ifndef AVR_DEFAULT_LFUSE_VALUE -#define AVR_DEFAULT_LFUSE_VALUE 0x62 -#endif + struct _ATmega_efuse { + uint8_t _BODLEVEL : 3; + uint8_t _HWBE : 1; + uint8_t reserved1 : 4; + }; + + struct _ATmega_hfuse { + uint8_t _BOOTRST : 1; + uint8_t _BOOTSZ : 2; + uint8_t _EESAVE : 1; + uint8_t _WDTON : 1; + uint8_t _SPIEN : 1; + uint8_t _JTAGEN : 1; + uint8_t _OCDEN : 1; + }; + + struct _ATmega_lfuse { + uint8_t _CKSEL : 4; + uint8_t _SUT0 : 1; + uint8_t _SUT1 : 1; + uint8_t _CKOUT : 1; + uint8_t _CKDIV8 : 1; + }; + + // Default values if not already defined. + #ifndef AVR_DEFAULT_EFUSE_VALUE + #define AVR_DEFAULT_EFUSE_VALUE 0xF3 + #endif + #ifndef AVR_DEFAULT_HFUSE_VALUE + #define AVR_DEFAULT_HFUSE_VALUE 0x99 + #endif + #ifndef AVR_DEFAULT_LFUSE_VALUE + #define AVR_DEFAULT_LFUSE_VALUE 0x62 + #endif #endif struct ATmega_efuse : public _ATmega_efuse { - inline ATmega_efuse(uint8_t val = 0) { - *(uint8_t*)this = val; - } + inline ATmega_efuse(uint8_t val = 0) { *(uint8_t*)this = val; } inline ATmega_efuse(const ATmega_efuse&) = default; }; struct ATmega_hfuse : public _ATmega_hfuse { - inline ATmega_hfuse(uint8_t val = 0) { - *(uint8_t*)this = val; - } + inline ATmega_hfuse(uint8_t val = 0) { *(uint8_t*)this = val; } inline ATmega_hfuse(const ATmega_hfuse&) = default; }; struct ATmega_lfuse : public _ATmega_lfuse { - inline ATmega_lfuse(uint8_t val = 0) { - *(uint8_t*)this = val; - } + inline ATmega_lfuse(uint8_t val = 0) { *(uint8_t*)this = val; } inline ATmega_lfuse(const ATmega_lfuse&) = default; }; From d0e67ef593f3271cb529e14004bf60a7c87a1f4d Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Mon, 12 Dec 2022 21:58:44 +0100 Subject: [PATCH 43/83] - added board schematic links to LPC1768, LPC1769, mega, RAMPS, sanguino and teensy2 pin header files - added missing AVR_CHIPOSCILLATOR_FREQ and LPC_MAINOSCILLATOR_FREQ board oscillator definitions where they were missing, according to the board schematics & made a guess whenever the schematics are missing (please help me get the remaining schematics for good future proofed support of Marlin FW!) - various adjustments --- Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h | 4 + Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 6 +- Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h | 7 ++ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h | 4 + Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 4 + Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 4 + Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h | 3 - Marlin/src/pins/lpc1768/pins_EMOTRONIC.h | 4 + Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h | 4 + Marlin/src/pins/lpc1768/pins_MKS_SBASE.h | 5 + Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 5 + Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h | 5 + Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h | 8 +- Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h | 5 + Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h | 8 ++ .../pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h | 5 + .../src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 + .../pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h | 4 + .../src/pins/lpc1769/pins_COHESION3D_MINI.h | 5 + .../src/pins/lpc1769/pins_COHESION3D_REMIX.h | 4 + Marlin/src/pins/lpc1769/pins_FLY_CDY.h | 4 + Marlin/src/pins/lpc1769/pins_MKS_SGEN.h | 5 + Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 5 + Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h | 4 + Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h | 3 + Marlin/src/pins/mega/pins_CHEAPTRONIC.h | 4 + Marlin/src/pins/mega/pins_CHEAPTRONICv2.h | 6 +- Marlin/src/pins/mega/pins_CNCONTROLS_11.h | 4 + Marlin/src/pins/mega/pins_CNCONTROLS_12.h | 4 + Marlin/src/pins/mega/pins_CNCONTROLS_15.h | 3 + Marlin/src/pins/mega/pins_EINSTART-S.h | 3 + Marlin/src/pins/mega/pins_ELEFU_3.h | 4 + Marlin/src/pins/mega/pins_GT2560_REV_A.h | 2 + Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h | 4 + Marlin/src/pins/mega/pins_GT2560_REV_B.h | 4 + Marlin/src/pins/mega/pins_GT2560_V3.h | 4 + Marlin/src/pins/mega/pins_GT2560_V4.h | 5 + Marlin/src/pins/mega/pins_HJC2560C_REV2.h | 3 + Marlin/src/pins/mega/pins_INTAMSYS40.h | 3 + Marlin/src/pins/mega/pins_LEAPFROG.h | 3 + Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h | 3 + Marlin/src/pins/mega/pins_MALYAN_M180.h | 4 + Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 4 + Marlin/src/pins/mega/pins_MEGATRONICS.h | 6 + Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 5 + Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 4 + Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h | 2 + Marlin/src/pins/mega/pins_MINITRONICS.h | 8 ++ Marlin/src/pins/mega/pins_OVERLORD.h | 4 + Marlin/src/pins/mega/pins_PICA.h | 5 + Marlin/src/pins/mega/pins_PICAOLD.h | 2 + .../pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h | 5 + Marlin/src/pins/mega/pins_SILVER_GATE.h | 3 + Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h | 3 + Marlin/src/pins/mega/pins_WEEDO_62A.h | 2 + Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 4 + Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 6 + Marlin/src/pins/rambo/pins_MINIRAMBO.h | 6 + Marlin/src/pins/rambo/pins_RAMBO.h | 6 + Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h | 3 + Marlin/src/pins/rambo/pins_SCOOVO_X9H.h | 5 +- Marlin/src/pins/ramps/pins_3DRAG.h | 8 ++ Marlin/src/pins/ramps/pins_AZTEEG_X3.h | 4 + Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h | 5 + Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h | 5 + Marlin/src/pins/ramps/pins_BIQU_KFB_2.h | 3 + Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h | 4 + .../src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h | 3 + Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h | 3 + .../src/pins/ramps/pins_FORMBOT_TREX2PLUS.h | 7 +- Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h | 7 +- Marlin/src/pins/ramps/pins_FYSETC_F6_13.h | 4 + Marlin/src/pins/ramps/pins_FYSETC_F6_14.h | 2 + Marlin/src/pins/ramps/pins_K8200.h | 2 + Marlin/src/pins/ramps/pins_K8400.h | 4 +- Marlin/src/pins/ramps/pins_K8600.h | 2 +- Marlin/src/pins/ramps/pins_K8800.h | 6 +- Marlin/src/pins/ramps/pins_MKS_BASE_10.h | 5 + Marlin/src/pins/ramps/pins_MKS_BASE_16.h | 2 + Marlin/src/pins/ramps/pins_MKS_GEN_13.h | 2 + Marlin/src/pins/ramps/pins_MKS_GEN_L.h | 3 +- Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h | 2 + Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h | 2 + Marlin/src/pins/ramps/pins_RAMPS.h | 9 +- Marlin/src/pins/ramps/pins_RUMBA.h | 6 + Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h | 2 +- Marlin/src/pins/ramps/pins_TANGO.h | 4 + Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h | 5 +- Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h | 106 +++++++++--------- Marlin/src/pins/ramps/pins_TT_OSCAR.h | 5 +- Marlin/src/pins/ramps/pins_ULTIMAIN_2.h | 20 ++++ Marlin/src/pins/ramps/pins_ULTIMAKER.h | 3 + Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h | 5 + Marlin/src/pins/ramps/pins_ZRIB_V20.h | 8 +- Marlin/src/pins/ramps/pins_ZRIB_V52.h | 4 +- Marlin/src/pins/ramps/pins_ZRIB_V53.h | 5 +- Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h | 3 + Marlin/src/pins/sanguino/pins_ANET_10.h | 4 + Marlin/src/pins/sanguino/pins_AZTEEG_X1.h | 4 + .../src/pins/sanguino/pins_GEN3_MONOLITHIC.h | 4 + Marlin/src/pins/sanguino/pins_GEN3_PLUS.h | 3 + Marlin/src/pins/sanguino/pins_GEN6.h | 6 + Marlin/src/pins/sanguino/pins_GEN7_12.h | 17 ++- Marlin/src/pins/sanguino/pins_GEN7_14.h | 7 ++ Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h | 3 + Marlin/src/pins/sanguino/pins_MELZI.h | 6 +- .../src/pins/sanguino/pins_MELZI_CREALITY.h | 4 + Marlin/src/pins/sanguino/pins_MELZI_V2.h | 4 + Marlin/src/pins/sanguino/pins_OMCA.h | 3 + Marlin/src/pins/sanguino/pins_OMCA_A.h | 3 + .../src/pins/sanguino/pins_SANGUINOLOLU_11.h | 14 +++ .../src/pins/sanguino/pins_SANGUINOLOLU_12.h | 8 ++ Marlin/src/pins/sanguino/pins_SETHI.h | 3 + Marlin/src/pins/sanguino/pins_STB_11.h | 3 +- Marlin/src/pins/sanguino/pins_ZMIB_V2.h | 4 + Marlin/src/pins/teensy2/pins_5DPRINT.h | 5 + Marlin/src/pins/teensy2/pins_BRAINWAVE.h | 6 + Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h | 5 + Marlin/src/pins/teensy2/pins_PRINTRBOARD.h | 14 +++ .../src/pins/teensy2/pins_PRINTRBOARD_REVF.h | 15 +++ Marlin/src/pins/teensy2/pins_SAV_MKI.h | 6 + Marlin/src/pins/teensy2/pins_TEENSY2.h | 4 + Marlin/src/pins/teensy2/pins_TEENSYLU.h | 6 + 123 files changed, 615 insertions(+), 81 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 4d1dbecf2e8f..a84a36139721 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -23,12 +23,16 @@ /** * AZSMZ MINI pin assignments + * Schematic: http://green-candy.osdn.jp/external/MarlinFW/board_schematics/AZSMZ%20MINI/AZSMZ.svg + * Source: https://raw.githubusercontent.com/Rose-Fish/AZSMZ-mini/master/AZSMZ.sch */ #include "env_validate.h" #define BOARD_INFO_NAME "AZSMZ Mini" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index bde6a1c5fc7b..ba39ce5907ed 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -22,11 +22,7 @@ #pragma once /** - * BIQU BQ111-A4 - * - * Applies to the following boards: - * - * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) + * BIQU Thunder B300 V1.0 */ #include "env_validate.h" diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h index 92152170a013..8814b5ccbffc 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_BQ111_A4.h @@ -23,12 +23,19 @@ /** * BIQU BQ111-A4 pin assignments + * + * Applies to the following boards: + * + * BOARD_BIQU_BQ111_A4 (Hotend, Fan, Bed) */ #include "env_validate.h" #define BOARD_INFO_NAME "BIQU BQ111-A4" +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h index 6e069e9786d7..280393caa902 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_1.h @@ -23,10 +23,14 @@ /** * BigTreeTech SKR 1.1 pin assignments + * Schematic: http://green-candy.osdn.jp/external/MarlinFW/board_schematics/BTT%20SKR%20V1.1/SKR-V1.1SchDoc.pdf + * Origin: https://github.com/bigtreetech/BIGTREETECH-SKR-V1.1/blob/master/hardware/SKR-V1.1SchDoc.pdf */ #define BOARD_INFO_NAME "BTT SKR V1.1" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 885d5f8bf595..de56fb375835 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -23,10 +23,14 @@ /** * BigTreeTech SKR 1.3 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/BTT%20SKR%20V1.3/SKR-V1.3-SCH.pdf + * Origin: https://github.com/bigtreetech/BIGTREETECH-SKR-V1.3/blob/master/BTT%20SKR%20V1.3/hardware/SKR-V1.3-SCH.pdf */ #define BOARD_INFO_NAME "BTT SKR V1.3" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #define LPC1768_IS_SKRV1_3 #define USES_DIAG_JUMPERS diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 3a8133edc0e6..0ed6f07f2152 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -23,6 +23,8 @@ /** * BigTreeTech SKR 1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/BTT%20SKR%20V1.4%20+%20Turbo/BTT%20SKR%20V1.4-SCH.pdf + * Origin: https://github.com/bigtreetech/BIGTREETECH-SKR-V1.3/blob/master/BTT%20SKR%20V1.4/Hardware/BTT%20SKR%20V1.4-SCH.pdf */ #include "env_validate.h" @@ -31,6 +33,8 @@ #define BOARD_INFO_NAME "BTT SKR V1.4" #endif +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #ifndef BOARD_CUSTOM_BUILD_FLAGS #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 #endif diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 927849971558..ec74cc640e85 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -35,9 +35,6 @@ #endif #endif -// BTT SKR V1.4 = 12MHz -#define LPC_MAINOSCILLATOR_FREQ 12000000 - // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 diff --git a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h index 6e1ea403b1f2..7d875b85a699 100644 --- a/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h +++ b/Marlin/src/pins/lpc1768/pins_EMOTRONIC.h @@ -23,6 +23,8 @@ /** * eMotion-Tech eMotronic pin assignments + * Schematic: http://green-candy.osdn.jp/external/MarlinFW/board_schematics/eMotion-Tech%20eMotronic/eMotronic_brd_sources_1.0.4/eMotronic_sch.pdf + * Origin: https://data.emotion-tech.com/ftp/Datasheets_et_sources/Sources/eMotronic_brd_sources_1.0.4.zip * * Board pins<->features assignments are based on the * Micro-Delta Rework printer default connections. @@ -33,6 +35,8 @@ #define BOARD_INFO_NAME "eMotronic" #define BOARD_WEBSITE_URL "www.reprap-france.com/article/lemotronic-quesaco" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Limit Switches // diff --git a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h index 39ab0bbd8968..924ea5431d36 100644 --- a/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h +++ b/Marlin/src/pins/lpc1768/pins_GMARSH_X6_REV1.h @@ -23,12 +23,16 @@ /** * GMARSH X6 Rev.1 pin assignments + * Schematic: http://green-candy.osdn.jp/external/MarlinFW/board_schematics/GMARSH%20X6%20Rev.1/armprinter_2208_1heater.pdf + * Origin: https://github.com/gmarsh/gmarsh_x6/blob/master/armprinter_2208_1heater.pdf */ #include "env_validate.h" #define BOARD_INFO_NAME "GMARSH X6 REV1" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h index 30e52a39dc6d..0b721ca952a2 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SBASE.h @@ -23,6 +23,8 @@ /** * Makerbase MKS SBASE pin assignments + * Schematic (V1.3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/MKS%20SBASE%20V1.3/MKS%20SBASE%20V1.3_002%20SCH.pdf + * Origin (V1.3): http://green-candy.osdn.jp/external/MarlinFW/board_schematics/MKS%20SBASE%20V1.3/MKS%20SBASE%20V1.3_002%20SCH.pdf */ #include "env_validate.h" @@ -34,6 +36,9 @@ #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SBASE" #endif +// Just a wild guess because schematics do not say! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #define LED_PIN P1_18 // Used as a status indicator #define LED2_PIN P1_19 #define LED3_PIN P1_20 diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index c1ace383857f..3cee9f5d80d5 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -23,6 +23,8 @@ /** * Makerbase MKS SGEN-L pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/MKS_GEN_L_V1_0/MKS%20Gen_L%20V1.0_008%20SCH.pdf + * Origin: https://github.com/makerbase-mks/SGEN_L/blob/master/Hardware/MKS%20SGEN_L%20V1.0_001/MKS%20SGEN_L%20V1.0_001%20SCH.pdf */ #include "env_validate.h" @@ -30,6 +32,9 @@ #define BOARD_INFO_NAME "MKS SGen-L" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN_L" +// Just a wild guess because schematics do not say! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #define USES_DIAG_JUMPERS // diff --git a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h index 1ccb3451e3e4..ed5b9b91401f 100644 --- a/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h +++ b/Marlin/src/pins/lpc1768/pins_RAMPS_RE_ARM.h @@ -23,6 +23,8 @@ /** * Re-ARM with RAMPS v1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Re-ARM%20RAMPS%201.4/Re_ARM_Schematic.pdf + * Origin: https://reprap.org/mediawiki/images/f/fa/Re_ARM_Schematic.pdf * * Applies to the following boards: * @@ -39,6 +41,9 @@ #define BOARD_INFO_NAME "Re-ARM RAMPS 1.4" +// ECS-120-20-46X +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 2972ac756079..125df89db99f 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -23,12 +23,18 @@ /** * Selena Compact pin assignments + * Pinout: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Selena%20Compact/Compact%20Pinout.pdf + * Origin: https://github.com/f61/Selena/blob/master/Compact%20Pinout.pdf */ #include "env_validate.h" #define BOARD_INFO_NAME "Selena Compact" -#define BOARD_WEBSITE_URL "github.com/Ales2-k/Selena" +#define BOARD_WEBSITE_URL "https://github.com/f61/Selena" +// We are very lucky that somebody forked the repository! The Alex one is gone. + +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 // // Servos diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h index bc7cada8da05..3080824daef2 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_GT.h @@ -23,6 +23,8 @@ /** * Azteeg X5 GT pin assignments + * Wiring diagram: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X5%20GT/X5%20GT%20Wiring%20Diagram.pdf + * Origin: https://panucattdevices.freshdesk.com/support/solutions/articles/1000244740-support-files */ #include "env_validate.h" @@ -30,6 +32,9 @@ #define BOARD_INFO_NAME "Azteeg X5 GT" #define BOARD_WEBSITE_URL "tinyurl.com/yx8tdqa3" +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h index c33fe6e28f45..3fec3f1f8ebe 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI.h @@ -23,6 +23,10 @@ /** * Azteeg X5 MINI pin assignments + * Schematic (V1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X5%20MINI/x5mini_design_files/X5mini_design_files/V1/X5%20Mini%20PUB%20v1.0.pdf + * Schematic (V2): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X5%20MINI/x5mini_design_files/X5mini_design_files/V2/X5%20Mini%20V2%20SCH%20Pub.pdf + * Schematic (V3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X5%20MINI/x5mini_design_files/X5mini_design_files/V3/X5%20Mini%20V3%20SCH%20Pub.pdf + * Origin: http://files.panucatt.com/datasheets/x5mini_design_files.zip */ #include "env_validate.h" @@ -30,6 +34,10 @@ #define BOARD_INFO_NAME "Azteeg X5 MINI" #endif #define BOARD_WEBSITE_URL "tiny.cc/x5_mini" +// https://www.panucatt.com/azteeg_X5_mini_reprap_3d_printer_controller_p/ax5mini.htm + +// ECS-120-20-46X +#define LPC_MAINOSCILLATOR_FREQ 12000000 // // LED diff --git a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h index 086bacbac0f6..db1facf73a4d 100644 --- a/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h +++ b/Marlin/src/pins/lpc1769/pins_AZTEEG_X5_MINI_WIFI.h @@ -23,12 +23,17 @@ /** * Azteeg X5 MINI WIFI pin assignments + * Wiring diagram: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X5%20MINI%20WIFI/x5mini_wifi_wiring.pdf + * Origin: http://files.panucatt.com/datasheets/x5mini_wifi_wiring.pdf */ #include "env_validate.h" #define BOARD_INFO_NAME "Azteeg X5 MINI WIFI" +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // DIGIPOT slave addresses // diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index dbaafb89ccf7..5016cd5f7eac 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -23,6 +23,8 @@ /** * BigTreeTech SKR E3 Turbo pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/BTT%20SKR%20E3%20Turbo/BTT%20SKR%20E3%20Turbo-SCH.pdf + * Origin: https://github.com/bigtreetech/BIGTREETECH-SKR-E3-Turbo/blob/master/Hardware/BTT%20SKR%20E3%20Turbo-SCH.pdf */ #include "env_validate.h" @@ -31,6 +33,8 @@ #define BOARD_INFO_NAME "BTT SKR E3 Turbo" #endif +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #define USES_DIAG_JUMPERS // Onboard I2C EEPROM diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h index 7f428fc91881..8ca065a0cf0f 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_V1_4_TURBO.h @@ -23,10 +23,14 @@ /** * BigTreeTech SKR 1.4 Turbo pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/BTT%20SKR%20V1.4%20+%20Turbo/BTT%20SKR%20V1.4-SCH.pdf + * Origin: https://github.com/bigtreetech/BIGTREETECH-SKR-V1.3/blob/master/BTT%20SKR%20V1.4/Hardware/BTT%20SKR%20V1.4-SCH.pdf */ #define BOARD_INFO_NAME "BTT SKR V1.4 TURBO" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Include SKR 1.4 pins // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h index f9f2345d9c21..16960a29247c 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_MINI.h @@ -23,12 +23,17 @@ /** * Cohesion3D Mini pin assignments + * Pinout: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Cohesion3D%20Mini/c3d-pinout.jpg + * Origin: https://lasergods.com/cohesion3d-mini-pinout-diagram/ */ #include "env_validate.h" #define BOARD_INFO_NAME "Cohesion3D Mini" +// Just a wild guess due to no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h index 3702acec73f8..491e600c3654 100644 --- a/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h +++ b/Marlin/src/pins/lpc1769/pins_COHESION3D_REMIX.h @@ -23,12 +23,16 @@ /** * Cohesion3D ReMix pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Cohesion3D%20ReMix/C3D%20ReMix%20rev2.svg + * Origin: https://github.com/Cohesion3D/Cohesion3D-ReMix/blob/master/C3D%20ReMix%20rev2.sch */ #include "env_validate.h" #define BOARD_INFO_NAME "Cohesion3D ReMix" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h index 21f262ad4195..4c33c1505a7d 100644 --- a/Marlin/src/pins/lpc1769/pins_FLY_CDY.h +++ b/Marlin/src/pins/lpc1769/pins_FLY_CDY.h @@ -23,6 +23,8 @@ /** * FLYmaker FLY-CDY pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/FLYmaker%20FLY-CDY%20V1/FLY_CDY%20SCH.pdf + * Origin: https://github.com/Mellow-3D/FLY-CDY/blob/master/Motherboard%20information/FLY_CDY%20SCH.pdf */ #include "env_validate.h" @@ -30,6 +32,8 @@ #define BOARD_INFO_NAME "FLY-CDY" #define BOARD_WEBSITE_URL "github.com/FLYmaker/FLY-CDY" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h index 23bcecc78d74..e7f3decc3b8b 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN.h @@ -23,6 +23,8 @@ /** * MKS SGen pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/MKS%20SGEN/MKS%20SGEN%20V1.0_001%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20SCH.pdf * * Pins diagram: * https://github.com/makerbase-mks/MKS-SGen/blob/master/Hardware/MKS%20SGEN%20V1.0_001/MKS%20SGEN%20V1.0_001%20PIN.pdf @@ -31,6 +33,9 @@ #define BOARD_INFO_NAME "MKS SGen" #define BOARD_WEBSITE_URL "github.com/makerbase-mks/MKS-SGEN" +// Just a wild guess because schematic does not say! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + #define REQUIRE_LPC1769 #include "../lpc1768/pins_MKS_SBASE.h" diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index 7a98a100a91f..65104b52ad67 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -23,6 +23,8 @@ /** * MKS SGen-L V2 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/MKS%20SGEN_L%20V2/MKS%20SGEN_L%20V2.0_003%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-SGEN_L-V2/blob/master/Hardware/MKS%20SGEN_L%20V2.0_003/MKS%20SGEN_L%20V2.0_003%20SCH.pdf */ #include "env_validate.h" @@ -32,6 +34,9 @@ #define USES_DIAG_JUMPERS +// Just a wild guess because schematic does not say! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // EEPROM, MKS SGEN_L V2.0 hardware has 4K EEPROM on the board // diff --git a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h index cfaca164f89e..cc32dac9a638 100644 --- a/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_SMOOTHIEBOARD.h @@ -23,6 +23,8 @@ /** * Smoothieware Smoothieboard pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Smoothieware%20Smoothieboard%20V1/http.i.imgur.com.oj4zqs3.png + * Origin: http://smoothieware.org/_media///external/http.i.imgur.com.oj4zqs3.png */ #include "env_validate.h" @@ -30,6 +32,8 @@ #define BOARD_INFO_NAME "Smoothieboard" #define BOARD_WEBSITE_URL "smoothieware.org/smoothieboard" +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h index f794e178f911..09aea8e5b481 100644 --- a/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h +++ b/Marlin/src/pins/lpc1769/pins_TH3D_EZBOARD.h @@ -32,6 +32,9 @@ #define BOARD_INFO_NAME "TH3D EZBoard" #define BOARD_WEBSITE_URL "th3dstudio.com" +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h index 690df5b3d7a5..7388c4ed3ec3 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONIC.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONIC.h @@ -29,6 +29,10 @@ #include "env_validate.h" #define BOARD_INFO_NAME "Cheaptronic v1.0" + +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h index 9c2b1d82de03..6669a00743d6 100644 --- a/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h +++ b/Marlin/src/pins/mega/pins_CHEAPTRONICv2.h @@ -24,7 +24,8 @@ /** * Cheaptronic v2.0 pin assignments * Built and sold by Michal Dyntar - RRO - * www.reprapobchod.cz + * www.reprapobchod.cz (DOES NOT EXIST ANYMORE) + * https://web.archive.org/web/20190306201523/http://reprapobchod.cz/ * ATmega2560 */ @@ -32,6 +33,9 @@ #define BOARD_INFO_NAME "Cheaptronic v2.0" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h index b6453167602a..5fc149835af4 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_11.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_11.h @@ -23,6 +23,8 @@ /** * CartesioV11 pin assignments + * Comes with an Arduino Mega, see + * https://web.archive.org/web/20171024190029/http://mauk.cc/mediawiki/index.php/Electronical_assembly * ATmega2560, ATmega1280 */ @@ -31,6 +33,8 @@ #define BOARD_INFO_NAME "CN Controls V11" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h index 0bfab09187ec..3cb6d4abe537 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_12.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_12.h @@ -23,6 +23,8 @@ /** * CartesioV12 pin assignments + * Comes with an Arduino Mega, see + * https://web.archive.org/web/20171024190029/http://mauk.cc/mediawiki/index.php/Electronical_assembly * ATmega2560, ATmega1280 */ @@ -31,6 +33,8 @@ #define BOARD_INFO_NAME "CN Controls V12" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h index 8ab256afd83d..38bfcade90c6 100644 --- a/Marlin/src/pins/mega/pins_CNCONTROLS_15.h +++ b/Marlin/src/pins/mega/pins_CNCONTROLS_15.h @@ -31,6 +31,9 @@ #define BOARD_INFO_NAME "CN Controls V15" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_EINSTART-S.h b/Marlin/src/pins/mega/pins_EINSTART-S.h index 2964e7c17ed9..2fd49ef1682e 100644 --- a/Marlin/src/pins/mega/pins_EINSTART-S.h +++ b/Marlin/src/pins/mega/pins_EINSTART-S.h @@ -32,6 +32,9 @@ #define BOARD_INFO_NAME "Einstart-S" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_ELEFU_3.h b/Marlin/src/pins/mega/pins_ELEFU_3.h index 223f2a9520c3..850b0ae75fb6 100644 --- a/Marlin/src/pins/mega/pins_ELEFU_3.h +++ b/Marlin/src/pins/mega/pins_ELEFU_3.h @@ -23,6 +23,8 @@ /** * Elefu RA Board Pin Assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Elefu%20Ra%20v3/schematic.pdf + * Origin: https://github.com/kiyoshigawa/Elefu-RAv3/blob/master/RA_Circuits.zip * ATmega2560 */ @@ -30,6 +32,8 @@ #define BOARD_INFO_NAME "Elefu Ra v3" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A.h b/Marlin/src/pins/mega/pins_GT2560_REV_A.h index eb7191e70c5a..ef7195751896 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A.h @@ -25,6 +25,8 @@ * Geeetech GT2560 Revision A board pin assignments, based on the work of * George Robles (https://georges3dprinters.com) and * Richard Smith + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%20Revision%20A/GT2560_sch.pdf + * Origin: https://www.geeetech.com/wiki/images/9/90/GT2560_sch.pdf * ATmega2560 */ diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h index 27b7accb0b24..2ba7739fb0c2 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_A_PLUS.h @@ -23,11 +23,15 @@ /** * Geeetech GT2560 Revision A+ board pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%20Revision%20A+/Hardware_GT2560_RevA+.pdf + * Origin: https://www.geeetech.com/wiki/images/d/d3/Hardware_GT2560_RevA%2B.pdf * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 Rev.A+" +//#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #include "pins_GT2560_REV_A.h" #if DISABLED(BLTOUCH) diff --git a/Marlin/src/pins/mega/pins_GT2560_REV_B.h b/Marlin/src/pins/mega/pins_GT2560_REV_B.h index d2732e34dc26..866b87e1e107 100644 --- a/Marlin/src/pins/mega/pins_GT2560_REV_B.h +++ b/Marlin/src/pins/mega/pins_GT2560_REV_B.h @@ -23,9 +23,13 @@ /** * Geeetech GT2560 Rev B Pins + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%20Rev%20B/GT2560_REVB.pdf + * Origin: https://www.geeetech.com/wiki/images/7/72/GT2560_REVB.pdf * ATmega2560 */ #define BOARD_INFO_NAME "GT2560 Rev B" +//#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index 5c94f6360979..f3e3dae02753 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -23,6 +23,8 @@ /** * Geeetech GT2560 3.0/3.1 pin assignments + * Schematic (3.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%203.0/GT2560_V3.0_SCH.pdf + * Origin (3.0): https://github.com/Geeetech3D/Diagram/blob/master/GT2560_V3.0_SCH.pdf * ATmega2560 * * Also GT2560 RevB and GT2560 4.0/4.1 @@ -35,6 +37,8 @@ #define BOARD_INFO_NAME "GT2560 3.x" #endif +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_GT2560_V4.h b/Marlin/src/pins/mega/pins_GT2560_V4.h index 6ac07b70bfce..5635beeccfea 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V4.h +++ b/Marlin/src/pins/mega/pins_GT2560_V4.h @@ -23,8 +23,13 @@ /** * Geeetech GT2560 V4.X Pins + * Schematic (4.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%20V4.x%20+%20A20/GT2560V4.0SCHA20T.pdf + * Schematic (4.1B): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Geeetech%20GT2560%20V4.x%20+%20A20/GT2560V4.1BSCHA20T.pdf + * Origin: https://www.geeetech.com/download.html?spm=a2g0s.imconversation.0.0.22d23e5fXlQBWv&download_id=45 */ #define BOARD_INFO_NAME "GT2560 4.x" +//#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #include "pins_GT2560_V3.h" diff --git a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h index 11a65da03332..b5775b689dae 100644 --- a/Marlin/src/pins/mega/pins_HJC2560C_REV2.h +++ b/Marlin/src/pins/mega/pins_HJC2560C_REV2.h @@ -31,6 +31,9 @@ #define DEFAULT_MACHINE_NAME "ADIMLab Gantry v2" #define BOARD_INFO_NAME "HJC2560-C" +// Just a wild guess because no schematic! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index 9217b307ad97..085841fceb77 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -32,6 +32,9 @@ #define BOARD_INFO_NAME "Intamsys 4.0" +// Just a wild guess because no schematic! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_LEAPFROG.h b/Marlin/src/pins/mega/pins_LEAPFROG.h index 21d63aa9b622..1f7b6de9299e 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG.h @@ -31,6 +31,9 @@ #define BOARD_INFO_NAME "Leapfrog" +// Just a wild guess because no schematic! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h index d17382f4d494..b82ab2b3473e 100644 --- a/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h +++ b/Marlin/src/pins/mega/pins_LEAPFROG_XEED2015.h @@ -34,6 +34,9 @@ #define BOARD_INFO_NAME "Leapfrog Xeed 2015" +// Just a wild guess because no schematic! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h index 4d8c42f12259..208e68533e11 100644 --- a/Marlin/src/pins/mega/pins_MALYAN_M180.h +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -31,6 +31,10 @@ #include "env_validate.h" #define BOARD_INFO_NAME "Malyan M180 v.2" + +// Just a wild guess because no schematic! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index d0e117a2c467..95d01c86c8c1 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -23,6 +23,8 @@ /** * Mega controller pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Mega%20Controller/Mega_controller.pdf + * Origin: https://reprap.org/mediawiki/images/b/ba/Mega_controller.pdf * ATmega2560 */ @@ -34,6 +36,8 @@ #define BOARD_INFO_NAME "Mega Controller" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index 5f2ed5bea6d9..3cacdc030030 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -23,12 +23,18 @@ /** * MegaTronics pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/MegaTronics/Megatronics_1_0_sch.pdf + * Origin: https://reprap.org/mediawiki/images/a/a3/Megatronics_1_0_sch.pdf * ATmega2560 */ #include "env_validate.h" #define BOARD_INFO_NAME "Megatronics" + +// Just a wild guess because schematic does not say! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index b6c5c0bbeca8..f13dd4cde428 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -23,12 +23,17 @@ /** * MegaTronics v2.0 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Megatronics%20v2.0/megatronics%20-%20Project.pdf + * Origin: https://reprap.org/wiki/File:Megatronicsv2PDF.zip * ATmega2560 */ #include "env_validate.h" #define BOARD_INFO_NAME "Megatronics v2.0" + +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index ffe9a54e7d05..48299cb0dd1b 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -23,6 +23,7 @@ /** * MegaTronics v3.0 / v3.1 / v3.2 pin assignments + * Schematic Origin: https://github.com/brupje/Megatronics_3/blob/master/Design%20Files/megatronics.sch * ATmega2560 */ @@ -36,6 +37,9 @@ #define BOARD_INFO_NAME "Megatronics v3.0" #endif +// Just a wild guess because the provided schematics do not work. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h index 840e02776456..5be0bb2236b9 100644 --- a/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/src/pins/mega/pins_MIGHTYBOARD_REVE.h @@ -23,6 +23,8 @@ /** * Mightyboard Rev.E pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Mightyboard%20Rev.E/MakerBot%20MightyBoard%20REVE%20Schematic.pdf + * Origin: https://github.com/sciguy14/HelioWatcher/blob/master/HelioWatcher%20Circuit/MakerBot%20MightyBoard%20REVE%20Schematic.pdf * also works for Rev D boards. It's all rev E despite what the silk screen says */ diff --git a/Marlin/src/pins/mega/pins_MINITRONICS.h b/Marlin/src/pins/mega/pins_MINITRONICS.h index 5fd6ebbcb0d9..d4d62831db54 100644 --- a/Marlin/src/pins/mega/pins_MINITRONICS.h +++ b/Marlin/src/pins/mega/pins_MINITRONICS.h @@ -23,6 +23,10 @@ /** * Minitronics v1.0/1.1 pin assignments + * Schematic (1.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Minitronics%20v1.0/minitronics%20-%20Project.pdf + * Origin (1.0): https://reprap.org/wiki/File:MinitronicsPDF.zip + * Datasheet (1.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Minitronics%20v1.1/datasheet%20minitronics%20v1.1.pdf + * Origin (1.1): https://reprapworld.nl/documentation/datasheet%20minitronics%20v1.1.pdf * ATmega1281 */ @@ -39,6 +43,10 @@ #endif #define BOARD_INFO_NAME "Minitronics v1.0/1.1" + +// Just a wild guess because schematic does not say! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_OVERLORD.h b/Marlin/src/pins/mega/pins_OVERLORD.h index dc73261d7fa8..b2955bae359c 100644 --- a/Marlin/src/pins/mega/pins_OVERLORD.h +++ b/Marlin/src/pins/mega/pins_OVERLORD.h @@ -23,6 +23,8 @@ /** * Dreammaker Overlord v1.1 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Dreammaker%20Overlord%20v1.1/Schematic.pdf + * Origin: https://github.com/jdpiercy/Overlord-Pro/blob/master/Motherboard/Schematic.pdf * ATmega2560 */ @@ -35,6 +37,8 @@ #define BOARD_INFO_NAME "OVERLORD" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index b69c6787a46d..1920ad6407a9 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -23,6 +23,8 @@ /** * Arduino Mega with PICA pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/PICA/pica_schematic.pdf + * Origin: https://github.com/mjrice/PICA/blob/master/pica_schematic.pdf * ATmega2560 * * PICA is Power, Interface, and Control Adapter and is open source hardware. @@ -37,6 +39,9 @@ #define BOARD_INFO_NAME "PICA" #endif +// Arduino Mega. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + /* // Note that these are the "pins" that correspond to the analog inputs on the arduino mega. // These are not the same as the physical pin numbers diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index 7782c8e8b343..bdd8c46922f9 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -21,6 +21,8 @@ */ #pragma once +// Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/PICAOLD/pica_schematic.pdf +// Origin: https://github.com/mjrice/PICA/blob/97ab9e7771a8e5eef97788f3adcc17a9fa9de9b9/pica_schematic.pdf // ATmega2560 #define HEATER_0_PIN PinH6 // E0 diff --git a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h index ed2a06ca47a1..f38b455c91a0 100644 --- a/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h +++ b/Marlin/src/pins/mega/pins_PROTONEER_CNC_SHIELD_V3.h @@ -23,6 +23,8 @@ /** * Protoneer v3.00 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Protoneer%20CNC%20Shield%20v3.00/Arduino-CNC-Shield-Scematics-V3.XX_.webp + * Origin: https://i0.wp.com/blog.protoneer.co.nz/wp-content/uploads/2013/07/Arduino-CNC-Shield-Scematics-V3.XX_.jpg * ATmega2560 * * This CNC shield has an UNO pinout and fits all Arduino-compatibles. @@ -36,6 +38,9 @@ #define BOARD_INFO_NAME "Protoneer CNC Shield v3.00" +// I guess an Arduino Mega. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_SILVER_GATE.h b/Marlin/src/pins/mega/pins_SILVER_GATE.h index 5f96f89431d2..74d4afe1f26b 100644 --- a/Marlin/src/pins/mega/pins_SILVER_GATE.h +++ b/Marlin/src/pins/mega/pins_SILVER_GATE.h @@ -29,6 +29,9 @@ #define BOARD_INFO_NAME "Silver Gate" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define X_STEP_PIN PinA5 #define X_DIR_PIN PinA6 #define X_ENABLE_PIN PinA4 diff --git a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h index 3089ed796c02..595a18fec3b7 100644 --- a/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h +++ b/Marlin/src/pins/mega/pins_WANHAO_ONEPLUS.h @@ -32,6 +32,9 @@ #define DEFAULT_MACHINE_NAME "i3 Mini" #define BOARD_WEBSITE_URL "tinyurl.com/yyxw7se7" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/mega/pins_WEEDO_62A.h b/Marlin/src/pins/mega/pins_WEEDO_62A.h index 7b87edf2e436..1bbcdca2a846 100644 --- a/Marlin/src/pins/mega/pins_WEEDO_62A.h +++ b/Marlin/src/pins/mega/pins_WEEDO_62A.h @@ -34,6 +34,8 @@ #define BOARD_INFO_NAME "WEEDO 62A" #endif +// Just a wild guess because no schematics! + // // Limit Switches // diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 10623771b968..89658d9ce542 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -23,6 +23,8 @@ /** * Einsy-Rambo pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Einsy-Rambo/Schematic%20Prints_Einsy%20Rambo_1.1a.PDF + * Origin: https://github.com/ultimachine/Einsy-Rambo/blob/1.1a/board/Project%20Outputs/Schematic%20Prints_Einsy%20Rambo_1.1a.PDF */ #include "env_validate.h" @@ -30,6 +32,8 @@ #define BOARD_INFO_NAME "Einsy Rambo" #define DEFAULT_MACHINE_NAME "Prusa MK3" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + //#define MK3_FAN_PINS // diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index 65af045f8c84..b624b97740e5 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -23,12 +23,18 @@ /** * Einsy-Retro pin assignments + * Schematic (1.0b): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Einsy-Retro/Schematic%20Prints_EinsyRetro_1.0b.PDF + * Origin (1.0b): https://github.com/ultimachine/EinsyRetro/blob/master/board/Project%20Outputs/Schematic%20Prints_EinsyRetro_1.0b.PDF + * Schematic (1.0c): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Einsy-Retro/Schematic%20Prints_EinsyRetro_1.0c.PDF + * Origin (1.0c): https://github.com/ultimachine/EinsyRetro/blob/master/board/Project%20Outputs/Schematic%20Prints_EinsyRetro_1.0c.PDF */ #include "env_validate.h" #define BOARD_INFO_NAME "Einsy Retro" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // TMC2130 Configuration_adv defaults for EinsyRetro // diff --git a/Marlin/src/pins/rambo/pins_MINIRAMBO.h b/Marlin/src/pins/rambo/pins_MINIRAMBO.h index 6da9e97de92e..33d2bc9a2382 100644 --- a/Marlin/src/pins/rambo/pins_MINIRAMBO.h +++ b/Marlin/src/pins/rambo/pins_MINIRAMBO.h @@ -23,6 +23,10 @@ /** * Mini-RAMBo pin assignments + * Schematic (1.3a): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Mini%20RAMBo/Mini-Rambo.PDF + * Origin (1.3a): https://github.com/ultimachine/Mini-Rambo/blob/1.3a/board/Project%20Outputs%20for%20Mini-Rambo/Mini-Rambo.PDF + * Schematic (1.0a): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Mini%20RAMBo%201.0a/Mini-Rambo.PDF + * Origin (1.0a): https://github.com/ultimachine/Mini-Rambo/blob/v1.1b/board/Project%20Outputs%20for%20Mini-Rambo/Mini-Rambo.PDF */ #include "env_validate.h" @@ -33,6 +37,8 @@ #define BOARD_INFO_NAME "Mini RAMBo" #endif +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/rambo/pins_RAMBO.h b/Marlin/src/pins/rambo/pins_RAMBO.h index 8b96f883fb89..faee2153fc86 100644 --- a/Marlin/src/pins/rambo/pins_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_RAMBO.h @@ -39,6 +39,8 @@ /** * Rambo pin assignments + * Schematic (1.1b): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMBo/Rambo1-1-schematic.png + * Origin (1.1b): https://www.reprap.org/wiki/File:Rambo1-1-schematic.png */ #include "env_validate.h" @@ -47,6 +49,10 @@ #define BOARD_INFO_NAME "Rambo" #endif +#ifndef AVR_CHIPOSCILLATOR_FREQ + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Servos // diff --git a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h index 8d85fe4524ed..e45c8974e3f5 100755 --- a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h +++ b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h @@ -27,6 +27,9 @@ #define BOARD_INFO_NAME "Rambo ThinkerV2" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define SERVO0_PIN PinG5 // Motor header MX1 #define SERVO2_PIN -1 // Motor header MX3 diff --git a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h index ae7a32ad95b2..7a6a94fef02d 100644 --- a/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h +++ b/Marlin/src/pins/rambo/pins_SCOOVO_X9H.h @@ -25,10 +25,13 @@ * Rambo pin assignments MODIFIED FOR Scoovo X9H ************************************************/ -#include "env_target.h" +#include "env_validate.h" #define BOARD_INFO_NAME "Scoovo X9H" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 02ee173d35af..57cedf411f54 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -23,6 +23,9 @@ /** * 3DRAG (and K8200 / K8400) Arduino Mega with RAMPS v1.4 pin assignments + * This may be compatible with the standalone Controller variant. + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/3DRAG%20+%20Controller/Schema_base.jpg + * Origin: https://reprap.org/wiki/File:Schema_base.jpg * ATmega2560, ATmega1280 */ @@ -38,6 +41,11 @@ #define DEFAULT_SOURCE_CODE_URL "3dprint.elettronicain.it" #endif +// Just a wild guess because schematic does not say! +#ifndef AVR_CHIPOSCILLATOR_FREQ + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h index 7a111f41ef6a..656ce9a786ed 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3.h @@ -23,6 +23,8 @@ /** * AZTEEG_X3 Arduino Mega with RAMPS v1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/AZTEEG_X3/AZTEEG%20X3%20PUB%20v1.12.pdf + * Origin: http://files.panucatt.com/datasheets/azteegx3_designfiles.zip * ATmega2560 */ @@ -38,6 +40,8 @@ #endif #define BOARD_INFO_NAME "Azteeg X3" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h index 78486793dab0..84088f424211 100644 --- a/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h +++ b/Marlin/src/pins/ramps/pins_AZTEEG_X3_PRO.h @@ -23,6 +23,8 @@ /** * AZTEEG_X3_PRO (Arduino Mega) pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/AZTEEG_X3_PRO/AZTEEG%20X3%20PRO%201.0%20PUB.pdf + * Origin: http://files.panucatt.com/datasheets/x3pro_sch_v1.0.zip * ATmega2560 */ @@ -35,6 +37,9 @@ #define BOARD_INFO_NAME "Azteeg X3 Pro" +// Just a wild guess because schematic does not say! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // RAMPS pins overrides // diff --git a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h index 8593fe5a82cc..d43d6f3557e7 100644 --- a/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h +++ b/Marlin/src/pins/ramps/pins_BAM_DICE_DUE.h @@ -23,6 +23,8 @@ /** * BAM&DICE Due (Arduino Mega) pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/BAM&DICE%20Due/2PRINTBETA-BAM&DICE-DUE-V1.1-sch.pdf + * Origin: http://www.2printbeta.de/download/2PRINTBETA-BAM&DICE-DUE-V1.1-sch.pdf * ATmega2560, ATmega1280 */ @@ -32,6 +34,9 @@ #define BOARD_INFO_NAME "2PrintBeta Due" +// Arduino Mega. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // M3/M4/M5 - Spindle/Laser Control // diff --git a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h index 8fc4158f1cf7..28b21000090a 100644 --- a/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h +++ b/Marlin/src/pins/ramps/pins_BIQU_KFB_2.h @@ -32,6 +32,9 @@ #define BOARD_INFO_NAME "KFB 2.0" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Heaters / Fans // diff --git a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h index 9dcf3a760552..51b66eb38d66 100644 --- a/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/src/pins/ramps/pins_BQ_ZUM_MEGA_3D.h @@ -23,6 +23,8 @@ /** * bq ZUM Mega 3D board definition + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/bq%20ZUM%20Mega%203D/Zum%20Mega%203D.PDF + * Origin: https://github.com/bq/zum/blob/master/zum-mega3d/Zum%20Mega%203D.PDF * ATmega2560 */ @@ -31,6 +33,8 @@ #define BOARD_INFO_NAME "ZUM Mega 3D" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h index ad5b9d9dc5c4..01cb5534d5a0 100644 --- a/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h +++ b/Marlin/src/pins/ramps/pins_DUPLICATOR_I3_PLUS.h @@ -31,6 +31,9 @@ #define BOARD_INFO_NAME "Duplicator i3 Plus" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h index a6670f4c8182..c6516b24eb0e 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_RAPTOR.h @@ -40,6 +40,9 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #endif +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h index 2a3f04195967..d7d9109f8d4e 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX2PLUS.h @@ -22,7 +22,7 @@ #pragma once /** - * Formbot pin assignments + * Formbot T-Rex 2+ pin assignments * ATmega2560 */ @@ -33,9 +33,12 @@ #error "Formbot supports up to 2 hotends / E steppers." #endif -#define BOARD_INFO_NAME "Formbot" +#define BOARD_INFO_NAME "Formbot T-Rex 2+" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h index 5936b50d6f24..c98e141e76fd 100644 --- a/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h +++ b/Marlin/src/pins/ramps/pins_FORMBOT_TREX3.h @@ -22,7 +22,7 @@ #pragma once /** - * Formbot pin assignments + * Formbot T-Rex 3 pin assignments * ATmega2560 */ @@ -33,9 +33,12 @@ #error "Formbot supports up to 2 hotends / E steppers." #endif -#define BOARD_INFO_NAME "Formbot" +#define BOARD_INFO_NAME "Formbot T-Rex 3" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h index 0f8bb4fa7cdc..16d6fef5151a 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_13.h @@ -23,6 +23,8 @@ // // FYSETC F6 1.3 (and 1.4) pin assignments +// Schematic (1.3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/FYSETC%20F6%201.3/F6_V13.pdf +// Origin: https://github.com/FYSETC/FYSETC-F6/blob/master/Hardware/V1.3/F6_V13.pdf // ATmega2560 // @@ -34,6 +36,8 @@ #define BOARD_INFO_NAME "FYSETC F6 1.3" #endif +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define RESET_PIN PinC7 #define SPI_FLASH_CS_PIN PinD6 diff --git a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h index fb20bc9e402b..cbbf9e906c13 100644 --- a/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h +++ b/Marlin/src/pins/ramps/pins_FYSETC_F6_14.h @@ -23,6 +23,8 @@ // // FYSETC F6 v1.4 pin assignments +// Schematic (1.4): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/FYSETC%20F6%20v1.4/F6%20V1.4%20Sch.pdf +// Origin (1.4): https://github.com/FYSETC/FYSETC-F6/blob/master/Hardware/V1.4/F6%20V1.4%20Sch.pdf // ATmega2560 // diff --git a/Marlin/src/pins/ramps/pins_K8200.h b/Marlin/src/pins/ramps/pins_K8200.h index b15551982dbf..d2557b26c3ee 100644 --- a/Marlin/src/pins/ramps/pins_K8200.h +++ b/Marlin/src/pins/ramps/pins_K8200.h @@ -24,6 +24,8 @@ /** * K8200 Arduino Mega with RAMPS v1.3 pin assignments * Identical to 3DRAG + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Velleman%20K8200/K8200diagram.jpg + * Origin: https://www.velleman.eu/images/tmp/K8200diagram.jpg * ATmega2560 */ diff --git a/Marlin/src/pins/ramps/pins_K8400.h b/Marlin/src/pins/ramps/pins_K8400.h index f59e25330198..2b7411325ebc 100644 --- a/Marlin/src/pins/ramps/pins_K8400.h +++ b/Marlin/src/pins/ramps/pins_K8400.h @@ -24,6 +24,8 @@ /** * Velleman K8400 (Vertex) * 3DRAG clone + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Velleman%20K8400/k8400-schema-electronique.jpg + * Origin: https://filimprimante3d.fr/documents/k8400-schema-electronique.jpg * ATmega2560, ATmega1280 * * K8400 has some minor differences over a normal 3Drag: @@ -33,7 +35,7 @@ * - Second heater has moved pin */ -#define BOARD_INFO_NAME "K8400" +#define BOARD_INFO_NAME "Velleman K8400" #define DEFAULT_MACHINE_NAME "Vertex" // diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 4df79d9a2582..9203e1197981 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -30,7 +30,7 @@ #error "K8600 only supports 1 hotend / E stepper." #endif -#define BOARD_INFO_NAME "K8600" +#define BOARD_INFO_NAME "Velleman K8600" #define DEFAULT_MACHINE_NAME "Vertex Nano" // diff --git a/Marlin/src/pins/ramps/pins_K8800.h b/Marlin/src/pins/ramps/pins_K8800.h index 809d9fb5bb31..cdf3e35a2b92 100644 --- a/Marlin/src/pins/ramps/pins_K8800.h +++ b/Marlin/src/pins/ramps/pins_K8800.h @@ -23,14 +23,18 @@ /** * Velleman K8800 (Vertex) + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Velleman%20K8800/K8800-schematic-V1.4.pdf + * Origin: https://www.velleman.eu/downloads/files/vertex-delta/schematics/K8800-schematic-V1.4.pdf * ATmega2560, ATmega1280 */ #include "env_validate.h" -#define BOARD_INFO_NAME "K8800" +#define BOARD_INFO_NAME "Velleman K8800" #define DEFAULT_MACHINE_NAME "Vertex Delta" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h index 390c30d0cb7d..8d46ac36fa6e 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_10.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_10.h @@ -23,6 +23,11 @@ /** * MKS BASE 1.0 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * Schematics: + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20BASE%201.0/PAGE1.pdf + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20BASE%201.0/PAGE2.pdf + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20BASE%201.0/PAGE3.pdf + * Origin: https://reprap.org/wiki/File:MKS_Base_V1.0_source.zip * ATmega2560 * * Rev B - Override pin definitions for CASE_LIGHT and M3/M4/M5 spindle control diff --git a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h index 5f81c564d3d8..bd233f579f5f 100644 --- a/Marlin/src/pins/ramps/pins_MKS_BASE_16.h +++ b/Marlin/src/pins/ramps/pins_MKS_BASE_16.h @@ -23,6 +23,8 @@ /** * MKS BASE v1.6 with A4982 stepper drivers and digital micro-stepping + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20BASE%201.6/MKS%20Base%20V1.6_004%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-BASE/blob/master/hardware/MKS%20Base%20V1.6_004/MKS%20Base%20V1.6_004%20SCH.pdf * ATmega2560 */ diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h index a3624db8e4d5..3d16aed0450b 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_13.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_13.h @@ -23,6 +23,8 @@ /** * Arduino Mega with RAMPS v1.4 adjusted pin assignments + * Schematic (1.4): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20GEN%20v1.4/MKS%20GEN%20V1.4_004%20SCH.pdf + * Origin (1.4): https://github.com/makerbase-mks/MKS-GEN/blob/master/hardware/MKS%20GEN%20V1.4_004/MKS%20GEN%20V1.4_004%20SCH.pdf * ATmega2560, ATmega1280 * * MKS GEN v1.3 (Extruder, Fan, Bed) diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h index d23f937e9702..c5f1a601b0ef 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L.h @@ -23,8 +23,9 @@ /** * MKS GEN L – Arduino Mega2560 with RAMPS v1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20GEN%20L%20v1.0/MKS%20Gen_L%20V1.0_008%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-GEN_L/blob/master/hardware/MKS%20Gen_L%20V1.0_008/MKS%20Gen_L%20V1.0_008%20SCH.pdf * ATmega2560, ATmega1280 - * https://github.com/makerbase-mks/MKS-GEN_L/blob/master/hardware/MKS%20Gen_L%20V1.0_008/MKS%20Gen_L%20V1.0_008%20SCH.pdf */ #if HOTENDS > 2 || E_STEPPERS > 2 diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h index 57019fb84aec..6f46f30ffca3 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V2.h @@ -23,6 +23,8 @@ /** * MKS GEN L V2 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20GEN%20L%20V2.0/MKS%20Gen_L%20V2.0_001%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-GEN_L/blob/master/hardware/MKS%20Gen_L%20V2.0_001/MKS%20Gen_L%20V2.0_001%20SCH.pdf * ATmega2560 */ diff --git a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h index 66d10e4d1598..4def1765fa5d 100644 --- a/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h +++ b/Marlin/src/pins/ramps/pins_MKS_GEN_L_V21.h @@ -23,6 +23,8 @@ /** * MKS GEN L V2 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/MKS%20GEN%20L%20V2.1/MKS%20GEN_L%20V2.1_001%20SCH.pdf + * Origin: https://github.com/makerbase-mks/MKS-GEN_L/blob/master/hardware/MKS%20Gen_L%20V2.1_001/MKS%20GEN_L%20V2.1_001%20SCH.pdf * ATmega2560 */ diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index 0fdd4a334672..55ca4580b3ce 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -50,8 +50,7 @@ #error "No pins defined for RAMPS with AZSMZ_12864." #endif -// https://www.arduino.cc/en/uploads/Main/arduino-mega2560-schematic.pdf -#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #include "env_validate.h" @@ -62,6 +61,12 @@ #define BOARD_INFO_NAME "RAMPS 1.4" #endif +// Arduino Mega. +#ifndef AVR_CHIPOSCILLATOR_FREQ + // https://www.arduino.cc/en/uploads/Main/arduino-mega2560-schematic.pdf + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index e659f74f0673..be6c6fa21c91 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -23,6 +23,8 @@ /** * RUMBA pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/RUMBA/RRD-RUMBA_SCHEMATICS.png + * Origin: https://reprap.org/wiki/File:RRD-RUMBA_SCHEMATICS.png * ATmega2560 */ @@ -40,6 +42,10 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #endif +#ifndef AVR_CHIPOSCILLATOR_FREQ + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h index dff2b8651427..3a6a5add35b4 100644 --- a/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h +++ b/Marlin/src/pins/ramps/pins_SAINSMART_2IN1.h @@ -30,7 +30,7 @@ #error "Sainsmart 2-in-1 supports up to 2 hotends / E steppers." #endif -#define BOARD_INFO_NAME "Sainsmart" +#define BOARD_INFO_NAME "Sainsmart 2-in-1" // // Heaters / Fans diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 3d86ba5a1842..4c72bb7017f2 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -23,11 +23,15 @@ /** * BIQU Tango pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/BIQU%20Tango/schematic.png + * Origin: https://github.com/bigtreetech/Tango-3D-Printer-Motherboard/blob/master/Schematic/Tango%20V1.0.SchDoc * ATmega2560 */ #define BOARD_INFO_NAME "Tango" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define FAN_PIN PinH5 #define FAN1_PIN -1 diff --git a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h index d608348f1c33..a11e354b5fe0 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_D3_HERO.h @@ -22,7 +22,7 @@ #pragma once /** - * Tenlog pin assignments + * Tenlog D3 Hero pin assignments * ATmega2560 */ @@ -36,6 +36,9 @@ #define BOARD_INFO_NAME "Tenlog D3 Hero" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h index b3f7d5f216b5..ce8ff9211bd3 100644 --- a/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h +++ b/Marlin/src/pins/ramps/pins_TENLOG_MB1_V23.h @@ -22,7 +22,8 @@ #pragma once /** - * Tenlog pin assignments + * Tenlog MB1 V2.3 pin assignments + * ATmega2560 */ #define REQUIRE_MEGA2560 @@ -35,97 +36,100 @@ #define BOARD_INFO_NAME "Tenlog MB1 V2.3" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 -#define Y_MIN_PIN 14 -//#define Y_MAX_PIN 15 // Connected to "DJ" plug on extruder heads -#define Z_MIN_PIN 18 +#define X_MIN_PIN PinE5 +#define X_MAX_PIN PinE4 +#define Y_MIN_PIN PinJ1 +//#define Y_MAX_PIN PinJ0 // Connected to "DJ" plug on extruder heads +#define Z_MIN_PIN PinD3 #if ENABLED(BLTOUCH) - #define SERVO0_PIN 19 + #define SERVO0_PIN PinD2 #else - #define Z_MAX_PIN 19 + #define Z_MAX_PIN PinD2 #endif // // Steppers // -#define X_STEP_PIN 54 -#define X_DIR_PIN 55 -#define X_ENABLE_PIN 38 +#define X_STEP_PIN PinF0 +#define X_DIR_PIN PinF1 +#define X_ENABLE_PIN PinD7 -#define X2_STEP_PIN 36 -#define X2_DIR_PIN 34 -#define X2_ENABLE_PIN 30 +#define X2_STEP_PIN PinC1 +#define X2_DIR_PIN PinC3 +#define X2_ENABLE_PIN PinC7 -#define Y_STEP_PIN 60 -#define Y_DIR_PIN 61 -#define Y_ENABLE_PIN 56 +#define Y_STEP_PIN PinF6 +#define Y_DIR_PIN PinF7 +#define Y_ENABLE_PIN PinF2 -#define Z_STEP_PIN 46 -#define Z_DIR_PIN 48 -#define Z_ENABLE_PIN 62 +#define Z_STEP_PIN PinL3 +#define Z_DIR_PIN PinL1 +#define Z_ENABLE_PIN PinK0 -#define Z2_STEP_PIN 65 -#define Z2_DIR_PIN 66 -#define Z2_ENABLE_PIN 64 +#define Z2_STEP_PIN PinK3 +#define Z2_DIR_PIN PinK4 +#define Z2_ENABLE_PIN PinK2 -#define E0_STEP_PIN 57 -#define E0_DIR_PIN 58 -#define E0_ENABLE_PIN 59 +#define E0_STEP_PIN PinF3 +#define E0_DIR_PIN PinF4 +#define E0_ENABLE_PIN PinF5 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 +#define E1_STEP_PIN PinA4 +#define E1_DIR_PIN PinA6 +#define E1_ENABLE_PIN PinA2 // // Temperature Sensors // -#define TEMP_0_PIN 15 // Analog Input -#define TEMP_1_PIN 13 // Analog Input -#define TEMP_BED_PIN 14 // Analog Input +#define TEMP_0_PIN PinJ0 // Analog Input +#define TEMP_1_PIN PinB7 // Analog Input +#define TEMP_BED_PIN PinJ1 // Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 11 -#define HEATER_1_PIN 10 -#define HEATER_BED_PIN 8 +#define HEATER_0_PIN PinB5 +#define HEATER_1_PIN PinB4 +#define HEATER_BED_PIN PinH5 -#define FAN_PIN 9 -#define FAN2_PIN 5 // Normally this would be a servo pin +#define FAN_PIN PinH6 +#define FAN2_PIN PinE3 // Normally this would be a servo pin -//#define NUM_RUNOUT_SENSORS 0 -#define FIL_RUNOUT_PIN 15 -//#define FIL_RUNOUT2_PIN 21 +//#define NUM_RUNOUT_SENSORS PinE0 +#define FIL_RUNOUT_PIN PinJ0 +//#define FIL_RUNOUT2_PIN PinD0 // // PSU and Powerloss Recovery // #if ENABLED(PSU_CONTROL) - #define PS_ON_PIN 40 // The M80/M81 PSU pin for boards v2.1-2.3 + #define PS_ON_PIN PinG1 // The M80/M81 PSU pin for boards v2.1-2.3 #endif // // Misc. Functions // -//#define CASE_LIGHT_PIN 5 +//#define CASE_LIGHT_PIN PinE3 //#ifndef LED_PIN -// #define LED_PIN 13 +// #define LED_PIN PinB7 //#endif #if HAS_CUTTER //#define SPINDLE_LASER_PWM_PIN -1 // Hardware PWM - //#define SPINDLE_LASER_ENA_PIN 4 // Pullup! + //#define SPINDLE_LASER_ENA_PIN PinG5 // Pullup! #endif // Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -//#define FILWIDTH_PIN 5 // Analog Input +//#define FILWIDTH_PIN PinE3 // Analog Input -#define SDSS 53 -#define SD_DETECT_PIN 49 +#define SDSS PinB0 +#define SD_DETECT_PIN PinL0 // // LCD / Controller @@ -144,12 +148,12 @@ #define LCD_PINS_D6 -1 #define LCD_PINS_D7 -1 -//#define BTN_EN1 31 -//#define BTN_EN2 33 -//#define BTN_ENC 35 +//#define BTN_EN1 PinC6 +//#define BTN_EN2 PinC4 +//#define BTN_ENC PinC2 //#ifndef KILL_PIN -// #define KILL_PIN 41 +// #define KILL_PIN PinG0 //#endif //#endif // IS_RRD_SC diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 9a0bf5ee7e92..3a6773298c86 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -26,12 +26,15 @@ #include "env_validate.h" #if HOTENDS > 5 || E_STEPPERS > 5 - #error "TTOSCAR supports up to 5 hotends / E steppers." + #error "TT OSCAR supports up to 5 hotends / E steppers." #endif #define BOARD_INFO_NAME "TT OSCAR" #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h index 0e8147a314cd..70b77f8ee5b8 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAIN_2.h @@ -23,6 +23,24 @@ /** * Ultiboard v2.0 pin assignments + * Schematics (2.1.4): + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%202.1.4/schema1.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%202.1.4/schema2.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%202.1.4/schema3.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%202.1.4/schema4.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%202.1.4/schema5.png + * Origins (2.1.4): + * - https://github.com/Ultimaker/Ultimaker2/blob/master/1546%20ultimainboard%20V2.1.4/schema1.SchDoc + * - https://github.com/Ultimaker/Ultimaker2/blob/master/1546%20ultimainboard%20V2.1.4/schema2.SchDoc + * - https://github.com/Ultimaker/Ultimaker2/blob/master/1546%20ultimainboard%20V2.1.4/schema3.SchDoc + * - https://github.com/Ultimaker/Ultimaker2/blob/master/1546%20ultimainboard%20V2.1.4/schema4.SchDoc + * - https://github.com/Ultimaker/Ultimaker2/blob/master/1546%20ultimainboard%20V2.1.4/schema5.SchDoc + * Schematics (Original+): + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%20Original+/Ultimainboard%20rev.%202.1.1%20altium/schema1.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%20Original+/Ultimainboard%20rev.%202.1.1%20altium/schema2.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%20Original+/Ultimainboard%20rev.%202.1.1%20altium/schema3.png + * - https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%20Original+/Ultimainboard%20rev.%202.1.1%20altium/schema4.png + * Origin (Original+): https://github.com/Ultimaker/Ultimaker-Original-Plus/blob/master/1091_Main_board_v2.1.1_(x1)/Ultimainboard%20rev.%202.1.1%20altium.zip * ATmega2560 */ @@ -41,6 +59,8 @@ #define DEFAULT_MACHINE_NAME "Ultimaker" #define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER.h b/Marlin/src/pins/ramps/pins_ULTIMAKER.h index 8bc85da0c9de..fc84d60c1892 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER.h @@ -40,6 +40,9 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" +// Just a guess? +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h index f9f57b46893f..72a67809688a 100644 --- a/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h +++ b/Marlin/src/pins/ramps/pins_ULTIMAKER_OLD.h @@ -23,6 +23,8 @@ /** * Ultimaker pin assignments (Old electronics) + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%201.0/ultipanel%20rev1.1.sch.pdf + * Origin: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/Ultimaker%201.0/ultipanel%20rev1.1.sch.pdf * ATmega2560, ATmega1280 */ @@ -75,6 +77,9 @@ #define DEFAULT_MACHINE_NAME "Ultimaker" #define DEFAULT_SOURCE_CODE_URL "github.com/Ultimaker/Marlin" +// Arduino Mega. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V20.h b/Marlin/src/pins/ramps/pins_ZRIB_V20.h index 1cbd76cee040..17fe976373b8 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V20.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V20.h @@ -22,11 +22,17 @@ #pragma once /** - * ZRIB V2.0 & V3.0 pin assignments + * ZONESTAR ZRIB V2.0 & V3.0 pin assignments * V2 and V3 Boards only differ in USB controller, nothing affecting the pins. + * Schematic (2.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/ZONESTAR%20ZRIB%20V2.0/ZRIB_V2_Schematic.pdf + * Origin (2.0): https://github.com/ZONESTAR3D/Control-Board/blob/main/8bit/ZRIB/ZRIB_V2/ZRIB_V2_Schematic.pdf + * Schematic (3.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/ZONESTAR%20ZRIB%20V3.0/ZRIB_V3_Schematic.pdf + * Origin (3.0): https://github.com/ZONESTAR3D/Control-Board/blob/main/8bit/ZRIB/ZRIB_V3/ZRIB_V3_Schematic.pdf * ATmega2560, ATmega1280 */ +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #ifndef FILWIDTH_PIN #define FILWIDTH_PIN PinB5 // Analog Input #endif diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V52.h b/Marlin/src/pins/ramps/pins_ZRIB_V52.h index 8cd380cadeb4..918efcda19c5 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V52.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V52.h @@ -22,7 +22,9 @@ #pragma once /** - * ZRIB V5.2 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * ZONESTAR ZRIB V5.2 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/RAMPS/ZONESTAR%20ZRIB%20V5.2/ZRIB_V52_Schematic.pdf + * Origin: https://github.com/ZONESTAR3D/Control-Board/blob/main/8bit/ZRIB/ZRIB_V5/ZRIB_V52_Schematic.pdf * ATmega2560, ATmega1280 */ diff --git a/Marlin/src/pins/ramps/pins_ZRIB_V53.h b/Marlin/src/pins/ramps/pins_ZRIB_V53.h index 2c1cc9fd885c..23ad2583ce37 100644 --- a/Marlin/src/pins/ramps/pins_ZRIB_V53.h +++ b/Marlin/src/pins/ramps/pins_ZRIB_V53.h @@ -22,7 +22,7 @@ #pragma once /** - * ZRIB V5.3 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping + * ZONESTAR ZRIB V5.3 Based on MKS BASE v1.4 with A4982 stepper drivers and digital micro-stepping * ATmega2560, ATmega1280 */ @@ -36,6 +36,9 @@ #define BOARD_INFO_NAME "ZRIB V5.3" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // PIN 12 Connector // diff --git a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h index 02e2c2a4c23a..6dd93e89a61a 100644 --- a/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h +++ b/Marlin/src/pins/ramps/pins_Z_BOLT_X_SERIES.h @@ -35,6 +35,9 @@ #define BOARD_INFO_NAME "Z-Bolt X Series" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/sanguino/pins_ANET_10.h b/Marlin/src/pins/sanguino/pins_ANET_10.h index fc2dc1e57510..63253910698d 100644 --- a/Marlin/src/pins/sanguino/pins_ANET_10.h +++ b/Marlin/src/pins/sanguino/pins_ANET_10.h @@ -23,6 +23,8 @@ /** * Anet V1.0 board pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Anet%20V1.0/ANET3D_Board_Schematic.pdf + * Origin: https://github.com/ralf-e/ANET-3D-Board-V1.0/blob/master/ANET3D_Board_Schematic.pdf */ /** @@ -108,6 +110,8 @@ #define BOARD_INFO_NAME "Anet 1.0" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h index 4c721da00038..8e8794ba572d 100644 --- a/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h +++ b/Marlin/src/pins/sanguino/pins_AZTEEG_X1.h @@ -23,10 +23,14 @@ /** * Azteeg X1 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Azteeg%20X1/Azteeg_X1_schematics.pdf + * Origin: https://reprap.org/mediawiki/images/0/07/Azteeg_X1_schematics.pdf */ #define BOARD_INFO_NAME "Azteeg X1" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define FAN_PIN 4 #include "pins_SANGUINOLOLU_12.h" // ... SANGUINOLOLU_11 diff --git a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h index 93a21970616d..dafa633c9cc9 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_MONOLITHIC.h @@ -23,6 +23,7 @@ /** * Gen3 Monolithic Electronics pin assignments + * https://reprap.org/wiki/Generation_3_Electronics */ /** @@ -54,6 +55,9 @@ #define BOARD_INFO_NAME "Gen3 Monolithic" #define DEBUG_PIN PinB0 +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h index a68ca114496b..12e23e1e8366 100644 --- a/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h +++ b/Marlin/src/pins/sanguino/pins_GEN3_PLUS.h @@ -53,6 +53,9 @@ #define BOARD_INFO_NAME "Gen3+" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_GEN6.h b/Marlin/src/pins/sanguino/pins_GEN6.h index 6a1e79e5a084..50bbda30f659 100644 --- a/Marlin/src/pins/sanguino/pins_GEN6.h +++ b/Marlin/src/pins/sanguino/pins_GEN6.h @@ -23,6 +23,8 @@ /** * Gen6 pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen6/GEN6_Mendel_Circuit.pdf + * Origin: https://reprap.org/mediawiki/images/0/0f/GEN6_Mendel_Circuit.pdf */ /** @@ -57,6 +59,10 @@ #define BOARD_INFO_NAME "Gen6" #endif +#ifndef AVR_CHIPOSCILLATOR_FREQ + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_GEN7_12.h b/Marlin/src/pins/sanguino/pins_GEN7_12.h index b3b65dd3ea52..c0ff8e328edd 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_12.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_12.h @@ -23,6 +23,14 @@ /** * Gen7 v1.1, v1.2, v1.3 pin assignments + * Schematic (1.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.1/Gen7Board%20Schematic.pdf + * Origin (1.1): https://github.com/Traumflug/Generation_7_Electronics/blob/release-1.1/release%20documents/Gen7Board%20Schematic.pdf + * Schematic (1.2): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.2/Gen7Board%20Schematic.pdf + * Origin (1.2): https://github.com/Traumflug/Generation_7_Electronics/blob/release-1.2/release%20documents/Gen7Board%20Schematic.pdf + * Schematic (1.3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.3/Gen7Board%20Schematic.pdf + * Origin (1.3): https://github.com/Traumflug/Generation_7_Electronics/blob/release-1.3/release%20documents/Gen7Board%20Schematic.pdf + * Schematic (1.3.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.3.1/Gen7Board%20Schematic.pdf + * Origin (1.3.1): https://github.com/Traumflug/Generation_7_Electronics/blob/release-1.3.1/release%20documents/Gen7Board%20Schematic.pdf */ /** @@ -54,13 +62,20 @@ #include "env_validate.h" #ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "Gen7 v1.1 / 1.2" + #define BOARD_INFO_NAME "Gen7 v1.1 - v1.3" #endif #ifndef GEN7_VERSION #define GEN7_VERSION PinD4 // v1.x #endif +#if defined(GEN7_VERSION) && GEN7_VERSION >= 13 + // Holy moly! Check the schematic! Ring the alarm bells! + #define AVR_CHIPOSCILLATOR_FREQ 20000000 +#else + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_GEN7_14.h b/Marlin/src/pins/sanguino/pins_GEN7_14.h index ddd3f15005dc..4a54869c2823 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_14.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_14.h @@ -23,6 +23,10 @@ /** * Gen7 v1.4 pin assignments + * Schematic (1.4): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.4/Gen7Board%201.4%20Schematic.pdf + * Origin (1.4): https://github.com/Traumflug/Generation_7_Electronics/blob/Gen7Board-1.4/release%20documents/Gen7Board%201.4%20Schematic.pdf + * Schematic (1.4.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Gen7%20v1.4.1/Gen7Board%201.4.1%20Schematic.pdf + * Origin (1.4.1): https://github.com/Traumflug/Generation_7_Electronics/blob/Gen7Board-1.4.1/release%20documents/Gen7Board%201.4.1%20Schematic.pdf */ /** @@ -57,6 +61,9 @@ #define GEN7_VERSION 14 // v1.4 +// Holy moly! Check the schematic! Ring the alarm bells! +#define AVR_CHIPOSCILLATOR_FREQ 20000000 + // // Limit switches // diff --git a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h index 3b555a47f354..62bdb3906add 100644 --- a/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h +++ b/Marlin/src/pins/sanguino/pins_GEN7_CUSTOM.h @@ -58,6 +58,9 @@ #define BOARD_INFO_NAME "Gen7 Custom" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_MELZI.h b/Marlin/src/pins/sanguino/pins_MELZI.h index cfd859f2b621..bafaf610bd46 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI.h +++ b/Marlin/src/pins/sanguino/pins_MELZI.h @@ -23,14 +23,18 @@ /** * Melzi pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Melzi/schematic.pdf + * Origin: https://github.com/mosfet/melzi/blob/master/melzi.sch */ #ifndef BOARD_INFO_NAME #define BOARD_INFO_NAME "Melzi" #endif +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #ifndef FAN_PIN - #define FAN_PIN 4 + #define FAN_PIN PinB4 #endif // Alter timing for graphical display diff --git a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h index ab63b9cca0f2..5d30183fccdc 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_CREALITY.h @@ -23,6 +23,8 @@ /** * Melzi (Creality) pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Melzi%20(Creality)/CR-10%20Schematic.pdf + * Origin: https://github.com/Creality3DPrinting/CR10-Melzi-1.1.2/blob/master/Circuit%20diagram/Motherboard/CR-10%20Schematic.pdf * ATmega1284P * * The Creality board needs a bootloader installed before Marlin can be uploaded. @@ -36,6 +38,8 @@ #define BOARD_INFO_NAME "Melzi (Creality)" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // Alter timing for graphical display #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 125 diff --git a/Marlin/src/pins/sanguino/pins_MELZI_V2.h b/Marlin/src/pins/sanguino/pins_MELZI_V2.h index e49eb57b1137..1ded67b45288 100644 --- a/Marlin/src/pins/sanguino/pins_MELZI_V2.h +++ b/Marlin/src/pins/sanguino/pins_MELZI_V2.h @@ -23,10 +23,14 @@ /** * Melzi V2.0 as found at https://www.reprap.org/wiki/Melzi + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Melzi%20V2/Melzi-circuit.png + * Origin: https://www.reprap.org/mediawiki/images/7/7d/Melzi-circuit.png */ #define BOARD_INFO_NAME "Melzi V2" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // Alter timing for graphical display #if IS_U8GLIB_ST7920 #define BOARD_ST7920_DELAY_1 0 diff --git a/Marlin/src/pins/sanguino/pins_OMCA.h b/Marlin/src/pins/sanguino/pins_OMCA.h index d57d000334f9..a62d5def9696 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA.h +++ b/Marlin/src/pins/sanguino/pins_OMCA.h @@ -81,6 +81,9 @@ #define BOARD_INFO_NAME "Final OMCA" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_OMCA_A.h b/Marlin/src/pins/sanguino/pins_OMCA_A.h index 5799261534c8..67763d64aea0 100644 --- a/Marlin/src/pins/sanguino/pins_OMCA_A.h +++ b/Marlin/src/pins/sanguino/pins_OMCA_A.h @@ -79,6 +79,9 @@ #define BOARD_INFO_NAME "Alpha OMCA" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h index 64506af4c819..035416963f6d 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_11.h @@ -23,6 +23,16 @@ /** * Sanguinololu board pin assignments + * Schematic (0.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v0.1/schematic.png + * Origin (0.1): https://github.com/mosfet/Sanguinololu/blob/master/rev0.1/sanguinololu.sch + * Schematic (0.6): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v0.6/schematic.jpg + * Origin (0.6): https://github.com/mosfet/Sanguinololu/blob/master/rev0.6/images/schematic.jpg + * Schematic (0.7): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v0.7/schematic.jpg + * Origin (0.7): https://github.com/mosfet/Sanguinololu/blob/master/rev0.7/images/schematic.jpg + * Schematic (1.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v1.0/Sanguinololu-schematic.jpg + * Origin (1.0): https://reprap.org/wiki/File:Sanguinololu-schematic.jpg + * Schematic (1.1): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v1.1/schematic.png + * Origin (1.1): https://github.com/mosfet/Sanguinololu/blob/master/rev1.1/sanguinololu.sch */ /** @@ -57,6 +67,10 @@ #define BOARD_INFO_NAME "Sanguinololu <1.2" #endif +#ifndef AVR_CHIPOSCILLATOR_FREQ + #define AVR_CHIPOSCILLATOR_FREQ 16000000 +#endif + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h index 505f289964ca..b2dfcb9fbc33 100644 --- a/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h +++ b/Marlin/src/pins/sanguino/pins_SANGUINOLOLU_12.h @@ -23,6 +23,12 @@ /** * Sanguinololu V1.2 pin assignments + * Schematic (1.2): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v1.2/schematic.png + * Origin (1.2): https://github.com/mosfet/Sanguinololu/blob/master/rev1.2/sanguinololu.sch + * Schematic (1.3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v1.3/schematic.png + * Origin (1.3): https://github.com/mosfet/Sanguinololu/blob/master/rev1.3/sanguinololu.sch + * Schematic (1.3a): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Sanguinololu%20v1.3a/schematic.png + * Origin (1.3a): https://github.com/mosfet/Sanguinololu/blob/master/rev1.3a/sanguinololu.sch * * Applies to the following boards: * @@ -38,6 +44,8 @@ #define BOARD_INFO_NAME "Sanguinololu 1.2" #endif +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + #define HEATER_BED_PIN PinD4 // (bed) #define X_ENABLE_PIN PinD6 #define Y_ENABLE_PIN PinD6 diff --git a/Marlin/src/pins/sanguino/pins_SETHI.h b/Marlin/src/pins/sanguino/pins_SETHI.h index 14bd12311c07..b10197935ae0 100644 --- a/Marlin/src/pins/sanguino/pins_SETHI.h +++ b/Marlin/src/pins/sanguino/pins_SETHI.h @@ -58,6 +58,9 @@ #define GEN7_VERSION PinD4 // v1.x #endif +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/sanguino/pins_STB_11.h b/Marlin/src/pins/sanguino/pins_STB_11.h index ad0919e99e69..1bda25b3d4f7 100644 --- a/Marlin/src/pins/sanguino/pins_STB_11.h +++ b/Marlin/src/pins/sanguino/pins_STB_11.h @@ -22,7 +22,8 @@ #pragma once /** - * STB V1.1 pin assignments + * STB Electronics V1.1 pin assignments + * https://www.reprap.org/wiki/STB_Electronics */ #define BOARD_INFO_NAME "STB V1.1" diff --git a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h index 81039782312a..43385d3699a6 100644 --- a/Marlin/src/pins/sanguino/pins_ZMIB_V2.h +++ b/Marlin/src/pins/sanguino/pins_ZMIB_V2.h @@ -29,8 +29,12 @@ #define IS_ZMIB_V2 +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + /** * ZMIB pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/ZONESTAR%20ZMIB%20V2/ZMIB_V2_Schmatic.pdf + * Origin: https://github.com/ZONESTAR3D/Control-Board/blob/main/8bit/ZMIB/ZMIB%20V2/ZMIB_V2_Schmatic.pdf * * The ZMIB board needs a bootloader installed before Marlin can be uploaded. * If you don't have a chip programmer you can use a spare Arduino plus a few diff --git a/Marlin/src/pins/teensy2/pins_5DPRINT.h b/Marlin/src/pins/teensy2/pins_5DPRINT.h index 70f1de077cd2..bdefd5a65e0e 100644 --- a/Marlin/src/pins/teensy2/pins_5DPRINT.h +++ b/Marlin/src/pins/teensy2/pins_5DPRINT.h @@ -64,6 +64,8 @@ /** * 5DPrint D8 Driver board pin assignments + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/5DPrint%20D8/5DPD8_v1.0_OS_schematics.PDF + * Origin: https://bitbucket.org/makible/5dprint-d8-controller-board/src/master/5DPD8_v1.0_OS_schematics.PDF * * https://bitbucket.org/makible/5dprint-d8-controller-board */ @@ -73,6 +75,9 @@ #define DEFAULT_MACHINE_NAME "Makibox" #define BOARD_INFO_NAME "5DPrint D8" +// Just a wild guess because schematic does not say! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h index 6c1ab0308dd9..b1a98cc0b91f 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE.h @@ -23,9 +23,13 @@ /** * Brainwave 1.0 pin assignments (AT90USB646) + * https://www.reprap.org/wiki/Brainwave * * Requires hardware bundle for Arduino: * https://github.com/unrepentantgeek/brainwave-arduino + * + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Brainwave/schematic.pdf + * Origin: https://github.com/unrepentantgeek/Brainwave/blob/master/brainwave/brainwave.sch */ /** @@ -74,6 +78,8 @@ #define BOARD_INFO_NAME "Brainwave" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h index 46fff4984d30..53b2d79c9cd7 100644 --- a/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h +++ b/Marlin/src/pins/teensy2/pins_BRAINWAVE_PRO.h @@ -26,6 +26,8 @@ * * Requires hardware bundle for Arduino: * https://github.com/unrepentantgeek/brainwave-arduino + * + * Not to be confused with the regular Brainwave controller (https://www.reprap.org/wiki/Brainwave) */ /** @@ -79,6 +81,9 @@ #define BOARD_INFO_NAME "Brainwave Pro" +// Just a wild guess because no schematics! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 4f3b1d07fcb1..ab096aa820a4 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -25,6 +25,15 @@ * Rev B 2 JUN 2017 * * Converted to Arduino pin numbering + * + * Schematic (RevA): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.A/schematic.png + * Origin (RevA): https://raw.githubusercontent.com/lwalkera/printrboard/revA/Printrboard.sch + * Schematic (RevB): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.B/schematic.png + * Origin (RevB): https://raw.githubusercontent.com/lwalkera/printrboard/revB/Printrboard.sch + * Schematic (RevC): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.C/schematic.png + * Origin (RevC): https://raw.githubusercontent.com/lwalkera/printrboard/revC/Printrboard.sch + * Schematic (RevD): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.D/schematic.png + * Origin (RevD): https://raw.githubusercontent.com/lwalkera/printrboard/RevD/Printrboard.sch */ /** @@ -69,6 +78,11 @@ // Disable JTAG pins so they can be used for the Extrudrboard #define DISABLE_JTAG +// Only for RevA. +//#define AVR_CHIPOSCILLATOR_FREQ 8000000 + +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h index f9ba526fd56c..afc8d4479428 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD_REVF.h @@ -25,6 +25,19 @@ * Rev B 2 JUN 2017 * * Converted to Arduino pin numbering + * + * Schematic (RevF): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F/schematic.png + * Origin (RevF): https://github.com/lwalkera/printrboard/raw/revF/Printrboard.sch + * Schematic (RevF2): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F2/schematic.png + * Origin (RevF2): https://raw.githubusercontent.com/lwalkera/printrboard/revF2/Printrboard.sch + * Schematic (RevF3): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F3/schematic.png + * Origin (RevF3): https://raw.githubusercontent.com/lwalkera/printrboard/revF3/Printrboard.sch + * Schematic (RevF4): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F4/schematic.png + * Origin (RevF4): https://raw.githubusercontent.com/lwalkera/printrboard/revF4/Printrboard.sch + * Schematic (RevF5): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F5/schematic.png + * Origin (RevF5): https://raw.githubusercontent.com/lwalkera/printrboard/revF5/Printrboard.sch + * Schematic (RevF6): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Printrboard%20Rev.F6/schematic.png + * Origin (RevF6): https://raw.githubusercontent.com/lwalkera/printrboard/revF6/Printrboard.sch */ /** @@ -71,6 +84,8 @@ #define BOARD_INFO_NAME "Printrboard Rev.F" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // Disable JTAG pins so EXP1 pins work correctly // (Its pins are used for the Extrudrboard and filament sensor, for example). #define DISABLE_JTAG diff --git a/Marlin/src/pins/teensy2/pins_SAV_MKI.h b/Marlin/src/pins/teensy2/pins_SAV_MKI.h index 8a4ea7903473..94f65034c6f4 100644 --- a/Marlin/src/pins/teensy2/pins_SAV_MKI.h +++ b/Marlin/src/pins/teensy2/pins_SAV_MKI.h @@ -25,6 +25,9 @@ * Rev B 2 JUN 2017 * * Converted to Arduino pin numbering + * + * Schematic: https://green-candy.osdn.jp/external/MarlinFW/board_schematics/SAV%20MkI/SAV_MK-I.pdf + * Origin: https://reprap.org/mediawiki/images/3/3c/SAV_MK-I.pdf */ /** @@ -68,6 +71,9 @@ #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME #define DEFAULT_SOURCE_CODE_URL "tinyurl.com/onru38b" +// Just a wild guess because schematic does not say! +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Servos // diff --git a/Marlin/src/pins/teensy2/pins_TEENSY2.h b/Marlin/src/pins/teensy2/pins_TEENSY2.h index 2589d1760028..e47d0a639daf 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSY2.h +++ b/Marlin/src/pins/teensy2/pins_TEENSY2.h @@ -109,8 +109,12 @@ #include "env_validate.h" +// https://reprap.org/wiki/Teensy_Breadboard #define BOARD_INFO_NAME "Teensy++2.0" +// Just a guess. +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switches // diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index 938a56eda10c..269bc7013ef7 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -24,6 +24,10 @@ * Rev C 2 JUN 2017 * * Converted to Arduino pin numbering + * + * Schematic (1.0): https://green-candy.osdn.jp/external/MarlinFW/board_schematics/Teensylu%20v1.0/schematic.png + * Origin (1.0): https://raw.githubusercontent.com/StephS/Teensylu/master/working/Teensylu-1.0.sch + * (*) Other versions are discouraged by creator. */ /** @@ -82,6 +86,8 @@ #define BOARD_INFO_NAME "Teensylu" +#define AVR_CHIPOSCILLATOR_FREQ 16000000 + // // Limit Switch definitions that match the SCHEMATIC // From 601547b221cb9a0a60a36c76e04436640dd79f92 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Dec 2022 15:08:18 -0600 Subject: [PATCH 44/83] sanity-check --- Marlin/src/inc/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index e8f390b5be20..f27e59fc29d7 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -656,6 +656,8 @@ #error "EXTRA_LIN_ADVANCE_K is now ADVANCE_K_EXTRA." #elif defined(POLAR_SEGMENTS_PER_SECOND) || defined(DELTA_SEGMENTS_PER_SECOND) || defined(SCARA_SEGMENTS_PER_SECOND) || defined(TPARA_SEGMENTS_PER_SECOND) #error "(POLAR|DELTA|SCARA|TPARA)_SEGMENTS_PER_SECOND is now DEFAULT_SEGMENTS_PER_SECOND." +#elif defined(TMC_SW_MOSI) || defined(TMC_SW_MISO) || defined(TMC_SW_SCK) + #error "TMC_SW_(MOSI|MISO|SCK) is now TMC_SPI_(MOSI|MISO|SCK)." #endif // L64xx stepper drivers have been removed From f2a95cdf368889544b2c3267219df32f9ad4a742 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Mon, 12 Dec 2022 22:51:28 +0100 Subject: [PATCH 45/83] - fixed a few bugs to the LPC175x/LPC176x HAL SPI that were introduced during code formatting on Dec 12, 18:12 - added missing board oscillator freq (forgot to commit it?) --- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 6 +++--- Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h | 3 +++ 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 8850a84c31d0..738814675e67 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -1359,7 +1359,7 @@ uint32_t _start_millis; #endif public: - void spi_monitored_loop() { + inline spi_monitored_loop() { #if defined(HALSPI_DO_LOOPBEEPS) && PIN_EXISTS(BEEPER) _start_millis = millis(); #endif @@ -1616,7 +1616,7 @@ bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); for (uint32_t n = 0; n < num_bytes; n++) { - uint32_t = revbytes ? (num_bytes - 1) - n : 0; + uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : 0; uint32_t bitidx = byte_idx * 8; spi_monitored_loop tnfw; @@ -1631,7 +1631,7 @@ } else if (_ssp_framesize == 2) { spi_monitored_loop tnfw; - while (!SSP.SR.TNF) { tnfw.update(3); /* wait for space om´n the TX FIFO */ } + while (!SSP.SR.TNF) { tnfw.update(3); /* wait for space on the TX FIFO */ } if (revbits) val = _flip_bits(val); diff --git a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h index ba39ce5907ed..428fdd798b78 100644 --- a/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h +++ b/Marlin/src/pins/lpc1768/pins_BIQU_B300_V1.0.h @@ -31,6 +31,9 @@ #define BOARD_INFO_NAME "BIQU Thunder B300 V1.0" #endif +// Just a wild guess because no schematics! +#define LPC_MAINOSCILLATOR_FREQ 12000000 + // // Limit Switches // From adbd7eb6fa695d669a5d318444c121405fdcbaf3 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Tue, 13 Dec 2022 01:20:03 +0100 Subject: [PATCH 46/83] - finalized the wiring of the MKS TinyBee V1.0 with MKS TS35-R V2.0 for my hardware partner --- Marlin/src/pins/esp32/pins_MKS_TINYBEE.h | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h index 01757b7ed366..9db21a200acc 100644 --- a/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h +++ b/Marlin/src/pins/esp32/pins_MKS_TINYBEE.h @@ -160,9 +160,6 @@ #if HAS_WIRED_LCD #define BEEPER_PIN EXP1_01_PIN - #define BTN_ENC EXP1_02_PIN - #define BTN_EN1 EXP2_03_PIN - #define BTN_EN2 EXP2_05_PIN #if ENABLED(MKS_TS35_V2_0) // The MKS TS35-R V2.0 is a SPI-bus driven screen whose logic signals @@ -170,6 +167,12 @@ // powered up to 5V we cannot use the EXP1 port for logic signals. // Thus we have to remap the pins onto the EXP1 connector, which is // a hassle. + // HOW TO WIRE: + // https://green-candy.osdn.jp/external/MarlinFW/support/MKS%20TinyBee/MKS%20TS35-R%20V2.0%20Wiring/wiring_howto.png + + #define BTN_ENC -1 + #define BTN_EN1 -1 + #define BTN_EN2 -1 // DISPLAY PINS. #define TFT_A0_PIN EXP1_02_PIN @@ -185,16 +188,19 @@ #define TOUCH_MOSI_PIN TFT_MOSI_PIN // SPI BUS CHIP-SELECT PINS. - #define TFT_CS_PIN EXP2_04_PIN + #define TFT_CS_PIN EXP2_03_PIN #define TOUCH_CS_PIN EXP2_05_PIN - #define TOUCH_INT_PIN EXP2_03_PIN + #define TOUCH_INT_PIN -1 //sacrificed for CS // Disable any LCD related PINs config #define LCD_PINS_ENABLE -1 #define LCD_PINS_RS -1 #else #define LCD_BACKLIGHT_PIN -1 + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN #if ENABLED(MKS_MINI_12864) // MKS MINI12864 and MKS LCD12864B; If using MKS LCD12864A (Need to remove RPK2 resistor) From 13a8a6730fb09de7dfa1d7e44900cbb48ddb9d7a Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Thu, 15 Dec 2022 02:07:56 +0100 Subject: [PATCH 47/83] - bugfixes for LPC1768 (I have been fighting the compiler, like a man) - grammar fix for SOFTWARE_SPI on LPC1768 - various stability adjustments for the heck of it (it is better to be safe than sorry!) - bugfix for DYNAMIC_VECTORTABLE exception handling on LPC1768 (vector table entry 7 does not contain default handler) --- Marlin/src/HAL/LPC1768/HAL.h | 6 - Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 307 +++++++++++------- Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp | 18 +- Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp | 23 +- .../shared/cpu_exception/exception_arm.cpp | 6 + 5 files changed, 218 insertions(+), 142 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 8d64ce69e48a..15d6a79d0776 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -238,19 +238,13 @@ class MarlinHAL { static void adc_enable(const pin_t pin) { // On some BTT SKR V1.4 boards the ADC peripheral could be faulty. // Disable it by setting that macro in your Configuration.h -#ifndef LPC_DISABLE_ADC FilteredADC::enable_channel(pin); -#endif } // Begin ADC sampling on the given pin. Called from Temperature::isr! static uint32_t adc_result; static void adc_start(const pin_t pin) { -#ifndef LPC_DISABLE_ADC adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits -#else - adc_result = 0; -#endif } // Is the ADC ready for reading? diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp index 738814675e67..782276256776 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp @@ -101,7 +101,7 @@ if (n < code-1) delay(200); } - delay(500); + delay(1000); OUT_WRITE(BEEPER_PIN, HIGH); delay(400); OUT_WRITE(BEEPER_PIN, LOW); @@ -114,8 +114,28 @@ return ( a < b ? a : b ); } + namespace LPCHelpers { + + // Helper. + template + struct no_volatile { + typedef T type; + }; + template + struct no_volatile : public no_volatile {}; + + template + inline typename no_volatile ::type& dwrite(T& v) { return (typename no_volatile ::type&)v; } + + template + inline void dwrite( volatile T& v, T& a ) { (T&)v = a; } + + } // namespace LPCHelpers + namespace MarlinLPC { + #define __LPC_DEFREG(tn, n, l) static volatile tn& n = *(tn*)l + // NXP UM10360 date: 20th of November, 2022 // There are pins for each "port" on the LPC1768. Do not be confused with other architectures @@ -347,25 +367,25 @@ }; static_assert(sizeof(pinmode9_reg_t) == 4, "invalid size of pinmode9_reg_t"); - static pinsel0_reg_t &PINSEL0 = *(pinsel0_reg_t*)0x4002C000; - static pinsel1_reg_t &PINSEL1 = *(pinsel1_reg_t*)0x4002C004; - static pinsel2_reg_t &PINSEL2 = *(pinsel2_reg_t*)0x4002C008; - static pinsel3_reg_t &PINSEL3 = *(pinsel3_reg_t*)0x4002C00C; - static pinsel4_reg_t &PINSEL4 = *(pinsel4_reg_t*)0x4002C010; - static pinsel7_reg_t &PINSEL7 = *(pinsel7_reg_t*)0x4002C01C; - //static pinsel8_reg_t &PINSEL8 = *(pinsel8_reg_t*)0x4002C020; - static pinsel9_reg_t &PINSEL9 = *(pinsel9_reg_t*)0x4002C024; - static pinsel10_reg_t &PINSEL10 = *(pinsel10_reg_t*)0x4002C028; - - static pinmode0_reg_t &PINMODE0 = *(pinmode0_reg_t*)0x4002C040; - static pinmode1_reg_t &PINMODE1 = *(pinmode1_reg_t*)0x4002C044; - static pinmode2_reg_t &PINMODE2 = *(pinmode2_reg_t*)0x4002C048; - static pinmode3_reg_t &PINMODE3 = *(pinmode3_reg_t*)0x4002C04C; - static pinmode4_reg_t &PINMODE4 = *(pinmode4_reg_t*)0x4002C050; - //static pinmode5_reg_t &PINMODE5 = *(pinmode5_reg_t*)0x4002C054; - //static pinmode6_reg_t &PINMODE6 = *(pinmode6_reg_t*)0x4002C058; - static pinmode7_reg_t &PINMODE7 = *(pinmode7_reg_t*)0x4002C05C; - static pinmode9_reg_t &PINMODE9 = *(pinmode9_reg_t*)0x4002C064; + __LPC_DEFREG(pinsel0_reg_t, PINSEL0, 0x4002C000); + __LPC_DEFREG(pinsel1_reg_t, PINSEL1, 0x4002C004); + __LPC_DEFREG(pinsel2_reg_t, PINSEL2, 0x4002C008); + __LPC_DEFREG(pinsel3_reg_t, PINSEL3, 0x4002C00C); + __LPC_DEFREG(pinsel4_reg_t, PINSEL4, 0x4002C010); + __LPC_DEFREG(pinsel7_reg_t, PINSEL7, 0x4002C01C); + //__LPC_DEFREG(pinsel8_reg_t, PINSEL8, 0x4002C020); + __LPC_DEFREG(pinsel9_reg_t, PINSEL9, 0x4002C024); + __LPC_DEFREG(pinsel10_reg_t, PINSEL10, 0x4002C028); + + __LPC_DEFREG(pinmode0_reg_t, PINMODE0, 0x4002C040); + __LPC_DEFREG(pinmode1_reg_t, PINMODE1, 0x4002C044); + __LPC_DEFREG(pinmode2_reg_t, PINMODE2, 0x4002C048); + __LPC_DEFREG(pinmode3_reg_t, PINMODE3, 0x4002C04C); + __LPC_DEFREG(pinmode4_reg_t, PINMODE4, 0x4002C050); + //__LPC_DEFREG(pinmode5_reg_t, PINMODE5, 0x4002C054); + //__LPC_DEFREG(pinmode6_reg_t, PINMODE6, 0x4002C058); + __LPC_DEFREG(pinmode7_reg_t, PINMODE7, 0x4002C05C); + __LPC_DEFREG(pinmode9_reg_t, PINMODE9, 0x4002C064); // Left out OD and I2C-specific. // UM10360 page 103: I am only taking the pin descriptions for LPC176x @@ -419,23 +439,23 @@ } }; - static fioXdir_reg_t &FIO0DIR = *(fioXdir_reg_t*)0x2009C000; - static fioXdir_reg_t &FIO1DIR = *(fioXdir_reg_t*)0x2009C020; - static fioXdir_reg_t &FIO2DIR = *(fioXdir_reg_t*)0x2009C040; - static fioXdir_reg_t &FIO3DIR = *(fioXdir_reg_t*)0x2009C060; - static fioXdir_reg_t &FIO4DIR = *(fioXdir_reg_t*)0x2009C080; + __LPC_DEFREG(fioXdir_reg_t, FIO0DIR, 0x2009C000); + __LPC_DEFREG(fioXdir_reg_t, FIO1DIR, 0x2009C020); + __LPC_DEFREG(fioXdir_reg_t, FIO2DIR, 0x2009C040); + __LPC_DEFREG(fioXdir_reg_t, FIO3DIR, 0x2009C060); + __LPC_DEFREG(fioXdir_reg_t, FIO4DIR, 0x2009C080); - static fioXmask_reg_t &FIO0MASK = *(fioXmask_reg_t*)0x2009C010; - static fioXmask_reg_t &FIO1MASK = *(fioXmask_reg_t*)0x2009C030; - static fioXmask_reg_t &FIO2MASK = *(fioXmask_reg_t*)0x2009C050; - static fioXmask_reg_t &FIO3MASK = *(fioXmask_reg_t*)0x2009C070; - static fioXmask_reg_t &FIO4MASK = *(fioXmask_reg_t*)0x2009C090; + __LPC_DEFREG(fioXmask_reg_t, FIO0MASK, 0x2009C010); + __LPC_DEFREG(fioXmask_reg_t, FIO1MASK, 0x2009C030); + __LPC_DEFREG(fioXmask_reg_t, FIO2MASK, 0x2009C050); + __LPC_DEFREG(fioXmask_reg_t, FIO3MASK, 0x2009C070); + __LPC_DEFREG(fioXmask_reg_t, FIO4MASK, 0x2009C090); - static fioXpin_reg_t &FIO0PIN = *(fioXpin_reg_t*)0x2009C014; - static fioXpin_reg_t &FIO1PIN = *(fioXpin_reg_t*)0x2009C034; - static fioXpin_reg_t &FIO2PIN = *(fioXpin_reg_t*)0x2009C054; - static fioXpin_reg_t &FIO3PIN = *(fioXpin_reg_t*)0x2009C074; - static fioXpin_reg_t &FIO4PIN = *(fioXpin_reg_t*)0x2009C094; + __LPC_DEFREG(fioXpin_reg_t, FIO0PIN, 0x2009C014); + __LPC_DEFREG(fioXpin_reg_t, FIO1PIN, 0x2009C034); + __LPC_DEFREG(fioXpin_reg_t, FIO2PIN, 0x2009C054); + __LPC_DEFREG(fioXpin_reg_t, FIO3PIN, 0x2009C074); + __LPC_DEFREG(fioXpin_reg_t, FIO4PIN, 0x2009C094); #endif @@ -677,7 +697,7 @@ }; static_assert(sizeof(scs_reg_t) == 4, "invalid size of LPC scs_reg_t"); - static scs_reg_t &SCS = *(scs_reg_t*)0x400FC1A0; + __LPC_DEFREG(scs_reg_t, SCS, 0x400FC1A0); #define LPC_CLKSRC_IRC 0 // 4MHz #define LPC_CLKSRC_MAINOSC 1 // depending on OSCRANGE @@ -689,7 +709,7 @@ }; static_assert(sizeof(clksrcsel_reg_t) == 4, "invalid size of LPC clksrcsel_reg_t"); - static clksrcsel_reg_t &CLKSRCSEL = *(clksrcsel_reg_t*)0x400FC10C; + __LPC_DEFREG(clksrcsel_reg_t, CLKSRCSEL, 0x400FC10C); struct pll0stat_reg_t { uint32_t MSEL0 : 15; // M - 1 @@ -702,7 +722,7 @@ }; static_assert(sizeof(pll0stat_reg_t) == 4, "invalid size of LPC pll0stat_reg_t"); - static pll0stat_reg_t &PLL0STAT = *(pll0stat_reg_t*)0x400FC088; + __LPC_DEFREG(pll0stat_reg_t, PLL0STAT, 0x400FC088); struct cclkcfg_reg_t { uint32_t CCLKSEL : 8; @@ -710,7 +730,7 @@ }; static_assert(sizeof(cclkcfg_reg_t) == 4, "invalid size of LPC cclkcfg_reg_t"); - static cclkcfg_reg_t &CCLKCFG = *(cclkcfg_reg_t*)0x400FC104; + __LPC_DEFREG(cclkcfg_reg_t, CCLKCFG, 0x400FC104); #define LPC_PCLKSEL_QUARTER 0 #define LPC_PCLKSEL_ONE 1 @@ -737,7 +757,7 @@ }; static_assert(sizeof(pclksel0_reg_t) == 4, "invalid size of LPC pclksel0_reg_t"); - static pclksel0_reg_t &PCLKSEL0 = *(pclksel0_reg_t*)0x400FC1A8; + __LPC_DEFREG(pclksel0_reg_t, PCLKSEL0, 0x400FC1A8); struct pclksel1_reg_t { uint32_t PCLK_QEI : 2; @@ -759,7 +779,7 @@ }; static_assert(sizeof(pclksel1_reg_t) == 4, "invalid size of LPC pclksel1_reg_t"); - static pclksel1_reg_t &PCLKSEL1 = *(pclksel1_reg_t*)0x400FC1AC; + __LPC_DEFREG(pclksel1_reg_t, PCLKSEL1, 0x400FC1AC); // Enables or disables peripherals (power control for peripherals). struct pconp_reg_t { @@ -798,7 +818,7 @@ }; static_assert(sizeof(pconp_reg_t) == 4, "invalid size of LPC pconp_reg_t"); - static pconp_reg_t &PCONP = *(pconp_reg_t*)0x400FC0C4; + __LPC_DEFREG(pconp_reg_t, PCONP, 0x400FC0C4); static uint32_t GetCPUClockFrequency() { if (!PLL0STAT.PLLE0_STAT || !PLL0STAT.PLLC0_STAT) { @@ -1003,8 +1023,8 @@ }; static_assert(sizeof(ssp_dev_t) == 40, "invalid size of LPC ssp_dev_t"); - static volatile ssp_dev_t &SSP0 = *(volatile ssp_dev_t*)0x40088000; - static volatile ssp_dev_t &SSP1 = *(volatile ssp_dev_t*)0x40030000; + __LPC_DEFREG(ssp_dev_t, SSP0, 0x40088000); + __LPC_DEFREG(ssp_dev_t, SSP1, 0x40030000); inline volatile ssp_dev_t &SPIGetBusFromIndex(uint8_t idx) { if (idx == 0) return SSP0; @@ -1026,7 +1046,7 @@ }; static_assert(sizeof(DMACIntStat_reg_t) == 4, "invalid size of LPC DMACIntStat_reg_t"); - static DMACIntStat_reg_t &DMACIntStat = *(DMACIntStat_reg_t*)0x50004000; + __LPC_DEFREG(DMACIntStat_reg_t, DMACIntStat, 0x50004000); struct DMACIntTCStat_reg_t { uint32_t IntTCStat : 8; @@ -1034,15 +1054,15 @@ }; static_assert(sizeof(DMACIntTCStat_reg_t) == 4, "invalid size of LPC DMACIntTCStat_reg_t"); - static DMACIntTCStat_reg_t &DMACIntTCStat = *(DMACIntTCStat_reg_t*)0x50004004; + __LPC_DEFREG(DMACIntTCStat_reg_t, DMACIntTCStat, 0x50004004); struct DMACIntTCClear_reg_t { uint32_t IntTCClear : 8; uint32_t reserved1 : 24; }; - static_assert(sizeof(DMACIntTCClear_reg_t) == 4, "invalid size of LPC DMAIntTCClear_reg_t"); + static_assert(sizeof(DMACIntTCClear_reg_t) == 4, "invalid size of LPC DMACIntTCClear_reg_t"); - static DMACIntTCClear_reg_t &DMACIntTCClear = *(DMACIntTCClear_reg_t*)0x50004008; + __LPC_DEFREG(DMACIntTCClear_reg_t, DMACIntTCClear, 0x50004008); struct DMACIntErrStat_reg_t { uint32_t IntErrStat : 8; @@ -1050,7 +1070,7 @@ }; static_assert(sizeof(DMACIntErrStat_reg_t) == 4, "invalid size of LPC DMACIntErrStat_reg_t"); - static DMACIntErrStat_reg_t &DMACIntErrStat = *(DMACIntErrStat_reg_t*)0x5000400C; + __LPC_DEFREG(DMACIntErrStat_reg_t, DMACIntErrStat, 0x5000400C); struct DMACIntErrClr_reg_t { uint32_t IntErrClr : 8; @@ -1058,7 +1078,7 @@ }; static_assert(sizeof(DMACIntErrClr_reg_t) == 4, "invalid size of LPC DMACIntErrClr_reg_t"); - static DMACIntErrClr_reg_t &DMACIntErrClr = *(DMACIntErrClr_reg_t*)0x50004010; + __LPC_DEFREG(DMACIntErrClr_reg_t, DMACIntErrClr, 0x50004010); struct DMACRawIntTCStat_reg_t { uint32_t RawIntTCStat : 8; @@ -1066,7 +1086,7 @@ }; static_assert(sizeof(DMACRawIntTCStat_reg_t) == 4, "invalid size of LPC DMACRawIntTCStat_reg_t"); - static DMACRawIntTCStat_reg_t &DMACRawIntTCStat = *(DMACRawIntTCStat_reg_t*)0x50004014; + __LPC_DEFREG(DMACRawIntTCStat_reg_t, DMACRawIntTCStat, 0x50004014); struct DMACRawIntErrStat_reg_t { uint32_t RawIntErrStat : 8; @@ -1074,7 +1094,7 @@ }; static_assert(sizeof(DMACRawIntErrStat_reg_t) == 4, "invalid size of LPC DMACRawIntErrStat_reg_t"); - static DMACRawIntErrStat_reg_t &DMACRawIntErrStat = *(DMACRawIntErrStat_reg_t*)0x50004018; + __LPC_DEFREG(DMACRawIntErrStat_reg_t, DMACRawIntErrStat, 0x50004018); struct DMACEnbldChns_reg_t { uint32_t EnabledChannels : 8; @@ -1082,7 +1102,7 @@ }; static_assert(sizeof(DMACEnbldChns_reg_t) == 4, "invalid size of LPC DMACEnbldChns_reg_t"); - static DMACEnbldChns_reg_t &DMACEnbldChns = *(DMACEnbldChns_reg_t*)0x5000401C; + __LPC_DEFREG(DMACEnbldChns_reg_t, DMACEnbldChns, 0x5000401C); struct DMACSoftBReq_reg_t { uint32_t SoftBReq : 16; @@ -1090,7 +1110,7 @@ }; static_assert(sizeof(DMACSoftBReq_reg_t) == 4, "invalid size of LPC DMACSoftBReq_reg_t"); - static DMACSoftBReq_reg_t &DMACSoftBReq = *(DMACSoftBReq_reg_t*)0x50004020; + __LPC_DEFREG(DMACSoftBReq_reg_t, DMACSoftBReq, 0x50004020); struct DMACSoftSReq_reg_t { uint32_t SoftSReq : 16; @@ -1098,7 +1118,7 @@ }; static_assert(sizeof(DMACSoftSReq_reg_t) == 4, "invalid size of LPC DMACSoftSReq_reg_t"); - static DMACSoftSReq_reg_t &DMACSoftSReq = *(DMACSoftSReq_reg_t*)0x50004024; + __LPC_DEFREG(DMACSoftSReq_reg_t, DMACSoftSReq, 0x50004024); struct DMACSoftLBReq_reg_t { uint32_t SoftLBReq : 16; @@ -1106,7 +1126,7 @@ }; static_assert(sizeof(DMACSoftLBReq_reg_t) == 4, "invalid size of LPC DMACSoftLBReq_reg_t"); - static DMACSoftLBReq_reg_t &DMACSoftLBReq = *(DMACSoftLBReq_reg_t*)0x50004028; + __LPC_DEFREG(DMACSoftLBReq_reg_t, DMACSoftLBReq, 0x50004028); struct DMACSoftLSReq_reg_t { uint32_t SoftLSReq : 16; @@ -1114,7 +1134,7 @@ }; static_assert(sizeof(DMACSoftLSReq_reg_t) == 4, "invalid size of LPC DMACSoftLSReq_reg_t"); - static DMACSoftLSReq_reg_t &DMACSoftLSReq = *(DMACSoftLSReq_reg_t*)0x5000402C; + __LPC_DEFREG(DMACSoftLSReq_reg_t, DMACSoftLSReq, 0x5000402C); struct DMACConfig_reg_t { uint32_t E : 1; @@ -1123,7 +1143,7 @@ }; static_assert(sizeof(DMACConfig_reg_t) == 4, "invalid size of LPC DMACConfig_reg_t"); - static DMACConfig_reg_t &DMACConfig = *(DMACConfig_reg_t*)0x50004030; + __LPC_DEFREG(DMACConfig_reg_t, DMACConfig, 0x50004030); struct DMACSync_reg_t { uint32_t DMACSync : 16; @@ -1131,7 +1151,7 @@ }; static_assert(sizeof(DMACSync_reg_t) == 4, "invalid size of LPC DMACSync_reg_t"); - static DMACSync_reg_t &DMACSync = *(DMACSync_reg_t*)0x50004034; + __LPC_DEFREG(DMACSync_reg_t, DMACSync, 0x50004034); struct DMAReqSel_reg_t { uint32_t DMASEL08 : 1; @@ -1146,7 +1166,7 @@ }; static_assert(sizeof(DMAReqSel_reg_t) == 4, "invalid size of LPC DMAReqSel_reg_t"); - static DMAReqSel_reg_t &DMAReqSel = *(DMAReqSel_reg_t*)0x400FC1C4; + __LPC_DEFREG(DMAReqSel_reg_t, DMAReqSel, 0x400FC1C4); struct DMACCxLLI_reg_t { uint32_t reserved1 : 2; @@ -1193,16 +1213,16 @@ }; static_assert(sizeof(DMACChannel_dev_t) == 20, "invalid size of LPC DMACChannel_dev_t"); - static DMACChannel_dev_t &DMACC0 = *(DMACChannel_dev_t*)0x50004100; - static DMACChannel_dev_t &DMACC1 = *(DMACChannel_dev_t*)0x50004120; - static DMACChannel_dev_t &DMACC2 = *(DMACChannel_dev_t*)0x50004140; - static DMACChannel_dev_t &DMACC3 = *(DMACChannel_dev_t*)0x50004160; - static DMACChannel_dev_t &DMACC4 = *(DMACChannel_dev_t*)0x50004180; - static DMACChannel_dev_t &DMACC5 = *(DMACChannel_dev_t*)0x500041A0; - static DMACChannel_dev_t &DMACC6 = *(DMACChannel_dev_t*)0x500041C0; - static DMACChannel_dev_t &DMACC7 = *(DMACChannel_dev_t*)0x500041E0; + __LPC_DEFREG(DMACChannel_dev_t, DMACC0, 0x50004100); + __LPC_DEFREG(DMACChannel_dev_t, DMACC1, 0x50004120); + __LPC_DEFREG(DMACChannel_dev_t, DMACC2, 0x50004140); + __LPC_DEFREG(DMACChannel_dev_t, DMACC3, 0x50004160); + __LPC_DEFREG(DMACChannel_dev_t, DMACC4, 0x50004180); + __LPC_DEFREG(DMACChannel_dev_t, DMACC5, 0x500041A0); + __LPC_DEFREG(DMACChannel_dev_t, DMACC6, 0x500041C0); + __LPC_DEFREG(DMACChannel_dev_t, DMACC7, 0x500041E0); - static DMACChannel_dev_t& DMAGetChannel(const uint32_t idx) { + static volatile DMACChannel_dev_t& DMAGetChannel(const uint32_t idx) { switch (idx) { case 0: return DMACC0; case 1: return DMACC1; @@ -1233,7 +1253,7 @@ struct DMACCxLLI_desc_t { uint32_t SrcAddr; uint32_t DestAddr; - DMACCxLLI_desc_t *Next; + volatile DMACCxLLI_desc_t *Next; DMACCxControl_reg_t Control; }; static_assert(sizeof(DMACCxLLI_desc_t) == 16, "invalid size of LPC DMACCxLLI_desc_t"); @@ -1247,31 +1267,34 @@ #define HALSPI_LPC_STATIC_DMADESCS 3 #endif - static DMACCxLLI_desc_user_t _available_dma_descs[HALSPI_LPC_STATIC_DMADESCS]; + static volatile DMACCxLLI_desc_user_t _available_dma_descs[HALSPI_LPC_STATIC_DMADESCS]; - static DMACCxLLI_desc_user_t* DMAFindFreeChainLLI() { + static volatile DMACCxLLI_desc_user_t* DMAFindFreeChainLLI() { for (auto &item : _available_dma_descs) if (item.available) return &item; return nullptr; } struct dma_process_t { - DMACChannel_dev_t *current_DMACC; + volatile DMACChannel_dev_t *current_DMACC; const void *current_buffer; size_t curoff; size_t txlen; uint8_t txunitsize; void (*completeCallback)(void*); void *complete_ud; - DMACCxLLI_desc_user_t *last_chain; + volatile DMACCxLLI_desc_user_t *last_chain; bool is_active = false; }; - static dma_process_t _dma_async_proc; + static volatile dma_process_t _dma_async_proc; - static void DMAProgramSSPChain(volatile ssp_dev_t &SSP, dma_process_t &proc) { - DMACCxLLI_desc_user_t *first = nullptr; - DMACCxLLI_desc_user_t *last = nullptr; + static void DMAProgramSSPChain(volatile ssp_dev_t &SSP, volatile dma_process_t &proc) { + // Martin says: Don't mess with this function, or else the compiler might generate wrong code. ;) + // The fight of priorities! Volatile versus whatever! The climax of the century! + // Don't worry! You will lose sleep when fighting compiler bugs! Promised! + volatile DMACCxLLI_desc_user_t *first = nullptr; + volatile DMACCxLLI_desc_user_t *last = nullptr; uint32_t txwidth = 0; @@ -1281,15 +1304,16 @@ else _spi_on_error(4); DMACCxControl_reg_t Control; - Control.SBSize = 0; - Control.DBSize = 0; + Control.SBSize = 1; // 4 bytes + Control.DBSize = 1; // 4 bytes Control.SWidth = txwidth; Control.DWidth = txwidth; + Control.reserved1 = 0; Control.SI = true; Control.DI = false; - Control.Prot1 = 1; + Control.Prot1 = 0; Control.Prot2 = 0; - Control.Prot3 = 1; + Control.Prot3 = 0; Control.I = false; bool init_ch_prog = false; @@ -1297,6 +1321,8 @@ auto &DMACC = *proc.current_DMACC; DMACC.Config.ITC = true; + DMACCxControl_reg_t ChannelControl; + while (proc.curoff < proc.txlen) { size_t left = (proc.txlen - proc.curoff); size_t takecnt = (uint32_t)__MIN (left, (1<<12)-1); @@ -1311,7 +1337,7 @@ DMACC.SrcAddr = SrcAddr; DMACC.DestAddr = DestAddr; DMACC.LLI.LLI = 0; - DMACC.Control = Control; + ChannelControl = Control; init_ch_prog = true; } else { @@ -1321,8 +1347,7 @@ freelli->SrcAddr = SrcAddr; freelli->DestAddr = DestAddr; - freelli->Next = nullptr; - freelli->Control = Control; + LPCHelpers::dwrite(freelli->Control, Control); freelli->available = false; if (first == nullptr) { @@ -1337,8 +1362,13 @@ proc.curoff += takecnt; } - if (last) last->Control.I = true; - else DMACC.Control.I = true; + if (last) { + last->Control.I = true; + last->Next = nullptr; + } + else ChannelControl.I = true; + + LPCHelpers::dwrite(DMACC.Control) = ChannelControl; proc.last_chain = first; } @@ -1412,9 +1442,11 @@ static void _spiAsyncBarrier() { #ifdef HAL_SPI_SUPPORTS_ASYNC - while (_ssp_async_proc.is_active) { /* wait for any async SPI TX to finish */ } + spi_monitored_loop asyncspiw; + while (_ssp_async_proc.is_active) { asyncspiw.update(10); /* wait for any async SPI TX to finish */ } #ifndef HALSPI_DISABLE_DMA - while (MarlinLPC::_dma_async_proc.is_active) { /* wait for any async DMA TX to finish */ } + spi_monitored_loop asyncdmaw; + while (MarlinLPC::_dma_async_proc.is_active) { asyncdmaw.update(11); /* wait for any async DMA TX to finish */ } #endif #endif } @@ -1457,7 +1489,8 @@ void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi, int hint_cs) { #ifdef HAL_SPI_SUPPORTS_ASYNC - while (_ssp_is_active) { /* wait for any other SPI activity to finish */ } + spi_monitored_loop initw; + while (_ssp_is_active) { initw.update(13); /* wait for any other SPI activity to finish */ } #else if (_ssp_is_active) _spi_on_error(1); #endif @@ -1611,12 +1644,12 @@ bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); if (_ssp_framesize == 1) { // Push it byte-by-byte (DSS = 7). - uint32_t num_bytes = sizeof(numberType); + const uint32_t num_bytes = sizeof(numberType); bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); for (uint32_t n = 0; n < num_bytes; n++) { - uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : 0; + uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : n; uint32_t bitidx = byte_idx * 8; spi_monitored_loop tnfw; @@ -1693,16 +1726,16 @@ template inline numberType _spi_fetch_from_queue(volatile MarlinLPC::ssp_dev_t &SSP) { numberType result = 0; - bool revbits = (_ssp_bitOrder == SPI_BITORDER_MSB); + bool revbits = (_ssp_bitOrder == SPI_BITORDER_LSB); if (_ssp_framesize == 1) { // Fetch it byte-by-byte (DSS = 7). - uint32_t num_bytes = sizeof(numberType); + const uint32_t num_bytes = sizeof(numberType); - bool revbytes = (_ssp_bitOrder == SPI_BITORDER_LSB); + bool revbytes = (_ssp_bitOrder == SPI_BITORDER_MSB); for (uint32_t n = 0; n < num_bytes; n++) { - uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : 0; + uint32_t byte_idx = revbytes ? (num_bytes - 1) - n : n; uint32_t bitidx = byte_idx * 8; spi_monitored_loop rnew; @@ -1821,11 +1854,11 @@ MarlinLPC::PCONP.PCGPDMA = false; } - static void _dmacInitSSP(MarlinLPC::DMACChannel_dev_t &DMACC, uint8_t sspBusIdx) { + static void _dmacInitSSP(volatile MarlinLPC::DMACChannel_dev_t &DMACC, uint8_t sspBusIdx) { if (sspBusIdx == 0) - DMACC.Config.DestPeripheral = 0; + DMACC.Config.DestPeripheral = 0; // SSP0 TX else if (sspBusIdx == 1) - DMACC.Config.DestPeripheral = 2; + DMACC.Config.DestPeripheral = 2; // SSP1 TX DMACC.Config.TransferType = 1; // memory to peripheral DMACC.Config.IE = false; DMACC.Config.ITC = false; @@ -1849,7 +1882,11 @@ DMACC.LLI.LLI = 0; _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); - size_t curoff = 0; + // Enable DMA on the SSP. + SSP.DMACR.TXDMAE = true; + SSP.DMACR.RXDMAE = false; + + uint32_t curoff = 0; while (curoff < cnt) { uint32_t left = (cnt - curoff); @@ -1857,28 +1894,32 @@ MarlinLPC::DMACCxControl_reg_t Control; Control.TransferSize = takecnt; - Control.SBSize = 0; - Control.DBSize = 0; + Control.SBSize = 1; // 4 bytes + Control.DBSize = 1; // 4 bytes Control.SWidth = txwidth; Control.DWidth = txwidth; Control.reserved1 = 0; Control.SI = true; Control.DI = false; - Control.Prot1 = 1; + Control.Prot1 = 0; Control.Prot2 = 0; Control.Prot3 = 0; Control.I = false; DMACC.SrcAddr = (uint32_t)( buf + curoff ); - DMACC.Control = Control; + LPCHelpers::dwrite(DMACC.Control) = Control; curoff += takecnt; // Kick off the DMA. DMACC.Config.E = true; - while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + spi_monitored_loop syncdmaw; + while (DMACC.Config.E) { syncdmaw.update(11); /* wait for the DMA TX to finish */ } } + // Disable DMA on the SSP. + SSP.DMACR.TXDMAE = false; + _ssp_dirty_rxbuffer = true; } @@ -1899,6 +1940,10 @@ DMACC.LLI.LLI = 0; _dmacInitSSP(DMACC, _ssp_gpioMap.sspBusIdx); + // Enable DMA on the SSP. + SSP.DMACR.TXDMAE = true; + SSP.DMACR.RXDMAE = false; + size_t curoff = 0; while (curoff < repcnt) { @@ -1907,27 +1952,31 @@ MarlinLPC::DMACCxControl_reg_t Control; Control.TransferSize = takecnt; - Control.SBSize = 0; - Control.DBSize = 0; + Control.SBSize = 1; // 4 bytes + Control.DBSize = 1; // 4 bytes Control.SWidth = txwidth; Control.DWidth = txwidth; Control.reserved1 = 0; Control.SI = false; Control.DI = false; - Control.Prot1 = 1; + Control.Prot1 = 0; Control.Prot2 = 0; Control.Prot3 = 0; Control.I = false; - DMACC.Control = Control; + LPCHelpers::dwrite(DMACC.Control) = Control; curoff += takecnt; // Kick off the DMA. DMACC.Config.E = true; - while (DMACC.Config.E) { /* wait for the DMA TX to finish */ } + spi_monitored_loop syncdmaw; + while (DMACC.Config.E) { syncdmaw.update(12); /* wait for the DMA TX to finish */ } } + // Disable DMA on the SSP. + SSP.DMACR.TXDMAE = false; + _ssp_dirty_rxbuffer = true; } @@ -2047,21 +2096,26 @@ static void _dmaUninstallInterrupt(); - static void _dmacAdvance(MarlinLPC::dma_process_t &proc) { + static void _dmacAdvance(volatile MarlinLPC::dma_process_t &proc) { // If there is any last chain that was used then clear it. if (auto *last_chain = proc.last_chain) { - MarlinLPC::DMACCxLLI_desc_user_t *iter = last_chain; + volatile MarlinLPC::DMACCxLLI_desc_user_t *iter = last_chain; while (iter) { iter->available = true; - iter = (MarlinLPC::DMACCxLLI_desc_user_t*)iter->Next; + iter = (volatile MarlinLPC::DMACCxLLI_desc_user_t*)iter->Next; } proc.last_chain = nullptr; } auto &DMACC = *proc.current_DMACC; + auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); + if (proc.curoff == proc.txlen) { + // Disable the SSP DMA TX. + SSP.DMACR.TXDMAE = false; + // Disable the terminal count interrupt. DMACC.Control.I = false; DMACC.Config.ITC = false; @@ -2082,21 +2136,21 @@ proc.complete_ud = nullptr; proc.is_active = false; + _ssp_dirty_rxbuffer = true; + if (completeCallback) { completeCallback(complete_ud); } return; } - auto &SSP = MarlinLPC::SPIGetBusFromIndex(_ssp_gpioMap.sspBusIdx); - MarlinLPC::DMAProgramSSPChain(SSP, proc); // Kick-off another async TX. DMACC.Config.E = true; } - static void _dma_interrupt() { + static void __attribute__((interrupt)) _dma_interrupt() { for (uint8_t n = 0; n < 8; n++) { uint32_t chmask = (1< (); } - static void _spi_interrupt_sspbus1() { + static void __attribute__((interrupt)) _spi_interrupt_sspbus1() { _spi_interrupt <1> (); } @@ -2423,7 +2485,8 @@ auto &DMACC = *proc.current_DMACC; DMACC.Config.H = true; - while (DMACC.Config.A) { /* wait until the DMA channel has no more data to process */ } + spi_monitored_loop abw; + while (DMACC.Config.A) { abw.update(9); /* wait until the DMA channel has no more data to process */ } DMACC.Config.E = false; DMACC.Config.ITC = false; diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp index c475cb8cff6f..17a0a109c957 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI_SW.cpp @@ -140,17 +140,27 @@ OUT_WRITE(BEEPER_PIN, LOW); delay(500); OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(200); + OUT_WRITE(BEEPER_PIN, HIGH); delay(300); OUT_WRITE(BEEPER_PIN, LOW); - delay(1500); + delay(300); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(200); + OUT_WRITE(BEEPER_PIN, LOW); + delay(500); + OUT_WRITE(BEEPER_PIN, HIGH); + delay(1000); + OUT_WRITE(BEEPER_PIN, LOW); + delay(2000); #endif } } } - void spiEstablish() { - _maybe_start_transaction(); - } + void spiEstablish() { /* do nothing */ } uint8_t spiRec(uint8_t txval) { return (_spi_bit_order == SPI_BITORDER_MSB) ? spiTransfer(txval) : _flip_bits_8(spiTransfer(_flip_bits_8(txval))); } diff --git a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp index 6dc0eb164fc1..6a2676b5a376 100644 --- a/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp +++ b/Marlin/src/HAL/shared/ARM/HAL_NVIC.cpp @@ -32,7 +32,7 @@ // Defined by GCC. // The vector is located in flash memory, thus there may be no memory bus for write access // wired into the CPU (hard fault at attempt). - extern void (*const g_pfnVectors[VECTOR_TABLE_SIZE])(); + extern void (*volatile const g_pfnVectors[VECTOR_TABLE_SIZE])(); #define _NVIC_HAS_DEFAULT_VECTOR #elif defined(STM32F4xx) // There are a few less entries specifically for "STM32F405xx/07xx and STM32F415xx/17xx" but w/e. @@ -41,7 +41,7 @@ // Defined by GCC. // The vector is located in flash memory, thus there may be no memory bus for write access // wired into the CPU (hard fault at attempt). - extern void (*const g_pfnVectors[VECTOR_TABLE_SIZE])(); + extern void (*volatile const g_pfnVectors[VECTOR_TABLE_SIZE])(); #define _NVIC_HAS_DEFAULT_VECTOR #elif defined(TARGET_LPC1768) // See NXP UM10360 page 75ff @@ -53,7 +53,7 @@ #define IRQ_START_IDX 16 // The interrupt table used by installment. -alignas(IRQ_VECTOR_ALIGNMENT) static void (*_isrv_redirect[VECTOR_TABLE_SIZE])(); +alignas(IRQ_VECTOR_ALIGNMENT) static void (*volatile _isrv_redirect[VECTOR_TABLE_SIZE])(); // From the ARM Cortex M3 reference manual. struct vtor_reg_t { @@ -63,7 +63,7 @@ struct vtor_reg_t { }; // For debugging ;) -static bool _NVIC_IsVectorInCorrectAddressSpace(const void *vectaddr) { +static bool _NVIC_IsVectorInCorrectAddressSpace(const volatile void *vectaddr) { uint32_t valaddr = (uint32_t)vectaddr; return (valaddr >= (1<<9) && valaddr < (1<<30)); } @@ -91,19 +91,19 @@ static void _NVIC_OnError() { } } -static vtor_reg_t& _SCB_VTOR = *(vtor_reg_t*)0xE000ED08; +static volatile vtor_reg_t& _SCB_VTOR = *(vtor_reg_t*)0xE000ED08; static unsigned int _vtor_refcount = 0; -static void (*const* _NVIC_GetCurrentVector())() { +static void (*const volatile* _NVIC_GetCurrentVector())() { return (void (*const*)())( _SCB_VTOR.TBLOFF << 9 ); } #ifndef _NVIC_HAS_DEFAULT_VECTOR -static void (*const*_nvic_default_vector)() = nullptr; +static void (*const volatile*_nvic_default_vector)() = nullptr; #endif -static void (*const*_NVIC_GetDefaultVector())() { +static void (*const volatile*_NVIC_GetDefaultVector())() { #ifdef STM32F1xx return g_pfnVectors; #else @@ -112,7 +112,7 @@ static void (*const*_NVIC_GetDefaultVector())() { } static void _nvicFetchVectorEntriesFromDefault() { - memcpy(_isrv_redirect, _NVIC_GetDefaultVector(), sizeof(void*)*VECTOR_TABLE_SIZE); + memcpy((void*)_isrv_redirect, (const void*)_NVIC_GetDefaultVector(), sizeof(void*)*VECTOR_TABLE_SIZE); } void nvicBegin() { @@ -130,7 +130,7 @@ void nvicResetVector() { void nvicUpdateVector() { if (_vtor_refcount == 0) { - memcpy(_isrv_redirect, (const void*)_NVIC_GetCurrentVector(), sizeof(_isrv_redirect)); + memcpy((void*)_isrv_redirect, (const void*)_NVIC_GetCurrentVector(), sizeof(_isrv_redirect)); } } @@ -140,6 +140,7 @@ void nvicSetHandler(uint32_t idx, void (*callback)()) { _isrv_redirect[idx] = callback; __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) + __ISB(); } void nvicSetIRQHandler(IRQn_Type irqn, void (*callback)()) { @@ -174,6 +175,7 @@ void nvicInstallRedirect() { { _SCB_VTOR.TBLOFF = ( (uint32_t)&_isrv_redirect[0] >> 9 ); __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) + __ISB(); } } @@ -182,6 +184,7 @@ void nvicUninstallRedirect() { { _SCB_VTOR.TBLOFF = ( (uint32_t)_NVIC_GetDefaultVector() >> 9 ); __DSB(); // handle CPU pipeline caching inconsistencies (non instruction encoding) + __ISB(); } _vtor_refcount--; } diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index ff9361ade77c..fe7dc6b4294d 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -457,6 +457,11 @@ void hook_cpu_exceptions() { // So we'll simply mask the top 8 bits of the first handler as an hint of being in the flash or not -that's poor and will // probably break if the flash happens to be more than 128MB, but in this case, we are not magician, we need help from outside. +#if !defined(TARGET_LPC1768) + // On LPC176x/LPC175x the entry indexed 7 is the checksum of the first entries 0..6, thus + // we cannot use it to peek for any default handler. + // See page 627 of UM10360. + // Undocumented!!! Use with caution!!! (peeking into reserved vector entries) auto defaultFaultHandler = nvicGetHandler(7u); // Replace all default handlers with our own handler. @@ -466,6 +471,7 @@ void hook_cpu_exceptions() { if (nvicGetHandler(i) == defaultFaultHandler) nvicSetHandler(i, CommonHandler_ASM); } +#endif // Let's hook now with our functions nvicSetHandler((unsigned long)hook_get_hardfault_vector_address(0), CommonHandler_ASM); From f58a26998d1fc6aff1f8c289bd0ba51a585a0c50 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Sat, 17 Dec 2022 20:02:07 +0100 Subject: [PATCH 48/83] - QoL improvement for AVR users: if the TMC SPI MISO,MOSI,SCK pins are not on the hardware SPI bus then we force their TMC SPI mode to software mode --- Marlin/src/inc/Conditionals_post.h | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index f6e76d1a6ef2..8dc4f98615cf 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2164,6 +2164,14 @@ #undef TMC_UART_IS #undef ANY_SERIAL_IS +#if defined(__AVR_ARCH__) && defined(TMC_SPI_MISO) && defined(TMC_SPI_MOSI) && defined(TMC_SPI_SCK) + // Check that the pins are the solitary supported SPI hardware pins of the (AVR) platform. + // Otherwise we are forced to enable software SPI. + #if TMC_SPI_MISO != MISO || TMC_SPI_MOSI != MOSI || TMC_SPI_SCK != SCK + #define TMC_USE_SW_SPI + #endif +#endif + // Clean up unused ESP_WIFI pins #ifdef ESP_WIFI_MODULE_COM #if !SERIAL_IN_USE(ESP_WIFI_MODULE_COM) From 1942dbbe133f05b63574333f2d3b4f6f5c19c3e5 Mon Sep 17 00:00:00 2001 From: Martin Turski Date: Mon, 30 Jan 2023 21:11:40 +0100 Subject: [PATCH 49/83] - added MKS TinyBee V1.0 board definition file + linked it with the build process - fixed some issues regarding volatile memory access semantics across AVR, LPC1768, ESP32 - upgraded MKS TinyBee compilation to espressif 6.0.0 + GCC 11.2.0 (very recently released) -> code changes to make Marlin FW compatible with the latest toolchain - overhaul of ESP32 HW HAL SPI layer, making use of Eir SDK BitManager code-graphs to speed up 64 byte / 512 bit SPI buffer fetch & fill (further optimizations to the software model are outstanding to a point past pull request approval) - tiny adjustments regarding SPI FLASH & MAX31865 SPI temperature controller (next project) --- Marlin/src/HAL/AVR/HAL_SPI_HW.cpp | 6 +- Marlin/src/HAL/AVR/registers.h | 147 +- Marlin/src/HAL/ESP32/HAL.cpp | 17 +- Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp | 1402 +++++++++++----- Marlin/src/HAL/ESP32/sdk/Arith.h | 62 + Marlin/src/HAL/ESP32/sdk/BitIteration.h | 440 +++++ Marlin/src/HAL/ESP32/sdk/BitManage.h | 1442 +++++++++++++++++ Marlin/src/HAL/ESP32/sdk/BitManip.h | 515 ++++++ Marlin/src/HAL/ESP32/sdk/Compare.h | 231 +++ Marlin/src/HAL/ESP32/sdk/Endian.h | 258 +++ Marlin/src/HAL/ESP32/sdk/MacroUtils.h | 72 + Marlin/src/HAL/ESP32/sdk/MemoryRaw.h | 135 ++ Marlin/src/HAL/ESP32/sdk/MetaHelpers.h | 1228 ++++++++++++++ Marlin/src/HAL/ESP32/sdk/PlatformStrategy.h | 808 +++++++++ Marlin/src/HAL/ESP32/sdk/Tuple.h | 143 ++ Marlin/src/HAL/ESP32/sdk/Union.h | 140 ++ Marlin/src/HAL/ESP32/sdk/Variant.h | 662 ++++++++ Marlin/src/HAL/ESP32/timers.cpp | 2 +- Marlin/src/HAL/LPC1768/HAL_SPI_HW.cpp | 25 +- Marlin/src/HAL/shared/tft/tft_spi.cpp | 6 + Marlin/src/HAL/shared/tft/tft_spi.h | 2 + Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- Marlin/src/lcd/tft_io/tft_io.cpp | 24 +- Marlin/src/libs/MAX31865.cpp | 50 +- Marlin/src/libs/MAX31865.h | 23 +- Marlin/src/libs/W25Qxx.cpp | 113 +- Marlin/src/libs/circularqueue.h | 6 +- Marlin/src/pins/stm32f4/pins_TRONXY_V10.h | 8 +- .../PlatformIO/boards/marlin_MKS_TinyBee.json | 38 + ini/esp32.ini | 12 + platformio.ini | 1 + 31 files changed, 7443 insertions(+), 577 deletions(-) create mode 100644 Marlin/src/HAL/ESP32/sdk/Arith.h create mode 100644 Marlin/src/HAL/ESP32/sdk/BitIteration.h create mode 100644 Marlin/src/HAL/ESP32/sdk/BitManage.h create mode 100644 Marlin/src/HAL/ESP32/sdk/BitManip.h create mode 100644 Marlin/src/HAL/ESP32/sdk/Compare.h create mode 100644 Marlin/src/HAL/ESP32/sdk/Endian.h create mode 100644 Marlin/src/HAL/ESP32/sdk/MacroUtils.h create mode 100644 Marlin/src/HAL/ESP32/sdk/MemoryRaw.h create mode 100644 Marlin/src/HAL/ESP32/sdk/MetaHelpers.h create mode 100644 Marlin/src/HAL/ESP32/sdk/PlatformStrategy.h create mode 100644 Marlin/src/HAL/ESP32/sdk/Tuple.h create mode 100644 Marlin/src/HAL/ESP32/sdk/Union.h create mode 100644 Marlin/src/HAL/ESP32/sdk/Variant.h create mode 100644 buildroot/share/PlatformIO/boards/marlin_MKS_TinyBee.json diff --git a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp index 2ba8a0ffafd4..817a241b701b 100644 --- a/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/AVR/HAL_SPI_HW.cpp @@ -245,7 +245,7 @@ __SMCR._SE = true; __SMCR._SM = 0; // IDLE __SMCR.reserved1 = 0; - AVRHelpers::dwrite(_SMCR) = __SMCR; + AVRHelpers::dwrite(_SMCR, __SMCR); // Enable the SPI interrupt. _SPCR._SPIE = true; @@ -259,7 +259,7 @@ __SMCR._SE = false; __SMCR._SM = 0; __SMCR.reserved1 = 0; - AVRHelpers::dwrite(_SMCR) = __SMCR; + AVRHelpers::dwrite(_SMCR, __SMCR); // Disable the SPI interrupt. _SPCR._SPIE = false; @@ -356,7 +356,7 @@ } // Write initial configuration. - AVRHelpers::dwrite(_SPCR) = __SPCR; + AVRHelpers::dwrite(_SPCR, __SPCR); _spi_is_running = true; _spi_transaction_is_active = false; diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index a00c7d334681..fc75bd65811c 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -1823,8 +1823,21 @@ namespace AVRHelpers { template struct no_volatile : public no_volatile {}; - template - inline typename no_volatile ::type& dwrite( memRegType& V ) { return (typename no_volatile ::type&)V; } + template + inline void dwrite(volatile T& v, const T& V) noexcept { + if constexpr ( sizeof(T) == sizeof(uint8_t) ) { + (volatile uint8_t&)v = (const uint8_t&)V; + } + else if constexpr ( sizeof(T) == sizeof(uint16_t) ) { + (volatile uint16_t&)v = (const uint16_t&)V; + } + else if constexpr ( sizeof(T) == sizeof(uint32_t) ) { + (volatile uint32_t&)v = (const uint32_t&)V; + } + else { + v = V; + } + } } // namespace AVRHelpers @@ -1844,7 +1857,7 @@ inline void _ATmega_resetperipherals() { __SREG._H = false; __SREG._T = false; __SREG._I = false; - dwrite(_SREG) = __SREG; + dwrite(_SREG, __SREG); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) @@ -1856,7 +1869,7 @@ inline void _ATmega_resetperipherals() { #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) _EEAR._EEAR = 0; - dwrite(_EEDR) = 0; + dwrite(_EEDR, (uint8_t)0u); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1868,7 +1881,7 @@ inline void _ATmega_resetperipherals() { __EECR._EEPM0 = 0; __EECR._EEPM1 = 0; __EECR.reserved1 = 0; - dwrite(_EECR) = __EECR; + dwrite(_EECR, __EECR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1883,13 +1896,13 @@ inline void _ATmega_resetperipherals() { __XMCRA._SRW1 = 0; __XMCRA._SRL = 0; __XMCRA._SRE = 0; - dwrite(_XMCRA) = __XMCRA; + dwrite(_XMCRA, __XMCRA); XMCRB_reg_t __XMCRB; __XMCRB._XMM = 0; __XMCRB.reserved1 = 0; __XMCRB._XMBK = false; - dwrite(_XMCRB) = __XMCRB; + dwrite(_XMCRB, __XMCRB); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1897,7 +1910,7 @@ inline void _ATmega_resetperipherals() { __SMCR._SE = false; __SMCR._SM = 0; __SMCR.reserved1 = 0; - dwrite(_SMCR) = __SMCR; + dwrite(_SMCR, __SMCR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1930,7 +1943,7 @@ inline void _ATmega_resetperipherals() { __PRR0._PRTIM2 = false; __PRR0._PRTWI = false; #endif - dwrite(_PRR0) = __PRR0; + dwrite(_PRR0, __PRR0); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -1950,7 +1963,7 @@ inline void _ATmega_resetperipherals() { __PRR1._PRUSART1 = false; __PRR1.reserved1 = 0; #endif - dwrite(_PRR1) = __PRR1; + dwrite(_PRR1, __PRR1); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1963,7 +1976,7 @@ inline void _ATmega_resetperipherals() { __WDTCSR._WDP3 = 0; __WDTCSR._WDIE = false; __WDTCSR._WDIF = false; - dwrite(_WDTCSR) = __WDTCSR; + dwrite(_WDTCSR, __WDTCSR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -1978,16 +1991,16 @@ inline void _ATmega_resetperipherals() { #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(_PORTA) = __PORT; - dwrite(_PORTC) = __PORT; + dwrite(_PORTA, __PORT); + dwrite(_PORTC, __PORT); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_PORTB) = __PORT; - dwrite(_PORTD) = __PORT; + dwrite(_PORTB, __PORT); + dwrite(_PORTD, __PORT); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) - dwrite(_PORTE) = __PORT; - dwrite(_PORTF) = __PORT; + dwrite(_PORTE, __PORT); + dwrite(_PORTF, __PORT); #endif #ifdef __AVR_TRM01__ @@ -1998,7 +2011,7 @@ inline void _ATmega_resetperipherals() { __PORTG._DDR.reserved1 = 0; __PORTG._PORT.val = 0; __PORTG._PORT.reserved1 = 0; - dwrite(_PORTG) = __PORTG; + dwrite(_PORTG, __PORTG); #endif #ifdef __AVR_TRM03__ @@ -2009,14 +2022,14 @@ inline void _ATmega_resetperipherals() { __PORTC._DDR.reserved1 = 0; __PORTC._PORT.val = 0; __PORTC._PORT.reserved1 = 0; - dwrite(_PORTC) = __PORTC; + dwrite(_PORTC, __PORTC); #endif #ifdef __AVR_TRM01__ - dwrite(_PORTH) = __PORT; - dwrite(_PORTJ) = __PORT; - dwrite(_PORTK) = __PORT; - dwrite(_PORTL) = __PORT; + dwrite(_PORTH, __PORT); + dwrite(_PORTJ, __PORT); + dwrite(_PORTK, __PORT); + dwrite(_PORTL, __PORT); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2036,7 +2049,7 @@ inline void _ATmega_resetperipherals() { __EICRA._ISC1 = 0; __EICRA.reserved1 = 0; #endif - dwrite(_EICRA) = __EICRA; + dwrite(_EICRA, __EICRA); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM04__) @@ -2045,7 +2058,7 @@ inline void _ATmega_resetperipherals() { __EICRB._ISC5 = 0; __EICRB._ISC6 = 0; __EICRB._ISC7 = 0; - dwrite(_EICRB) = __EICRB; + dwrite(_EICRB, __EICRB); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2069,7 +2082,7 @@ inline void _ATmega_resetperipherals() { __EIMSK._INT1 = false; __EIMSK.reserved1 = 0; #endif - dwrite(_EIMSK) = __EIMSK; + dwrite(_EIMSK, __EIMSK); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2093,7 +2106,7 @@ inline void _ATmega_resetperipherals() { __EIFR._INTF1 = false; __EIFR.reserved1 = 0; #endif - dwrite(_EIFR) = __EIFR; + dwrite(_EIFR, __EIFR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2113,7 +2126,7 @@ inline void _ATmega_resetperipherals() { __PCICR._PCIE0 = false; __PCICR.reserved1 = 0; #endif - dwrite(_PCICR) = __PCICR; + dwrite(_PCICR, __PCICR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2133,7 +2146,7 @@ inline void _ATmega_resetperipherals() { __PCIFR._PCIF0 = false; __PCIFR.reserved1 = 0; #endif - dwrite(_PCIFR) = __PCIFR; + dwrite(_PCIFR, __PCIFR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2165,7 +2178,7 @@ inline void _ATmega_resetperipherals() { __TIMER_8bit._TCNTn = 0; __TIMER_8bit._OCRnA = 0; __TIMER_8bit._OCRnB = 0; - dwrite(TIMER0) = __TIMER_8bit; + dwrite(TIMER0, __TIMER_8bit); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2174,14 +2187,14 @@ inline void _ATmega_resetperipherals() { __TIMSK0._OCIE0A = false; __TIMSK0._OCIE0B = false; __TIMSK0.reserved1 = 0; - dwrite(_TIMSK0) = __TIMSK0; + dwrite(_TIMSK0, __TIMSK0); TIFR0_reg_t __TIFR0; __TIFR0._TOV0 = false; __TIFR0._OCF0A = false; __TIFR0._OCF0B = false; __TIFR0.reserved1 = 0; - dwrite(_TIFR0) = __TIFR0; + dwrite(_TIFR0, __TIFR0); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2211,14 +2224,14 @@ inline void _ATmega_resetperipherals() { TIMER._OCRnC = 0; #endif TIMER._ICRn = 0; - dwrite(TIMER1) = TIMER; + dwrite(TIMER1, TIMER); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(TIMER3) = TIMER; + dwrite(TIMER3, TIMER); #endif #ifdef __AVR_TRM01__ - dwrite(TIMER4) = TIMER; - dwrite(TIMER5) = TIMER; + dwrite(TIMER4, TIMER); + dwrite(TIMER5, TIMER); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2232,7 +2245,7 @@ inline void _ATmega_resetperipherals() { __TIMSK1.reserved1 = 0; __TIMSK1._ICIE1 = false; __TIMSK1.reserved2 = 0; - dwrite(_TIMSK1) = __TIMSK1; + dwrite(_TIMSK1, __TIMSK1); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -2246,7 +2259,7 @@ inline void _ATmega_resetperipherals() { __TIMSK3.reserved1 = 0; __TIMSK3._ICIE3 = false; __TIMSK3.reserved2 = 0; - dwrite(_TIMSK3) = __TIMSK3; + dwrite(_TIMSK3, __TIMSK3); #endif #ifdef __AVR_TRM01__ @@ -2258,7 +2271,7 @@ inline void _ATmega_resetperipherals() { __TIMSK4.reserved1 = false; __TIMSK4._ICIE4 = false; __TIMSK4.reserved2 = false; - dwrite(_TIMSK4) = __TIMSK4; + dwrite(_TIMSK4, __TIMSK4); TIMSK5_reg_t __TIMSK5; __TIMSK5._TOIE5 = false; @@ -2268,7 +2281,7 @@ inline void _ATmega_resetperipherals() { __TIMSK5.reserved1 = 0; __TIMSK5._ICIE5 = false; __TIMSK5.reserved2 = 0; - dwrite(_TIMSK5) = __TIMSK5; + dwrite(_TIMSK5, __TIMSK5); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2282,7 +2295,7 @@ inline void _ATmega_resetperipherals() { __TIFR1.reserved1 = 0; __TIFR1._ICF1 = false; __TIFR1.reserved2 = 0; - dwrite(_TIFR1) = __TIFR1; + dwrite(_TIFR1, __TIFR1); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) @@ -2296,7 +2309,7 @@ inline void _ATmega_resetperipherals() { __TIFR3.reserved1 = 0; __TIFR3._ICF3 = false; __TIFR3.reserved2 = 0; - dwrite(_TIFR3) = __TIFR3; + dwrite(_TIFR3, __TIFR3); #endif #ifdef __AVR_TRM01__ @@ -2308,7 +2321,7 @@ inline void _ATmega_resetperipherals() { __TIFR4.reserved1 = 0; __TIFR4._ICF4 = false; __TIFR4.reserved2 = 0; - dwrite(_TIFR4) = __TIFR4; + dwrite(_TIFR4, __TIFR4); TIFR5_reg_t __TIFR5; __TIFR5._TOV5 = false; @@ -2318,11 +2331,11 @@ inline void _ATmega_resetperipherals() { __TIFR5.reserved1 = 0; __TIFR5._ICF5 = false; __TIFR5.reserved2 = 0; - dwrite(_TIFR5) = __TIFR5; + dwrite(_TIFR5, __TIFR5); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_TIMER2) = __TIMER_8bit; + dwrite(_TIMER2, __TIMER_8bit); #endif #if defined(__AV_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2335,7 +2348,7 @@ inline void _ATmega_resetperipherals() { __ASSR._AS2 = false; __ASSR._EXCLK = false; __ASSR.reserved1 = 0; - dwrite(_ASSR) = __ASSR; + dwrite(_ASSR, __ASSR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2344,14 +2357,14 @@ inline void _ATmega_resetperipherals() { __TIMSK2._OCIE2A = false; __TIMSK2._OCIE2B = false; __TIMSK2.reserved1 = 0; - dwrite(_TIMSK2) = __TIMSK2; + dwrite(_TIMSK2, __TIMSK2); TIFR2_reg_t __TIFR2; __TIFR2._TOV2 = false; __TIFR2._OCF2A = false; __TIFR2._OCF2B = false; __TIFR2.reserved1 = 0; - dwrite(_TIFR2) = __TIFR2; + dwrite(_TIFR2, __TIFR2); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2363,14 +2376,14 @@ inline void _ATmega_resetperipherals() { __SPCR._DORD = 0; __SPCR._SPE = false; __SPCR._SPIE = false; - dwrite(_SPCR) = __SPCR; + dwrite(_SPCR, __SPCR); SPSR_reg_t __SPSR; __SPSR._SPI2X = false; __SPSR.reserved1 = 0; __SPSR._WCOL = false; __SPSR._SPIF = false; - dwrite(_SPSR) = __SPSR; + dwrite(_SPSR, __SPSR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2403,18 +2416,18 @@ inline void _ATmega_resetperipherals() { USART._UBRRn.reserved1 = 0; #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) - dwrite(USART0) = USART; + dwrite(USART0, USART); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM04__) - dwrite(USART1) = USART; + dwrite(USART1, USART); #endif #ifdef __AVR_TRM01__ - dwrite(USART2) = USART; - dwrite(USART3) = USART; + dwrite(USART2, USART); + dwrite(USART3, USART); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) - dwrite(_TWBR) = 0; + dwrite(_TWBR, (uint8_t)0); TWCR_reg_t __TWCR; __TWCR._TWIE = false; @@ -2425,7 +2438,7 @@ inline void _ATmega_resetperipherals() { __TWCR._TWSTA = false; __TWCR._TWEA = false; __TWCR._TWINT = false; - dwrite(_TWCR) = __TWCR; + dwrite(_TWCR, __TWCR); TWSR_reg_t __TWSR; __TWSR._TWPS0 = false; @@ -2436,19 +2449,19 @@ inline void _ATmega_resetperipherals() { __TWSR._TWS5 = 1; __TWSR._TWS6 = 1; __TWSR._TWS7 = 1; - dwrite(_TWSR) = __TWSR; + dwrite(_TWSR, __TWSR); - dwrite(_TWDR) = 0xFF; + dwrite(_TWDR, (uint8_t)0xFF); TWAR_reg_t __TWAR; __TWAR._TWGCE = false; __TWAR._TWA = 0x7F; - dwrite(_TWAR) = __TWAR; + dwrite(_TWAR, __TWAR); TWAMR_reg_t __TWAMR; __TWAMR.reserved1 = false; __TWAMR._TWAM = 0; - dwrite(_TWAMR) = __TWAMR; + dwrite(_TWAMR, __TWAMR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2460,7 +2473,7 @@ inline void _ATmega_resetperipherals() { __ADCSRB.reserved1 = 0; __ADCSRB._ACME = false; __ADCSRB.reserved2 = 0; - dwrite(_ADCSRB) = __ADCSRB; + dwrite(_ADCSRB, __ADCSRB); ACSR_reg_t __ACSR; __ACSR._ACIS = 0; @@ -2470,7 +2483,7 @@ inline void _ATmega_resetperipherals() { __ACSR._ACO = false; __ACSR._ACBG = false; __ACSR._ACD = false; - dwrite(_ACSR) = __ACSR; + dwrite(_ACSR, __ACSR); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2478,7 +2491,7 @@ inline void _ATmega_resetperipherals() { __DIDR1._AIN0D = false; __DIDR1._AIN1D = false; __DIDR1.reserved1 = false; - dwrite(_DIDR1) = __DIDR1; + dwrite(_DIDR1, __DIDR1); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2495,7 +2508,7 @@ inline void _ATmega_resetperipherals() { __ADMUX._ADLAR = 0; __ADMUX._REFS0 = 0; __ADMUX._REFS1 = 0; - dwrite(_ADMUX) = __ADMUX; + dwrite(_ADMUX, __ADMUX); ADCSRA_reg_t __ADCSRA; __ADCSRA._ADPS = 0; @@ -2504,9 +2517,9 @@ inline void _ATmega_resetperipherals() { __ADCSRA._ADATE = false; __ADCSRA._ADSC = false; __ADCSRA._ADEN = false; - dwrite(_ADCSRA) = __ADCSRA; + dwrite(_ADCSRA, __ADCSRA); - dwrite(_ADC) = 0; + dwrite(_ADC, (uint16_t)0); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) @@ -2541,7 +2554,7 @@ inline void _ATmega_resetperipherals() { __SPMCSR._SPMIE = false; #endif #endif - dwrite(_SPMCSR) = __SPMCSR; + dwrite(_SPMCSR, __SPMCSR); #endif // TODO: add the __AVR_TRM04__ initializations, if required (mostly USB related) diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 29f3be3c028a..dd9170588716 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -209,16 +209,17 @@ int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } // ADC // ------------------------ -#define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL - +//https://docs.espressif.com/projects/esp-idf/en/release-v4.4/esp32/api-reference/peripherals/adc.html adc1_channel_t get_channel(int pin) { switch (pin) { - case 39: return ADC1_CHANNEL(39); - case 36: return ADC1_CHANNEL(36); - case 35: return ADC1_CHANNEL(35); - case 34: return ADC1_CHANNEL(34); - case 33: return ADC1_CHANNEL(33); - case 32: return ADC1_CHANNEL(32); + case 39: return ADC1_CHANNEL_3; + case 36: return ADC1_CHANNEL_0; + case 35: return ADC1_CHANNEL_7; + case 34: return ADC1_CHANNEL_6; + case 33: return ADC1_CHANNEL_5; + case 32: return ADC1_CHANNEL_4; + case 37: return ADC1_CHANNEL_1; + case 38: return ADC1_CHANNEL_2; } return ADC1_CHANNEL_MAX; } diff --git a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp index 8215c8346722..747ae3ee7b72 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI_HW.cpp @@ -41,18 +41,52 @@ #include "../../inc/MarlinConfig.h" #include "../shared/HAL_SPI.h" -#include "../shared/SPI/bufmgmt.h" #if !ENABLED(SOFTWARE_SPI) && !ENABLED(HALSPI_HW_GENERIC) -#include "FreeRTOS.h" -//#include "semphr.h" +#include "sdk/BitManage.h" + +template +using esp32BitManager = eir::BitManager ::template spec, eir::typelist >; // ------------------------ // Hardware SPI -// tested using MKS TinyBee V1.0 (ESP32-WROOM-32U) +// tested using MKS TinyBee V1.0 (ESP32-WROOM-32U / ESP32-D0WD (rev1)) // ------------------------ +/* + The ESP32 SPI DMA hardware implementation problem. + - written by Martin Turski on the 30th of January, 2023 + + Reliability of a platform implementation comes first. Thus I have decided to cut away the optional SPI DMA + implementation from the first generation of ESP32 chips. Continue reading so I can elaborate on why. + + Numerous people on the internet have tried to reach the Espressif support about custom SPI DMA implementations + but failed. + - https://www.esp32.com/viewtopic.php?t=16036 (https://web.archive.org/web/20230130174342/https://www.esp32.com/viewtopic.php?t=16036) + - https://esp32.com/viewtopic.php?t=5152 (https://web.archive.org/web/20230130174608/https://esp32.com/viewtopic.php?t=5152) + - https://esp32.com/viewtopic.php?t=10075 (https://web.archive.org/web/20230130174757/https://esp32.com/viewtopic.php?t=10075) + The esp-idf so called "SPI master driver" does not, by design, support automatic MSBFIRST 16bit SPI frames. I want to highlight + the ESP32 hardware "workaround" that points to reliability issues in the silicon. + - (https://www.esp32.com/viewtopic.php?t=8433 spi_master.zip:spi_master.c:line 754) + Support issues make people give up on the MCU altogether. + - https://esp32.com/viewtopic.php?t=14732 (https://web.archive.org/web/20230130185951/https://esp32.com/viewtopic.php?t=14732) + + I would appreciate good help! I want to implement the ESP32 DMA SPI for the ESP32-D0WD, revision 1. The best way + would be in the form of a sample project easily compilable & runnable on the MKS TinyBee V1.0. The example project + must not use the SPI Master driver from esp-idf. Please contact me in the original pull request if you have found a solution. + + ESP32 SPI DMA machine-state dump at DMASendBlocking call related to the error: https://pastebin.com/LNBzJvRy + + Other SPI issues of ESP32 that seem fatal: + - https://www.esp32.com/viewtopic.php?t=31389 (https://web.archive.org/web/20230130184649/https://www.esp32.com/viewtopic.php?t=31389) + + Please note that SPI with interrupts has been 100% tested and works just fine. Hence it is not a big deal to leave-out DMA acceleration. +*/ +#ifndef HALSPI_DISABLE_DMA + #define HALSPI_DISABLE_DMA +#endif + static void _spi_on_error(const uint32_t code=0) { for (;;) { #if defined(HALSPI_DO_ERRORBEEPS) && PIN_EXISTS(BEEPER) @@ -134,13 +168,40 @@ inline numberType _MIN(numberType a, numberType b) { namespace MarlinESP32 { +#define __ESP32_DEFREG(tn,n,l) static volatile tn& n = *(volatile tn*)l + +template +inline void dwrite(volatile T& v, const T& V) noexcept { + if constexpr ( sizeof(T) == sizeof(uint8_t) ) { + (volatile uint8_t&)v = (const uint8_t&)V; + } + else if constexpr ( sizeof(T) == sizeof(uint16_t) ) { + (volatile uint16_t&)v = (const uint16_t&)V; + } + else if constexpr ( sizeof(T) == sizeof(uint32_t) ) { + (volatile uint32_t&)v = (const uint32_t&)V; + } + else { + v = V; + } +} + struct spi_cmd_reg_t { uint32_t reserved1 : 18; uint32_t SPI_USR : 1; uint32_t reserved2 : 13; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_CMD_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_CMD_REG.SPI_USR = ", SPI_USR, ";"); + SERIAL_ECHOLNPGM("SPI_CMD_REG.reserved2 = ", reserved2, ";"); + } }; static_assert(sizeof(spi_cmd_reg_t) == 4, "invalid size for ESP32 spi_cmd_reg_t"); +#define _ESP32_BIT_ORDER_MSB 0 +#define _ESP32_BIT_ORDER_LSB 1 + struct spi_ctrl_reg_t { uint32_t reserved1 : 13; uint32_t SPI_FASTRD_MODE : 1; @@ -154,9 +215,35 @@ struct spi_ctrl_reg_t { uint32_t SPI_RD_BIT_ORDER : 1; uint32_t SPI_WR_BIT_ORDER : 1; uint32_t reserved4 : 5; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_CTRL_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_FASTRD_MODE = ", SPI_FASTRD_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_FREAD_DUAL = ", SPI_FREAD_DUAL, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.reserved2 = ", reserved2, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_FREAD_QUAD = ", SPI_FREAD_QUAD, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_WP = ", SPI_WP, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.reserved3 = ", reserved3, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_FREAD_DIO = ", SPI_FREAD_DIO, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_FREAD_QIO = ", SPI_FREAD_QIO, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_RD_BIT_ORDER = ", SPI_RD_BIT_ORDER, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.SPI_WR_BIT_ORDER = ", SPI_WR_BIT_ORDER, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL_REG.reserved4 = ", reserved4, ";"); + } }; static_assert(sizeof(spi_ctrl_reg_t) == 4, "invalid size for ESP32 spi_ctrl_reg_t"); +struct spi_ctrl1_reg_t { + uint32_t reserved1 : 28; + uint32_t SPI_CS_HOLD_DELAY : 4; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_CTRL1_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL1_REG.SPI_CS_HOLD_DELAY = ", SPI_CS_HOLD_DELAY, ";"); + } +}; +static_assert(sizeof(spi_ctrl1_reg_t) == 4, "invalid size for ESP32 spi_ctrl1_reg_t"); + struct spi_ctrl2_reg_t { uint32_t SPI_SETUP_TIME : 4; uint32_t SPI_HOLD_TIME : 4; @@ -168,6 +255,19 @@ struct spi_ctrl2_reg_t { uint32_t SPI_MOSI_DELAY_NUM : 3; uint32_t SPI_CS_DELAY_MODE : 2; uint32_t SPI_CS_DELAY_NUM : 4; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_SETUP_TIME = ", SPI_SETUP_TIME, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_HOLD_TIME = ", SPI_HOLD_TIME, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_CK_OUT_HIGH_MODE = ", SPI_CK_OUT_HIGH_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = ", SPI_MISO_DELAY_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_MISO_DELAY_NUM = ", SPI_MISO_DELAY_NUM, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_MOSI_DELAY_MODE = ", SPI_MOSI_DELAY_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_MOSI_DELAY_NUM = ", SPI_MOSI_DELAY_NUM, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_CS_DELAY_MODE = ", SPI_CS_DELAY_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_CTRL2_REG.SPI_CS_DELAY_NUM = ", SPI_CS_DELAY_NUM, ";"); + } }; static_assert(sizeof(spi_ctrl2_reg_t) == 4, "invalid size for ESP32 spi_ctrl2_reg_t"); @@ -177,6 +277,14 @@ struct spi_clock_reg_t { uint32_t SPI_CLKCNT_N : 6; uint32_t SPI_CLKDIV_PRE : 13; uint32_t SPI_CLK_EQU_SYSCLK : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_CLOCK_REG.SPI_CLKCNT_L = ", SPI_CLKCNT_L, ";"); + SERIAL_ECHOLNPGM("SPI_CLOCK_REG.SPI_CLKCNT_H = ", SPI_CLKCNT_H, ";"); + SERIAL_ECHOLNPGM("SPI_CLOCK_REG.SPI_CLKCNT_N = ", SPI_CLKCNT_N, ";"); + SERIAL_ECHOLNPGM("SPI_CLOCK_REG.SPI_CLKDIV_PRE = ", SPI_CLKDIV_PRE, ";"); + SERIAL_ECHOLNPGM("SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = ", SPI_CLK_EQU_SYSCLK, ";"); + } }; static_assert(sizeof(spi_clock_reg_t) == 4, "invalid size for ESP32 spi_clock_reg_t"); @@ -204,6 +312,32 @@ struct spi_user_reg_t { uint32_t SPI_USR_DUMMY : 1; uint32_t SPI_USR_ADDR : 1; uint32_t SPI_USR_COMMAND : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_DOUTDIN = ", SPI_DOUTDIN, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_CS_HOLD = ", SPI_CS_HOLD, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_CS_SETUP = ", SPI_CS_SETUP, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_CK_I_EDGE = ", SPI_CK_I_EDGE, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_CK_OUT_EDGE = ", SPI_CK_OUT_EDGE, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.reserved2 = ", reserved2, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_RD_BYTE_ORDER = ", SPI_RD_BYTE_ORDER, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_WR_BYTE_ORDER = ", SPI_WR_BYTE_ORDER, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_FWRITE_DUAL = ", SPI_FWRITE_DUAL, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_FWRITE_QUAD = ", SPI_FWRITE_QUAD, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_FWRITE_DIO = ", SPI_FWRITE_DIO, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_FWRITE_QIO = ", SPI_FWRITE_QIO, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_SIO = ", SPI_SIO, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.reserved3 = ", reserved3, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_MISO_HIGHPART = ", SPI_USR_MISO_HIGHPART, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_MOSI_HIGHPART = ", SPI_USR_MOSI_HIGHPART, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_DUMMY_IDLE = ", SPI_USR_DUMMY_IDLE, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_MOSI = ", SPI_USR_MOSI, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_MISO = ", SPI_USR_MISO, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_DUMMY = ", SPI_USR_DUMMY, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_ADDR = ", SPI_USR_ADDR, ";"); + SERIAL_ECHOLNPGM("SPI_USER_REG.SPI_USR_COMMAND = ", SPI_USR_COMMAND, ";"); + } }; static_assert(sizeof(spi_user_reg_t) == 4, "invalid size for ESP32 spi_user_reg_t"); @@ -211,6 +345,12 @@ struct spi_user1_reg_t { uint32_t SPI_USR_DUMMY_CYCLELEN : 8; uint32_t reserved1 : 18; uint32_t SPI_USR_ADDR_BITLEN : 6; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = ", SPI_USR_DUMMY_CYCLELEN, ";"); + SERIAL_ECHOLNPGM("SPI_USER1_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_USER1_REG.SPI_USR_ADDR_BITLEN = ", SPI_USR_ADDR_BITLEN, ";"); + } }; static_assert(sizeof(spi_user1_reg_t) == 4, "invalid size for ESP32 spi_user1_reg_t"); @@ -218,18 +358,34 @@ struct spi_user2_reg_t { uint32_t SPI_USR_COMMAND_VALUE : 16; uint32_t reserved1 : 12; uint32_t SPI_USR_COMMAND_BITLEN : 4; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_USER2_REG.SPI_USR_COMMAND_VALUE = ", SPI_USR_COMMAND_VALUE, ";"); + SERIAL_ECHOLNPGM("SPI_USER2_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_USER2_REG.SPI_USR_COMMAND_BITLEN = ", SPI_USR_COMMAND_BITLEN, ";"); + } }; static_assert(sizeof(spi_user2_reg_t) == 4, "invalid size for ESP32 spi_user2_reg_t"); struct spi_mosi_dlen_reg_t { uint32_t SPI_USR_MOSI_DBITLEN : 24; uint32_t reserved1 : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = ", SPI_USR_MOSI_DBITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_MOSI_DLEN_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_mosi_dlen_reg_t) == 4, "invalid size for ESP32 spi_mosi_dlen_reg_t"); struct spi_miso_dlen_reg_t { uint32_t SPI_USR_MISO_DBITLEN : 24; uint32_t reserved1 : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = ", SPI_USR_MISO_DBITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_MISO_DLEN_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_miso_dlen_reg_t) == 4, "invalid size for ESP32 spi_miso_dlen_reg_t"); @@ -246,6 +402,21 @@ struct spi_pin_reg_t { uint32_t SPI_CK_IDLE_EDGE : 1; uint32_t SPI_CS_KEEP_ACTIVE : 1; uint32_t reserved4 : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CS0_DIS = ", SPI_CS0_DIS, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CS1_DIS = ", SPI_CS1_DIS, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CS2_DIS = ", SPI_CS2_DIS, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CK_DIS = ", SPI_CK_DIS, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_MASTER_CS_POL = ", SPI_MASTER_CS_POL, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.reserved2 = ", reserved2, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_MASTER_CK_SEL = ", SPI_MASTER_CK_SEL, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.reserved3 = ", reserved3, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CK_IDLE_EDGE = ", SPI_CK_IDLE_EDGE, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.SPI_CS_KEEP_ACTIVE = ", SPI_CS_KEEP_ACTIVE, ";"); + SERIAL_ECHOLNPGM("SPI_PIN_REG.reserved4 = ", reserved4, ";"); + } }; static_assert(sizeof(spi_pin_reg_t) == 4, "invalid size for ESP32 spi_pin_reg_t"); @@ -270,6 +441,29 @@ struct spi_slave_reg_t { uint32_t SPI_SLV_WR_RD_BUF_EN : 1; uint32_t SPI_SLAVE_MODE : 1; uint32_t SPI_SYNC_RESET : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_RD_BUF_DONE = ", SPI_SLV_RD_BUF_DONE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_BUF_DONE = ", SPI_SLV_WR_BUF_DONE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_RD_STA_DONE = ", SPI_SLV_RD_STA_DONE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_STA_DONE = ", SPI_SLV_WR_STA_DONE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_TRANS_DONE = ", SPI_TRANS_DONE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_RD_BUF_INTEN = ", SPI_SLV_RD_BUF_INTEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_BUF_INTEN = ", SPI_SLV_WR_BUF_INTEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_RD_STA_INTEN = ", SPI_SLV_RD_STA_INTEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_STA_INTEN = ", SPI_SLV_WR_STA_INTEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_TRANS_INTEN = ", SPI_TRANS_INTEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_CS_I_MODE = ", SPI_CS_I_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_LAST_COMMAND = ", SPI_SLV_LAST_COMMAND, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_LAST_STATE = ", SPI_SLV_LAST_STATE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_TRANS_CNT = ", SPI_TRANS_CNT, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_CMD_DEFINE = ", SPI_SLV_CMD_DEFINE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_RD_STA_EN = ", SPI_SLV_WR_RD_STA_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLV_WR_RD_BUF_EN = ", SPI_SLV_WR_RD_BUF_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SLAVE_MODE = ", SPI_SLAVE_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE_REG.SPI_SYNC_RESET = ", SPI_SYNC_RESET, ";"); + } }; static_assert(sizeof(spi_slave_reg_t) == 4, "invalid size for ESP32 spi_slave_reg_t"); @@ -284,6 +478,19 @@ struct spi_slave1_reg_t { uint32_t SPI_SLV_STATUS_READBACK : 1; uint32_t SPI_SLV_STATUS_FAST_EN : 1; uint32_t SPI_SLV_STATUS_BITLEN : 5; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_RDBUF_DUMMY_EN = ", SPI_SLV_RDBUF_DUMMY_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_WRBUF_DUMMY_EN = ", SPI_SLV_WRBUF_DUMMY_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_RDSTA_DUMMY_EN = ", SPI_SLV_RDSTA_DUMMY_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_WRSTA_DUMMY_EN = ", SPI_SLV_WRSTA_DUMMY_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_WR_ADDR_BITLEN = ", SPI_SLV_WR_ADDR_BITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_RD_ADDR_BITLEN = ", SPI_SLV_RD_ADDR_BITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_STATUS_READBACK = ", SPI_SLV_STATUS_READBACK, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_STATUS_FAST_EN = ", SPI_SLV_STATUS_FAST_EN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE1_REG.SPI_SLV_STATUS_BITLEN = ", SPI_SLV_STATUS_BITLEN, ";"); + } }; static_assert(sizeof(spi_slave1_reg_t) == 4, "invalid size for ESP32 spi_slave1_reg_t"); @@ -292,6 +499,13 @@ struct spi_slave2_reg_t { uint32_t SPI_SLV_WRSTA_DUMMY_CYCLELEN : 8; uint32_t SPI_SLV_RDBUF_DUMMY_CYCLELEN : 8; uint32_t SPI_SLV_WRBUF_DUMMY_CYCLELEN : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLAVE2_REG.SPI_SLV_RDSTA_DUMMY_CYCLELEN = ", SPI_SLV_RDSTA_DUMMY_CYCLELEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE2_REG.SPI_SLV_WRSTA_DUMMY_CYCLELEN = ", SPI_SLV_WRSTA_DUMMY_CYCLELEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE2_REG.SPI_SLV_RDBUF_DUMMY_CYCLELEN = ", SPI_SLV_RDBUF_DUMMY_CYCLELEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE2_REG.SPI_SLV_WRBUF_DUMMY_CYCLELEN = ", SPI_SLV_WRBUF_DUMMY_CYCLELEN, ";"); + } }; static_assert(sizeof(spi_slave2_reg_t) == 4, "invalid size for ESP32 spi_slave2_reg_t"); @@ -300,30 +514,57 @@ struct spi_slave3_reg_t { uint32_t SPI_SLV_WRBUF_CMD_VALUE : 8; uint32_t SPI_SLV_RDSTA_CMD_VALUE : 8; uint32_t SPI_SLV_WRSTA_CMD_VALUE : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLAVE3_REG.SPI_SLV_RDBUF_CMD_VALUE = ", SPI_SLV_RDBUF_CMD_VALUE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE3_REG.SPI_SLV_WRBUF_CMD_VALUE = ", SPI_SLV_WRBUF_CMD_VALUE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE3_REG.SPI_SLV_RDSTA_CMD_VALUE = ", SPI_SLV_RDSTA_CMD_VALUE, ";"); + SERIAL_ECHOLNPGM("SPI_SLAVE3_REG.SPI_SLV_WRSTA_CMD_VALUE = ", SPI_SLV_WRSTA_CMD_VALUE, ";"); + } }; static_assert(sizeof(spi_slave3_reg_t) == 4, "invalid size for ESP32 spi_slave3_reg_t"); struct spi_slv_wrbuf_dlen_reg_t { uint32_t SPI_SLV_WRBUF_DBITLEN : 24; uint32_t reserved1 : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLV_WRBUF_DLEN_REG.SPI_SLV_WRBUF_DBITLEN = ", SPI_SLV_WRBUF_DBITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLV_WRBUF_DLEN_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_slv_wrbuf_dlen_reg_t) == 4, "invalid size for ESP32 spi_slv_wrbuf_dlen_reg_t"); struct spi_slv_rdbuf_dlen_reg_t { uint32_t SPI_SLV_RDBUF_DBITLEN : 24; uint32_t reserved1 : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLV_RDBUF_DLEN_REG.SPI_SLV_RDBUF_DBITLEN = ", SPI_SLV_RDBUF_DBITLEN, ";"); + SERIAL_ECHOLNPGM("SPI_SLV_RDBUF_DLEN_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_slv_rdbuf_dlen_reg_t) == 4, "invalid size for ESP32 spi_slv_rdbuf_dlen_reg_t"); struct spi_slv_rd_bit_reg_t { uint32_t SPI_SLV_RDATA_BIT : 24; uint32_t reserved1 : 8; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_SLV_RD_BIT_REG.SPI_SLV_RDATA_BIT = ", SPI_SLV_RDATA_BIT, ";"); + SERIAL_ECHOLNPGM("SPI_SLV_RD_BIT_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_slv_rd_bit_reg_t) == 4, "invalid size for ESP32 spi_slv_rd_bit_reg_t"); struct spi_ext2_reg_t { uint32_t SPI_ST : 3; // read-only uint32_t reserved1 : 29; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_EXT2_REG.SPI_ST = ", SPI_ST, ";"); + SERIAL_ECHOLNPGM("SPI_EXT2_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_ext2_reg_t) == 4, "invalid size for ESP32 spi_ext2_reg_t"); @@ -343,6 +584,24 @@ struct spi_dma_conf_reg_t { uint32_t SPI_DMA_TX_STOP : 1; uint32_t SPI_DMA_CONTINUE : 1; uint32_t reserved4 : 15; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_IN_RST = ", SPI_IN_RST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_OUT_RST = ", SPI_OUT_RST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = ", SPI_AHBM_FIFO_RST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_AHBM_RST = ", SPI_AHBM_RST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.reserved2 = ", reserved2, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_OUT_EOF_MODE = ", SPI_OUT_EOF_MODE, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_OUTDSCR_BURST_EN = ", SPI_OUTDSCR_BURST_EN, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_INDSCR_BURST_EN = ", SPI_INDSCR_BURST_EN, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_OUT_DATA_BURST_EN = ", SPI_OUT_DATA_BURST_EN, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.reserved3 = ", reserved3, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_DMA_RX_STOP = ", SPI_DMA_RX_STOP, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_DMA_TX_STOP = ", SPI_DMA_TX_STOP, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.SPI_DMA_CONTINUE = ", SPI_DMA_CONTINUE, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_CONF_REG.reserved4 = ", reserved4, ";"); + } }; static_assert(sizeof(spi_dma_conf_reg_t) == 4, "invalid size for ESP32 spi_dma_conf_reg_t"); @@ -353,6 +612,15 @@ struct spi_dma_out_link_reg_t { uint32_t SPI_OUTLINK_START : 1; uint32_t SPI_OUTLINK_RESTART : 1; uint32_t reserved2 : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = ", SPI_OUTLINK_ADDR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_STOP = ", SPI_OUTLINK_STOP, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = ", SPI_OUTLINK_START, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_RESTART = ", SPI_OUTLINK_RESTART, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_OUT_LINK_REG.reserved2 = ", reserved2, ";"); + } }; static_assert(sizeof(spi_dma_out_link_reg_t) == 4, "invalid size for ESP32 spi_dma_out_link_reg_t"); @@ -364,6 +632,16 @@ struct spi_dma_in_link_reg_t { uint32_t SPI_INLINK_START : 1; uint32_t SPI_INLINK_RESTART : 1; uint32_t reserved2 : 1; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = ", SPI_INLINK_ADDR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.SPI_INLINK_AUTO_RET = ", SPI_INLINK_AUTO_RET, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.SPI_INLINK_STOP = ", SPI_INLINK_STOP, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.SPI_INLINK_START = ", SPI_INLINK_START, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.SPI_INLINK_RESTART = ", SPI_INLINK_RESTART, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_IN_LINK_REG.reserved2 = ", reserved2, ";"); + } }; static_assert(sizeof(spi_dma_in_link_reg_t) == 4, "invalid size for ESP32 spi_dma_in_link_reg_t"); @@ -371,6 +649,12 @@ struct spi_dma_status_reg_t { uint32_t SPI_DMA_TX_EN : 1; // read-only uint32_t SPI_DMA_RX_EN : 1; // read-only uint32_t reserved1 : 30; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_STATUS_REG.SPI_DMA_TX_EN = ", SPI_DMA_TX_EN, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_STATUS_REG.SPI_DMA_RX_EN = ", SPI_DMA_RX_EN, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_STATUS_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_dma_status_reg_t) == 4, "invalid size for ESP32 spi_dma_status_reg_t"); @@ -385,6 +669,19 @@ struct spi_dma_int_ena_reg_t { uint32_t SPI_OUT_EOF_INT_ENA : 1; uint32_t SPI_OUT_TOTAL_EOF_INT_ENA : 1; uint32_t reserved1 : 23; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_INLINK_DSCR_EMPTY_INT_ENA = ", SPI_INLINK_DSCR_EMPTY_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_OUTLINK_DSCR_ERROR_INT_ENA = ", SPI_OUTLINK_DSCR_ERROR_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_INLINK_DSCR_ERROR_INT_ENA = ", SPI_INLINK_DSCR_ERROR_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_IN_DONE_INT_ENA = ", SPI_IN_DONE_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_IN_ERR_EOF_INT_ENA = ", SPI_IN_ERR_EOF_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_IN_SUC_EOF_INT_ENA = ", SPI_IN_SUC_EOF_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_OUT_DONE_INT_ENA = ", SPI_OUT_DONE_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_OUT_EOF_INT_ENA = ", SPI_OUT_EOF_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.SPI_OUT_TOTAL_EOF_INT_ENA = ", SPI_OUT_TOTAL_EOF_INT_ENA, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ENA_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_dma_int_ena_reg_t) == 4, "invalid size for ESP32 spi_dma_int_ena_reg_t"); @@ -399,6 +696,19 @@ struct spi_dma_int_raw_reg_t { uint32_t SPI_OUT_EOF_INT_RAW : 1; // read-only uint32_t SPI_OUT_TOTAL_EOF_INT_RAW : 1; // read-only uint32_t reserved1 : 23; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_INLINK_DSCR_EMPTY_INT_RAW = ", SPI_INLINK_DSCR_EMPTY_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_OUTLINK_DSCR_ERROR_INT_RAW = ", SPI_OUTLINK_DSCR_ERROR_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_INLINK_DSCR_ERROR_INT_RAW = ", SPI_INLINK_DSCR_ERROR_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_IN_DONE_INT_RAW = ", SPI_IN_DONE_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_IN_ERR_EOF_INT_RAW = ", SPI_IN_ERR_EOF_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_IN_SUC_EOF_INT_RAW = ", SPI_IN_SUC_EOF_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_OUT_DONE_INT_RAW = ", SPI_OUT_DONE_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_OUT_EOF_INT_RAW = ", SPI_OUT_EOF_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.SPI_OUT_TOTAL_EOF_INT_RAW = ", SPI_OUT_TOTAL_EOF_INT_RAW, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_RAW_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_dma_int_raw_reg_t) == 4, "invalid size for ESP32 spi_dma_int_raw_reg_t"); @@ -413,6 +723,19 @@ struct spi_dma_int_st_reg_t { uint32_t SPI_OUT_EOF_INT_ST : 1; // read-only uint32_t SPI_OUT_TOTAL_EOF_INT_ST : 1; // read-only uint32_t reserved1 : 23; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_INLINK_DSCR_EMPTY_INT_ST = ", SPI_INLINK_DSCR_EMPTY_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_OUTLINK_DSCR_ERROR_INT_ST = ", SPI_OUTLINK_DSCR_ERROR_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_INLINK_DSCR_ERROR_INT_ST = ", SPI_INLINK_DSCR_ERROR_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_IN_DONE_INT_ST = ", SPI_IN_DONE_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_IN_ERR_EOF_INT_ST = ", SPI_IN_ERR_EOF_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_IN_SUC_EOF_INT_ST = ", SPI_IN_SUC_EOF_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_OUT_DONE_INT_ST = ", SPI_OUT_DONE_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_OUT_EOF_INT_ST = ", SPI_OUT_EOF_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.SPI_OUT_TOTAL_EOF_INT_ST = ", SPI_OUT_TOTAL_EOF_INT_ST, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_ST_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_dma_int_st_reg_t) == 4, "invalid size for ESP32 spi_dma_int_st_reg_t"); @@ -427,6 +750,19 @@ struct spi_dma_int_clr_reg_t { uint32_t SPI_OUT_EOF_INT_CLR : 1; uint32_t SPI_OUT_TOTAL_EOF_INT_CLR : 1; uint32_t reserved1 : 23; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_INLINK_DSCR_EMPTY_INT_CLR = ", SPI_INLINK_DSCR_EMPTY_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_OUTLINK_DSCR_ERROR_INT_CLR = ", SPI_OUTLINK_DSCR_ERROR_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_INLINK_DSCR_ERROR_INT_CLR = ", SPI_INLINK_DSCR_ERROR_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_IN_DONE_INT_CLR = ", SPI_IN_DONE_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_IN_ERR_EOF_INT_CLR = ", SPI_IN_ERR_EOF_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_IN_SUC_EOF_INT_CLR = ", SPI_IN_SUC_EOF_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_OUT_DONE_INT_CLR = ", SPI_OUT_DONE_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_OUT_EOF_INT_CLR = ", SPI_OUT_EOF_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.SPI_OUT_TOTAL_EOF_INT_CLR = ", SPI_OUT_TOTAL_EOF_INT_CLR, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_INT_CLR_REG.reserved1 = ", reserved1, ";"); + } }; static_assert(sizeof(spi_dma_int_clr_reg_t) == 4, "invalid size for ESP32 spi_dma_int_clr_reg_t"); @@ -435,6 +771,13 @@ struct spi_dma_rstatus_reg_t { uint32_t reserved1 : 10; uint32_t TX_FIFO_FULL : 1; // read-only uint32_t TX_FIFO_EMPTY : 1; // read-only + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_RSTATUS_REG.TX_DES_ADDRESS = ", TX_DES_ADDRESS, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_RSTATUS_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_RSTATUS_REG.TX_FIFO_FULL = ", TX_FIFO_FULL, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_RSTATUS_REG.TX_FIFO_EMPTY = ", TX_FIFO_EMPTY, ";"); + } }; static_assert(sizeof(spi_dma_rstatus_reg_t) == 4, "invalid size for ESP32 spi_dma_rstatus_reg_t"); @@ -443,58 +786,114 @@ struct spi_dma_tstatus_reg_t { uint32_t reserved1 : 10; uint32_t RX_FIFO_FULL : 1; // read-only uint32_t RX_FIFO_EMPTY : 1; // read-only + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_DMA_TSTATUS_REG.RX_DES_ADDRESS = ", RX_DES_ADDRESS, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_TSTATUS_REG.reserved1 = ", reserved1, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_TSTATUS_REG.RX_FIFO_FULL = ", RX_FIFO_FULL, ";"); + SERIAL_ECHOLNPGM("SPI_DMA_TSTATUS_REG.RX_FIFO_EMPTY = ", RX_FIFO_EMPTY, ";"); + } }; static_assert(sizeof(spi_dma_tstatus_reg_t) == 4, "invalid size for ESP32 spi_dma_tstatus_reg_t"); struct spi_dev_t { - volatile spi_cmd_reg_t SPI_CMD_REG; - volatile uint32_t SPI_ADDR_REG; - volatile spi_ctrl_reg_t SPI_CTRL_REG; - volatile uint32_t SPI_CTRL1_REG; - volatile uint32_t SPI_RD_STATUS_REG; - volatile spi_ctrl2_reg_t SPI_CTRL2_REG; - volatile spi_clock_reg_t SPI_CLOCK_REG; - volatile spi_user_reg_t SPI_USER_REG; - volatile spi_user1_reg_t SPI_USER1_REG; - volatile spi_user2_reg_t SPI_USER2_REG; - volatile spi_mosi_dlen_reg_t SPI_MOSI_DLEN_REG; - volatile spi_miso_dlen_reg_t SPI_MISO_DLEN_REG; - volatile uint32_t SPI_SLV_WR_STATUS_REG; - volatile spi_pin_reg_t SPI_PIN_REG; - volatile spi_slave_reg_t SPI_SLAVE_REG; - volatile spi_slave1_reg_t SPI_SLAVE1_REG; - volatile spi_slave2_reg_t SPI_SLAVE2_REG; - volatile spi_slave3_reg_t SPI_SLAVE3_REG; - volatile spi_slv_wrbuf_dlen_reg_t SPI_SLV_WRBUF_DLEN_REG; - volatile spi_slv_rdbuf_dlen_reg_t SPI_SLV_RDBUF_DLEN_REG; - volatile uint8_t pad1[0x14]; - volatile spi_slv_rd_bit_reg_t SPI_SLV_RD_BIT_REG; - volatile uint8_t pad2[0x18]; - volatile uint32_t SPI_W_REG[16]; - volatile uint32_t SPI_TX_CRC_REG; - volatile uint8_t pad3[0x34]; - volatile spi_ext2_reg_t SPI_EXT2_REG; - volatile uint8_t pad4[4]; - volatile spi_dma_conf_reg_t SPI_DMA_CONF_REG; - volatile spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; - volatile spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; - volatile spi_dma_status_reg_t SPI_DMA_STATUS_REG; - volatile spi_dma_int_ena_reg_t SPI_DMA_INT_ENA_REG; - volatile spi_dma_int_raw_reg_t SPI_DMA_INT_RAW_REG; - volatile spi_dma_int_st_reg_t SPI_DMA_INT_ST_REG; - volatile spi_dma_int_clr_reg_t SPI_DMA_INT_CLR_REG; - volatile const uint32_t SPI_IN_ERR_EOF_DES_ADDR_REG; - volatile const uint32_t SPI_IN_SUC_EOF_DES_ADDR_REG; - volatile const uint32_t SPI_INLINK_DSCR_REG; - volatile const uint32_t SPI_INLINK_DSCR_BF0_REG; - volatile const uint32_t SPI_INLINK_DSCR_BF1_REG; - volatile const uint32_t SPI_OUT_EOF_BFR_DES_ADDR_REG; - volatile const uint32_t SPI_OUT_EOF_DES_ADDR_REG; - volatile const uint32_t SPI_OUTLINK_DSCR_REG; - volatile const uint32_t SPI_OUTLINK_DSCR_BF0_REG; - volatile const uint32_t SPI_OUTLINK_DSCR_BF1_REG; - volatile spi_dma_rstatus_reg_t SPI_DMA_RSTATUS_REG; - volatile spi_dma_tstatus_reg_t SPI_DMA_TSTATUS_REG; + spi_cmd_reg_t SPI_CMD_REG; + uint32_t SPI_ADDR_REG; + spi_ctrl_reg_t SPI_CTRL_REG; + spi_ctrl1_reg_t SPI_CTRL1_REG; + uint32_t SPI_RD_STATUS_REG; + spi_ctrl2_reg_t SPI_CTRL2_REG; + spi_clock_reg_t SPI_CLOCK_REG; + spi_user_reg_t SPI_USER_REG; + spi_user1_reg_t SPI_USER1_REG; + spi_user2_reg_t SPI_USER2_REG; + spi_mosi_dlen_reg_t SPI_MOSI_DLEN_REG; + spi_miso_dlen_reg_t SPI_MISO_DLEN_REG; + uint32_t SPI_SLV_WR_STATUS_REG; + spi_pin_reg_t SPI_PIN_REG; + spi_slave_reg_t SPI_SLAVE_REG; + spi_slave1_reg_t SPI_SLAVE1_REG; + spi_slave2_reg_t SPI_SLAVE2_REG; + spi_slave3_reg_t SPI_SLAVE3_REG; + spi_slv_wrbuf_dlen_reg_t SPI_SLV_WRBUF_DLEN_REG; + spi_slv_rdbuf_dlen_reg_t SPI_SLV_RDBUF_DLEN_REG; + uint8_t pad1[0x14]; + spi_slv_rd_bit_reg_t SPI_SLV_RD_BIT_REG; + uint8_t pad2[0x18]; + uint32_t SPI_W_REG[16]; + uint32_t SPI_TX_CRC_REG; + uint8_t pad3[0x34]; + spi_ext2_reg_t SPI_EXT2_REG; + uint8_t pad4[4]; + spi_dma_conf_reg_t SPI_DMA_CONF_REG; + spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; + spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; + spi_dma_status_reg_t SPI_DMA_STATUS_REG; + spi_dma_int_ena_reg_t SPI_DMA_INT_ENA_REG; + spi_dma_int_raw_reg_t SPI_DMA_INT_RAW_REG; + spi_dma_int_st_reg_t SPI_DMA_INT_ST_REG; + spi_dma_int_clr_reg_t SPI_DMA_INT_CLR_REG; + const uint32_t SPI_IN_ERR_EOF_DES_ADDR_REG; + const uint32_t SPI_IN_SUC_EOF_DES_ADDR_REG; + const uint32_t SPI_INLINK_DSCR_REG; + const uint32_t SPI_INLINK_DSCR_BF0_REG; + const uint32_t SPI_INLINK_DSCR_BF1_REG; + const uint32_t SPI_OUT_EOF_BFR_DES_ADDR_REG; + const uint32_t SPI_OUT_EOF_DES_ADDR_REG; + const uint32_t SPI_OUTLINK_DSCR_REG; + const uint32_t SPI_OUTLINK_DSCR_BF0_REG; + const uint32_t SPI_OUTLINK_DSCR_BF1_REG; + spi_dma_rstatus_reg_t SPI_DMA_RSTATUS_REG; + spi_dma_tstatus_reg_t SPI_DMA_TSTATUS_REG; + + void serial_dump() volatile { + SERIAL_ECHOLNPGM("SPI_ADDR_REG = ", SPI_ADDR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_RD_STATUS_REG = ", SPI_RD_STATUS_REG, ";"); + SERIAL_ECHOLNPGM("SPI_SLV_WR_STATUS_REG = ", SPI_SLV_WR_STATUS_REG, ";"); + SERIAL_ECHOLNPGM("SPI_TX_CRC_REG = ", SPI_TX_CRC_REG, ";"); + + SPI_CMD_REG.serial_dump(); + SPI_CTRL_REG.serial_dump(); + SPI_CTRL1_REG.serial_dump(); + SPI_CTRL2_REG.serial_dump(); + SPI_CLOCK_REG.serial_dump(); + SPI_USER_REG.serial_dump(); + SPI_USER1_REG.serial_dump(); + SPI_USER2_REG.serial_dump(); + SPI_MOSI_DLEN_REG.serial_dump(); + SPI_MISO_DLEN_REG.serial_dump(); + SPI_PIN_REG.serial_dump(); + SPI_SLAVE_REG.serial_dump(); + SPI_SLAVE1_REG.serial_dump(); + SPI_SLAVE2_REG.serial_dump(); + SPI_SLAVE3_REG.serial_dump(); + SPI_SLV_WRBUF_DLEN_REG.serial_dump(); + SPI_SLV_RDBUF_DLEN_REG.serial_dump(); + SPI_SLV_RD_BIT_REG.serial_dump(); + SPI_EXT2_REG.serial_dump(); + SPI_DMA_CONF_REG.serial_dump(); + SPI_DMA_OUT_LINK_REG.serial_dump(); + SPI_DMA_IN_LINK_REG.serial_dump(); + SPI_DMA_STATUS_REG.serial_dump(); + SPI_DMA_INT_ENA_REG.serial_dump(); + SPI_DMA_INT_RAW_REG.serial_dump(); + //SPI_DMA_INT_ST_REG.serial_dump(); + //SPI_DMA_INT_CLR_REG.serial_dump(); + + SERIAL_ECHOLNPGM("SPI_IN_ERR_EOF_DES_ADDR_REG = ", SPI_IN_ERR_EOF_DES_ADDR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_IN_SUC_EOF_DES_ADDR_REG = ", SPI_IN_SUC_EOF_DES_ADDR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_INLINK_DSCR_REG = ", SPI_INLINK_DSCR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_INLINK_DSCR_BF0_REG = ", SPI_INLINK_DSCR_BF0_REG, ";"); + SERIAL_ECHOLNPGM("SPI_INLINK_DSCR_BF1_REG = ", SPI_INLINK_DSCR_BF1_REG, ";"); + SERIAL_ECHOLNPGM("SPI_OUT_EOF_BFR_DES_ADDR_REG = ", SPI_OUT_EOF_BFR_DES_ADDR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_OUT_EOF_DES_ADDR_REG = ", SPI_OUT_EOF_DES_ADDR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_OUTLINK_DSCR_REG = ", SPI_OUTLINK_DSCR_REG, ";"); + SERIAL_ECHOLNPGM("SPI_OUTLINK_DSCR_BF0_REG = ", SPI_OUTLINK_DSCR_BF0_REG, ";"); + SERIAL_ECHOLNPGM("SPI_OUTLINK_DSCR_BF1_REG = ", SPI_OUTLINK_DSCR_BF1_REG, ";"); + + SPI_DMA_RSTATUS_REG.serial_dump(); + SPI_DMA_TSTATUS_REG.serial_dump(); + } }; static_assert(offsetof(spi_dev_t, SPI_CLOCK_REG) == 0x18, "invalid ESP32 offsetof SPI_CLOCK_REG"); static_assert(offsetof(spi_dev_t, SPI_W_REG[0]) == 0x80, "invalid ESP32 offsetof SPI_W_REG"); @@ -502,17 +901,17 @@ static_assert(offsetof(spi_dev_t, SPI_EXT2_REG) == 0xF8, "invalid ESP32 offsetof static_assert(sizeof(spi_dev_t) == 0x150, "wrong formatting of ESP32 spi_dev_t!"); #ifdef HALSPI_ESP32_ENABLE_INTERNBUS -static spi_dev_t& SPI0 = *(spi_dev_t*)0x3FF43000; // shares signals with SPI1 (USAGE DISALLOWED) -static spi_dev_t& SPI1 = *(spi_dev_t*)0x3FF42000; // (USAGE DISALLOWED) +__ESP32_DEFREG(spi_dev_t, SPI0, 0x3FF43000); // shares signals with SPI1 (USAGE DISALLOWED) +__ESP32_DEFREG(spi_dev_t, SPI1, 0x3FF42000); // (USAGE DISALLOWED) #endif -static spi_dev_t& SPI2 = *(spi_dev_t*)0x3FF64000; // HSPI -static spi_dev_t& SPI3 = *(spi_dev_t*)0x3FF65000; // VSPI +__ESP32_DEFREG(spi_dev_t, SPI2, 0x3FF64000); // HSPI +__ESP32_DEFREG(spi_dev_t, SPI3, 0x3FF65000); // VSPI #define _SPI_DEFAULT_BUS 2 #define __SPI_BUSOBJ(IDX) (SPI##IDX) #define _SPI_BUSOBJ(IDX) (__SPI_BUSOBJ(IDX)) -inline spi_dev_t& SPIGetBusFromIndex(uint8_t idx) { +inline volatile spi_dev_t& SPIGetBusFromIndex(uint8_t idx) { switch(idx) { #ifdef HALSPI_ESP32_ENABLE_INTERNBUS case 0: return SPI0; @@ -524,7 +923,7 @@ inline spi_dev_t& SPIGetBusFromIndex(uint8_t idx) { } } -inline uint8_t SPIGetBusIndex(spi_dev_t& SPI) { +inline uint8_t SPIGetBusIndex(volatile spi_dev_t& SPI) { #ifdef HALSPI_ESP32_ENABLE_INTERNBUS if (&SPI == &SPI0) return 0; else if (&SPI == &SPI1) return 1; @@ -807,8 +1206,8 @@ struct dport_perip_rst_en_reg_t { }; static_assert(sizeof(dport_perip_rst_en_reg_t) == 4, "invalid size of ESP32 dport_perip_rst_en_reg_t"); -static dport_perip_clk_en_reg_t& DPORT_PERIP_CLK_EN_REG = *(dport_perip_clk_en_reg_t*)0x3FF000C0; -static dport_perip_rst_en_reg_t& DPORT_PERIP_RST_EN_REG = *(dport_perip_rst_en_reg_t*)0x3FF000C4; +__ESP32_DEFREG(dport_perip_clk_en_reg_t, DPORT_PERIP_CLK_EN_REG, 0x3FF000C0); +__ESP32_DEFREG(dport_perip_rst_en_reg_t, DPORT_PERIP_RST_EN_REG, 0x3FF000C4); #define DPORT_SPI_DMA_CHAN_SEL_NONE 0 #define DPORT_SPI_DMA_CHAN_SEL_CHAN1 1 @@ -822,7 +1221,7 @@ struct dport_spi_dma_chan_sel_reg_t { }; static_assert(sizeof(dport_spi_dma_chan_sel_reg_t) == sizeof(uint32_t), "invalid size of ESP32 dport_spi_dma_chan_sel_reg_t"); -static dport_spi_dma_chan_sel_reg_t& DPORT_SPI_DMA_CHAN_SEL_REG = *(dport_spi_dma_chan_sel_reg_t*)0x3FF005A8; +__ESP32_DEFREG(dport_spi_dma_chan_sel_reg_t, DPORT_SPI_DMA_CHAN_SEL_REG, 0x3FF005A8); #if 0 @@ -832,7 +1231,7 @@ struct dport_cpu_per_conf_reg_t { }; static_assert(sizeof(dport_cpu_per_conf_reg_t) == 4, "invalid size of ESP32 dport_cpu_per_conf_reg_t"); -static dport_cpu_per_conf_reg_t& DPORT_CPU_PER_CONF_REG = *(dport_cpu_per_conf_reg_t*)0x3FF0003C; +__ESP32_DEFREG(dport_cpu_per_conf_reg_t, DPORT_CPU_PER_CONF_REG, 0x3FF0003C); #define RTC_CNTL_SOC_CLK_XTL 0 #define RTC_CNTL_SOC_CLK_PLL 1 @@ -859,7 +1258,7 @@ struct rtc_cntl_clk_conf_reg_t { }; static_assert(sizeof(rtc_cntl_clk_conf_reg_t) == 4, "invalid size of ESP32 rtc_cntl_clk_conf_reg_t"); -static rtc_cntl_clk_conf_reg_t& RTC_CNTL_CLK_CONF_REG = *(rtc_cntl_clk_conf_reg_t*)0x3FF48070; +__ESP32_DEFREG(rtc_cntl_clk_conf_reg_t, RTC_CNTL_CLK_CONF_REG, 0x3FF48070); struct syscon_conf_reg_t { uint32_t SYSCON_PRE_DIV_CNT : 10; @@ -871,9 +1270,9 @@ struct syscon_conf_reg_t { }; // Undocumented. -static syscon_conf_reg_t& SYSCON_CONF_REG = *(syscon_conf_reg_t*)0x3FF66000; +__ESP32_DEFREG(syscon_conf_reg_t, SYSCON_CONF_REG, 0x3FF66000); -#endif //0 +#endif // You can transfer up to 64bytes in one burst using default SPI without DMA on the ESP32. @@ -889,7 +1288,7 @@ struct clkcnt_res_t { } }; -static void SPIConfigureClock(spi_dev_t& SPI, int clkMode, bool is_direct_io, const clkcnt_res_t& clkdiv) { +static void SPIConfigureClock(volatile spi_dev_t& SPI, int clkMode, bool is_direct_io, const clkcnt_res_t& clkdiv) { if (clkMode == SPI_CLKMODE_0) { SPI.SPI_PIN_REG.SPI_CK_IDLE_EDGE = 0; SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 0; @@ -907,12 +1306,15 @@ static void SPIConfigureClock(spi_dev_t& SPI, int clkMode, bool is_direct_io, co SPI.SPI_USER_REG.SPI_CK_OUT_EDGE = 0; } - SPI.SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = clkdiv.sysclock; - SPI.SPI_CLOCK_REG.SPI_CLKDIV_PRE = clkdiv.pre; - SPI.SPI_CLOCK_REG.SPI_CLKCNT_N = clkdiv.n; - SPI.SPI_CLOCK_REG.SPI_CLKCNT_L = clkdiv.l; - SPI.SPI_CLOCK_REG.SPI_CLKCNT_H = clkdiv.h; + spi_clock_reg_t _SPI_CLOCK_REG; + _SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = clkdiv.sysclock; + _SPI_CLOCK_REG.SPI_CLKDIV_PRE = clkdiv.pre; + _SPI_CLOCK_REG.SPI_CLKCNT_N = clkdiv.n; + _SPI_CLOCK_REG.SPI_CLKCNT_L = clkdiv.l; + _SPI_CLOCK_REG.SPI_CLKCNT_H = clkdiv.h; + dwrite(SPI.SPI_CLOCK_REG, _SPI_CLOCK_REG); +#ifndef HALSPI_ESP32_DISABLE_ADV_DELAYCONF uint32_t apbFreqDiv = clkdiv.GetFrequencyDivider(); if (is_direct_io) { @@ -949,20 +1351,32 @@ static void SPIConfigureClock(spi_dev_t& SPI, int clkMode, bool is_direct_io, co SPI.SPI_USER_REG.SPI_USR_DUMMY = 0; } } +#else + SPI.SPI_USER_REG.SPI_USR_DUMMY = 0; + SPI.SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = 0; + SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_MODE = 0; +#endif SPI.SPI_CTRL2_REG.SPI_MISO_DELAY_NUM = 0; SPI.SPI_CTRL2_REG.SPI_MOSI_DELAY_MODE = 0; SPI.SPI_CTRL2_REG.SPI_MOSI_DELAY_NUM = 0; } +#if 0 static const uint8_t _spi_clkcnt_n_primes[] = { 2, 3, 4, 5, 11, 13, 17, 19, 23, 29, 31, 37, 41, 43, 47, 53, 59, 61 }; +#endif -template -inline numberType CEIL_DIV(numberType A, numberType B) { - numberType rem = ( A % B ); - return ( rem == 0 ? (A/B) : (A/B+1) ); +template +inline auto DIST(T1 a, T2 b) noexcept -> decltype(a-b) +{ + if (a < b) { + return b - a; + } + else { + return a - b; + } } // see page 121 of ESP32 technical reference manual (GP-SPI Clock Control) @@ -987,7 +1401,7 @@ inline clkcnt_res_t SPIApproximateClockDivider(uint32_t maxClockFreq, uint32_t s // spibasefreq = f_apb uint32_t approx_div = CEIL_DIV(spibasefreq, maxClockFreq); // pre + 1 - if (approx_div <= (1<<13)) { // 2^14 + if (approx_div <= (1<<13)) { // 2^13 res.pre = (approx_div - 1); res.n = 1; // n needs to be at least 2 so we have one LOW and one HIGH pulse (this detail is found nowhere in the ESP32 docs) goto finalize; @@ -1001,7 +1415,7 @@ inline clkcnt_res_t SPIApproximateClockDivider(uint32_t maxClockFreq, uint32_t s for (uint8_t prime : _spi_clkcnt_n_primes) { uint32_t primediv = (approx_div / prime); uint32_t approx_freqdiv = (primediv * approx_div); - if (approx_freqdiv <= (1<<6)*(1<<13)) { // (2^7 * 2^14) + if (approx_freqdiv <= (1<<6)*(1<<13)) { // (2^6 * 2^13) if (found_best_approx_prime == false || (best_approx > approx_freqdiv)) { best_approx_prime = prime; best_approx = approx_freqdiv; @@ -1018,8 +1432,8 @@ inline clkcnt_res_t SPIApproximateClockDivider(uint32_t maxClockFreq, uint32_t s res.pre = (approx_div - 1); } finalize: - res.h = _MIN ( ((res.n+1) / 2), 1 ) - 1; - res.l = res.n; + res.h = 0u; + res.l = eir::Maximum( ((unsigned int)(res.n+1u) / 2u), 1u ) - 1u; return res; #else // Taken from the ArduinoCore ESP32 because the ESP32 clock documentation is VERY lacking! @@ -1068,184 +1482,111 @@ inline clkcnt_res_t SPIApproximateClockDivider(uint32_t maxClockFreq, uint32_t s reg.n = calN; reg.l = ((reg.n + 1) / 2); + calPre = ((int32_t)((spibasefreq / (reg.n + 1)) / maxClockFreq) - 1) + calPreVari; while(calPreVari++ <= 1) { - calPre = ((int32_t)((spibasefreq / (reg.n + 1)) / maxClockFreq) - 1) + calPreVari; + calPre++; if(calPre > (1<<13)-1) { reg.pre = (1<<13)-1; } else if(calPre <= 0) { reg.pre = 0; } else { - reg.pre = calPre; + reg.pre = (uint32_t)calPre; } calFreq = (spibasefreq / reg.GetFrequencyDivider()); if(calFreq == maxClockFreq) { - bestReg = reg; - break; + return reg; } else if(calFreq < maxClockFreq) { - if(has_best_freq == false || (abs(maxClockFreq - calFreq) < abs(maxClockFreq - bestFreq))) { + if(has_best_freq == false || ((maxClockFreq - calFreq) < (maxClockFreq - bestFreq))) { bestFreq = calFreq; bestReg = reg; has_best_freq = true; } } } - if(calFreq == maxClockFreq) { - break; - } calN++; } return bestReg; #endif } -static void SPIConfigureBitOrder(spi_dev_t& SPI, int bitOrder) { +static void SPIConfigureBitOrder(volatile spi_dev_t& SPI, int bitOrder) { if (bitOrder == SPI_BITORDER_MSB) { - SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = 0; - SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = 0; + SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = _ESP32_BIT_ORDER_MSB; + SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = _ESP32_BIT_ORDER_MSB; } else { - SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = 1; - SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = 1; + SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER = _ESP32_BIT_ORDER_LSB; + SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER = _ESP32_BIT_ORDER_LSB; } } -inline uint16_t SPIGetWriteBufferSize(spi_dev_t& SPI) { - return ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 32 : 64 ); +inline uint16_t SPIGetWriteBufferSize(volatile spi_dev_t& SPI) { + return 64;//( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 32 : 64 ); } -template -inline uint8_t SPIGetSingleByteToTransferEx(spi_dev_t& SPI, numberType num, uint32_t byteIdx, bool notrevbits) { - using namespace ::bufmgmt; - -#ifdef HALSPI_DEBUG - if (GetNumberIndexFromTotalByteIndex (byteIdx) >= 1) return 0; -#endif - - return - GetByteFromNumber( - num, - GetLocalByteIndexFromTotalByteIndex (byteIdx), - notrevbits // reverse if MSBFIRST - ); +inline uint16_t SPIGetWriteBufferStartIndex(volatile spi_dev_t& SPI) { + return 0;//( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); } -template -inline uint8_t SPIGetSingleByteToTransfer(spi_dev_t& SPI, numberType num, uint32_t byteIdx) { - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); +template +inline void SPIPrepareWriteBitManager(volatile spi_dev_t& SPI, bitManType& bitman) noexcept { + bool wr_msbfirst = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == _ESP32_BIT_ORDER_MSB); - return SPIGetSingleByteToTransferEx(SPI, num, byteIdx, notrevbits); -} - -inline void SPIWriteSingleByteToTransferEx(spi_dev_t& SPI, uint8_t byteval, uint32_t byteIdx, uint16_t start_num_idx) { -#ifdef HALSPI_DEBUG - auto max_transfer_size = SPIGetWriteBufferSize(SPI); - - if (byteIdx >= max_transfer_size) return; -#endif - - using namespace ::bufmgmt; - - WriteByteToNumber( - SPI.SPI_W_REG[ start_num_idx + GetNumberIndexFromTotalByteIndex ( byteIdx ) ], - GetLocalByteIndexFromTotalByteIndex ( byteIdx ), - byteval, - true + bitman.SetDefaultStorageProperty( + wr_msbfirst ? eir::endian::eSpecificEndian::BIG_ENDIAN : eir::endian::eSpecificEndian::LITTLE_ENDIAN, + false ); } -inline void SPIWriteSingleByteToTransfer(spi_dev_t& SPI, uint8_t byteval, uint32_t byteIdx) { - uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); +template +inline void SPIPrepareReadBitManager(volatile spi_dev_t& SPI, bitManType& bitman) noexcept { + bool rd_msbfirst = (SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER == _ESP32_BIT_ORDER_MSB); - return SPIWriteSingleByteToTransferEx(SPI, byteval, byteIdx, start_num_idx); + bitman.SetDefaultStorageProperty( + rd_msbfirst ? eir::endian::eSpecificEndian::BIG_ENDIAN : eir::endian::eSpecificEndian::LITTLE_ENDIAN, + false + ); } template -inline void SPIWriteDataToTransferEx( - spi_dev_t& SPI, const numberType *buf, uint32_t cnt_bytes, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, +inline void SPIWriteDataToTransferIsolated( + volatile spi_dev_t& SPI, const numberType *buf, uint16_t cnt, uint32_t srcByteStartIdx, uint16_t& cntSentBytes_out ) { - uint16_t total_bytes_written = 0; + uint16_t start_num_idx = SPIGetWriteBufferStartIndex(SPI); - using namespace ::bufmgmt; + esp32BitManager src_bitman( buf, cnt ); - auto max_transfer_size = SPIGetWriteBufferSize(SPI); - uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); + SPIPrepareWriteBitManager( SPI, src_bitman ); - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); + eir::BitNumberIteratorForStruct src_iter; + src_iter.addBytes( srcByteStartIdx ); + src_bitman.SetIterator( src_iter ); - for (uint16_t txidx = 0; txidx < _MIN (cnt_bytes - srcByteStartIdx, max_transfer_size - dstByteStartIdx); txidx++) { - uint8_t byteval = - GetByteFromNumber( - buf[ GetNumberIndexFromTotalByteIndex ( txidx + srcByteStartIdx ) ], - GetLocalByteIndexFromTotalByteIndex ( txidx + srcByteStartIdx ), - notrevbits // reverse if MSBFIRST - ); - - WriteByteToNumber( - SPI.SPI_W_REG[ start_num_idx + GetNumberIndexFromTotalByteIndex ( txidx + dstByteStartIdx ) ], - GetLocalByteIndexFromTotalByteIndex ( txidx + dstByteStartIdx ), - byteval, - true - ); - - total_bytes_written++; + eir::BitNumberIteratorForStruct txiter( start_num_idx ); + while ( src_bitman.IsAtEnd() == false && txiter.getNumberOffset() < COUNT(SPI.SPI_W_REG) ) { + uint32_t txitem = 0u; + uint32_t n = txiter.getNumberOffset(); + src_bitman.FetchSingle( txitem, txiter ); + SPI.SPI_W_REG[n] = txitem; } - cntSentBytes_out = total_bytes_written; -} - -template -inline void SPIWriteDataToTransfer( - spi_dev_t& SPI, const numberType *buf, uint16_t cnt, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, - uint16_t& cntSentBytes_out -) { - return SPIWriteDataToTransferEx(SPI, buf, cnt * sizeof(numberType), srcByteStartIdx, dstByteStartIdx, cntSentBytes_out); + cntSentBytes_out = ( txiter.getTotalByteOffset() ); } -inline uint16_t SPIGetReadBufferSize(spi_dev_t& SPI) { - return ( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 32 : 64 ); +inline uint16_t SPIGetReadBufferSize(volatile spi_dev_t& SPI) { + return 64;//( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 32 : 64 ); } -template -inline void SPIReadDataFromTransfer( - spi_dev_t& SPI, numberType *buf, uint16_t cnt, uint32_t srcByteStartIdx, uint32_t dstByteStartIdx, - uint16_t& cntReadBytes_out -) { - uint16_t total_bytes_read = 0; - - uint16_t bufNumStartIdx = ( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 8 : 0 ); - uint16_t bufByteLen = SPIGetReadBufferSize(SPI); - - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER == 1); // reverse if MSBFIRST - - using namespace ::bufmgmt; - - for (uint16_t txidx = 0; txidx < _MIN ((uint32_t)cnt*sizeof(numberType) - srcByteStartIdx, bufByteLen - dstByteStartIdx); txidx++) { - uint8_t byteval = - GetByteFromNumber( - SPI.SPI_W_REG[ GetNumberIndexFromTotalByteIndex (txidx + dstByteStartIdx) ], - GetLocalByteIndexFromTotalByteIndex (txidx + dstByteStartIdx), - true - ); - - WriteByteToNumber( - buf[ bufNumStartIdx + GetNumberIndexFromTotalByteIndex (txidx + srcByteStartIdx) ], - GetLocalByteIndexFromTotalByteIndex (txidx + srcByteStartIdx), - byteval, - notrevbits - ); - - total_bytes_read++; - } - - cntReadBytes_out = total_bytes_read; +inline uint16_t SPIGetReadBufferStartIndex(volatile spi_dev_t& SPI) { + return 0;//( SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART == 1 ? 8 : 0 ); } -static void SPITransaction(spi_dev_t& SPI, uint32_t txcount) { - if (txcount == 0) return; +static void SPITransaction(volatile spi_dev_t& SPI, uint32_t txcount_bytes) { + if (txcount_bytes == 0) return; - uint32_t txcount_bits = ( txcount * 8 ); + uint32_t txcount_bits = ( txcount_bytes * 8u ); if (SPI.SPI_USER_REG.SPI_USR_MOSI == true) { SPI.SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = txcount_bits - 1; @@ -1263,12 +1604,12 @@ static void SPITransaction(spi_dev_t& SPI, uint32_t txcount) { } } -static void SPIResetBus(spi_dev_t& SPI) { +static void SPIResetBus(volatile spi_dev_t& SPI) { spi_cmd_reg_t SPI_CMD_REG; SPI_CMD_REG.reserved1 = 0; SPI_CMD_REG.SPI_USR = 0; SPI_CMD_REG.reserved2 = 0; - (spi_cmd_reg_t&)SPI.SPI_CMD_REG = SPI_CMD_REG; + dwrite(SPI.SPI_CMD_REG, SPI_CMD_REG); SPI.SPI_ADDR_REG = 0; @@ -1282,12 +1623,16 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_CTRL_REG.reserved3 = 0; SPI_CTRL_REG.SPI_FREAD_DIO = 0; SPI_CTRL_REG.SPI_FREAD_QIO = 0; - SPI_CTRL_REG.SPI_RD_BIT_ORDER = 0; - SPI_CTRL_REG.SPI_WR_BIT_ORDER = 0; + SPI_CTRL_REG.SPI_RD_BIT_ORDER = _ESP32_BIT_ORDER_MSB; + SPI_CTRL_REG.SPI_WR_BIT_ORDER = _ESP32_BIT_ORDER_MSB; SPI_CTRL_REG.reserved4 = 0; - (spi_ctrl_reg_t&)SPI.SPI_CTRL_REG = SPI_CTRL_REG; + dwrite(SPI.SPI_CTRL_REG, SPI_CTRL_REG); + + spi_ctrl1_reg_t SPI_CTRL1_REG; + SPI_CTRL1_REG.reserved1 = 0; + SPI_CTRL1_REG.SPI_CS_HOLD_DELAY = 5; + dwrite(SPI.SPI_CTRL1_REG, SPI_CTRL1_REG); - SPI.SPI_CTRL1_REG = 0; SPI.SPI_RD_STATUS_REG = 0; spi_ctrl2_reg_t SPI_CTRL2_REG; @@ -1301,7 +1646,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_CTRL2_REG.SPI_MOSI_DELAY_NUM = 0; SPI_CTRL2_REG.SPI_CS_DELAY_MODE = 0; SPI_CTRL2_REG.SPI_CS_DELAY_NUM = 0; - (spi_ctrl2_reg_t&)SPI.SPI_CTRL2_REG = SPI_CTRL2_REG; + dwrite(SPI.SPI_CTRL2_REG, SPI_CTRL2_REG); spi_clock_reg_t SPI_CLOCK_REG; SPI_CLOCK_REG.SPI_CLKCNT_L = 3; @@ -1309,7 +1654,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_CLOCK_REG.SPI_CLKCNT_N = 3; SPI_CLOCK_REG.SPI_CLKDIV_PRE = 0; SPI_CLOCK_REG.SPI_CLK_EQU_SYSCLK = 1; - (spi_clock_reg_t&)SPI.SPI_CLOCK_REG = SPI_CLOCK_REG; + dwrite(SPI.SPI_CLOCK_REG, SPI_CLOCK_REG); spi_user_reg_t SPI_USER_REG; SPI_USER_REG.SPI_DOUTDIN = 0; @@ -1335,7 +1680,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_USER_REG.SPI_USR_DUMMY = 0; SPI_USER_REG.SPI_USR_ADDR = 0; SPI_USER_REG.SPI_USR_COMMAND = 1; - (spi_user_reg_t&)SPI.SPI_USER_REG = SPI_USER_REG; + dwrite(SPI.SPI_USER_REG, SPI_USER_REG); SPI.SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = 0; @@ -1343,17 +1688,17 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_USER2_REG.SPI_USR_COMMAND_VALUE = 0; SPI_USER2_REG.reserved1 = 0; SPI_USER2_REG.SPI_USR_COMMAND_BITLEN = 7; - (spi_user2_reg_t&)SPI.SPI_USER2_REG = SPI_USER2_REG; + dwrite(SPI.SPI_USER2_REG, SPI_USER2_REG); spi_mosi_dlen_reg_t SPI_MOSI_DLEN_REG; SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = 0; SPI_MOSI_DLEN_REG.reserved1 = 0; - (spi_mosi_dlen_reg_t&)SPI.SPI_MOSI_DLEN_REG = SPI_MOSI_DLEN_REG; + dwrite(SPI.SPI_MOSI_DLEN_REG, SPI_MOSI_DLEN_REG); spi_miso_dlen_reg_t SPI_MISO_DLEN_REG; SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = 0; SPI_MISO_DLEN_REG.reserved1 = 0; - (spi_miso_dlen_reg_t&)SPI.SPI_MISO_DLEN_REG = SPI_MISO_DLEN_REG; + dwrite(SPI.SPI_MISO_DLEN_REG, SPI_MISO_DLEN_REG); SPI.SPI_SLV_WR_STATUS_REG = 0; @@ -1370,7 +1715,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_PIN_REG.SPI_CK_IDLE_EDGE = 0; SPI_PIN_REG.SPI_CS_KEEP_ACTIVE = 0; SPI_PIN_REG.reserved4 = 0; - (spi_pin_reg_t&)SPI.SPI_PIN_REG = SPI_PIN_REG; + dwrite(SPI.SPI_PIN_REG, SPI_PIN_REG); spi_slave_reg_t SPI_SLAVE_REG; SPI_SLAVE_REG.SPI_SLV_RD_BUF_DONE = 0; @@ -1393,7 +1738,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_SLAVE_REG.SPI_SLV_WR_RD_BUF_EN = 0; SPI_SLAVE_REG.SPI_SLAVE_MODE = 0; SPI_SLAVE_REG.SPI_SYNC_RESET = 0; - (spi_slave_reg_t&)SPI.SPI_SLAVE_REG = SPI_SLAVE_REG; + dwrite(SPI.SPI_SLAVE_REG, SPI_SLAVE_REG); spi_slave1_reg_t SPI_SLAVE1_REG; SPI_SLAVE1_REG.SPI_SLV_RDBUF_DUMMY_EN = 0; @@ -1406,36 +1751,36 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_SLAVE1_REG.SPI_SLV_STATUS_READBACK = 1; SPI_SLAVE1_REG.SPI_SLV_STATUS_FAST_EN = 0; SPI_SLAVE1_REG.SPI_SLV_STATUS_BITLEN = 0; - (spi_slave1_reg_t&)SPI.SPI_SLAVE1_REG = SPI_SLAVE1_REG; + dwrite(SPI.SPI_SLAVE1_REG, SPI_SLAVE1_REG); spi_slave2_reg_t SPI_SLAVE2_REG; SPI_SLAVE2_REG.SPI_SLV_RDSTA_DUMMY_CYCLELEN = 0; SPI_SLAVE2_REG.SPI_SLV_WRSTA_DUMMY_CYCLELEN = 0; SPI_SLAVE2_REG.SPI_SLV_RDBUF_DUMMY_CYCLELEN = 0; SPI_SLAVE2_REG.SPI_SLV_WRBUF_DUMMY_CYCLELEN = 0; - (spi_slave2_reg_t&)SPI.SPI_SLAVE2_REG = SPI_SLAVE2_REG; + dwrite(SPI.SPI_SLAVE2_REG, SPI_SLAVE2_REG); spi_slave3_reg_t SPI_SLAVE3_REG; SPI_SLAVE3_REG.SPI_SLV_RDBUF_CMD_VALUE = 0; SPI_SLAVE3_REG.SPI_SLV_WRBUF_CMD_VALUE = 0; SPI_SLAVE3_REG.SPI_SLV_RDSTA_CMD_VALUE = 0; SPI_SLAVE3_REG.SPI_SLV_WRSTA_CMD_VALUE = 0; - (spi_slave3_reg_t&)SPI.SPI_SLAVE3_REG = SPI_SLAVE3_REG; + dwrite(SPI.SPI_SLAVE3_REG, SPI_SLAVE3_REG); spi_slv_wrbuf_dlen_reg_t SPI_SLV_WRBUF_DLEN_REG; SPI_SLV_WRBUF_DLEN_REG.SPI_SLV_WRBUF_DBITLEN = 0; SPI_SLV_WRBUF_DLEN_REG.reserved1 = 0; - (spi_slv_wrbuf_dlen_reg_t&)SPI.SPI_SLV_WRBUF_DLEN_REG = SPI_SLV_WRBUF_DLEN_REG; + dwrite(SPI.SPI_SLV_WRBUF_DLEN_REG, SPI_SLV_WRBUF_DLEN_REG); spi_slv_rdbuf_dlen_reg_t SPI_SLV_RDBUF_DLEN_REG; SPI_SLV_RDBUF_DLEN_REG.SPI_SLV_RDBUF_DBITLEN = 0; SPI_SLV_RDBUF_DLEN_REG.reserved1 = 0; - (spi_slv_rdbuf_dlen_reg_t&)SPI.SPI_SLV_RDBUF_DLEN_REG = SPI_SLV_RDBUF_DLEN_REG; + dwrite(SPI.SPI_SLV_RDBUF_DLEN_REG, SPI_SLV_RDBUF_DLEN_REG); spi_slv_rd_bit_reg_t SPI_SLV_RD_BIT_REG; SPI_SLV_RD_BIT_REG.SPI_SLV_RDATA_BIT = 0; SPI_SLV_RD_BIT_REG.reserved1 = 0; - (spi_slv_rd_bit_reg_t&)SPI.SPI_SLV_RD_BIT_REG = SPI_SLV_RD_BIT_REG; + dwrite(SPI.SPI_SLV_RD_BIT_REG, SPI_SLV_RD_BIT_REG); for (uint32_t n = 0; n < 16; n++) SPI.SPI_W_REG[n] = 0; @@ -1461,7 +1806,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_DMA_CONF_REG.SPI_DMA_TX_STOP = 0; SPI_DMA_CONF_REG.SPI_DMA_CONTINUE = 0; SPI_DMA_CONF_REG.reserved4 = 0; - (spi_dma_conf_reg_t&)SPI.SPI_DMA_CONF_REG = SPI_DMA_CONF_REG; + dwrite(SPI.SPI_DMA_CONF_REG, SPI_DMA_CONF_REG); spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = 0; @@ -1470,7 +1815,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = 0; SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_RESTART = 0; SPI_DMA_OUT_LINK_REG.reserved2 = 0; - (spi_dma_out_link_reg_t&)SPI.SPI_DMA_OUT_LINK_REG = SPI_DMA_OUT_LINK_REG; + dwrite(SPI.SPI_DMA_OUT_LINK_REG, SPI_DMA_OUT_LINK_REG); spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = 0; @@ -1480,7 +1825,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_DMA_IN_LINK_REG.SPI_INLINK_START = 0; SPI_DMA_IN_LINK_REG.SPI_INLINK_RESTART = 0; SPI_DMA_IN_LINK_REG.reserved2 = 0; - (spi_dma_in_link_reg_t&)SPI.SPI_DMA_IN_LINK_REG = SPI_DMA_IN_LINK_REG; + dwrite(SPI.SPI_DMA_IN_LINK_REG, SPI_DMA_IN_LINK_REG); SPI.SPI_DMA_STATUS_REG.reserved1 = 0; @@ -1495,7 +1840,7 @@ static void SPIResetBus(spi_dev_t& SPI) { SPI_DMA_INT_ENA_REG.SPI_OUT_EOF_INT_ENA = 0; SPI_DMA_INT_ENA_REG.SPI_OUT_TOTAL_EOF_INT_ENA = 0; SPI_DMA_INT_ENA_REG.reserved1 = 0; - (spi_dma_int_ena_reg_t&)SPI.SPI_DMA_INT_ENA_REG = SPI_DMA_INT_ENA_REG; + dwrite(SPI.SPI_DMA_INT_ENA_REG, SPI_DMA_INT_ENA_REG); SPI.SPI_DMA_INT_RAW_REG.reserved1 = 0; @@ -1508,7 +1853,7 @@ static void SPIResetBus(spi_dev_t& SPI) { #ifdef HAL_SPI_SUPPORTS_ASYNC struct spi_async_process_t { - spi_dev_t *current_spibus; + volatile spi_dev_t *current_spibus; const void *current_buffer; size_t curoff_bytes; size_t txlen; @@ -1538,21 +1883,21 @@ static void IRAM_ATTR spi_async_fill_buffer(volatile spi_async_process_t& proc) _spi_on_error(13); #endif - spi_dev_t& SPI = *proc.current_spibus; + auto& SPI = *proc.current_spibus; bool has_prepared_spibus = false; uint16_t writecnt_bytes = 0; if (proc.txunitsize == 1) { - SPIWriteDataToTransfer(SPI, (const uint8_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + SPIWriteDataToTransferIsolated(SPI, (const uint8_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, writecnt_bytes); has_prepared_spibus = true; } else if (proc.txunitsize == 2) { - SPIWriteDataToTransfer(SPI, (const uint16_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + SPIWriteDataToTransferIsolated(SPI, (const uint16_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, writecnt_bytes); has_prepared_spibus = true; } else if (proc.txunitsize == 4) { - SPIWriteDataToTransfer(SPI, (const uint32_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, 0, writecnt_bytes); + SPIWriteDataToTransferIsolated(SPI, (const uint32_t*)proc.current_buffer, proc.txlen, proc.curoff_bytes, writecnt_bytes); has_prepared_spibus = true; } @@ -1601,14 +1946,14 @@ static void IRAM_ATTR spi_async_fill_buffer(volatile spi_async_process_t& proc) } static void IRAM_ATTR spi_async_process_isr(void *ud, uint32_t spibusIdx) { - spi_dev_t& SPI = SPIGetBusFromIndex(spibusIdx); + auto& SPI = SPIGetBusFromIndex(spibusIdx); // Check the type of the triggered interrupt. if (SPI.SPI_SLAVE_REG.SPI_TRANS_DONE) { // Clear the interrupt. SPI.SPI_SLAVE_REG.SPI_TRANS_DONE = false; - volatile spi_async_process_t& proc = _current_spi_proc; + auto& proc = _current_spi_proc; if (proc.is_active && proc.current_spibus == &SPI) { // Is the SPI bus ready? Otherwise we could have a spurious interrupt call. @@ -1639,7 +1984,7 @@ static void IRAM_ATTR spi_async_process_isr_spibus3(void *ud) { spi_async_process_isr(ud, 3); } -static void SPIInstallAsync(spi_dev_t& SPI, intr_handle_t& handleOut) { +static void SPIInstallAsync(volatile spi_dev_t& SPI, intr_handle_t& handleOut) { int intsrc = -1; void (*inthandler)(void*) = nullptr; @@ -1688,8 +2033,8 @@ static void SPIAsyncInitialize() { SPIInstallAsync(SPI3, _spi3_interrupt); } -static void SPIStartRawAsync(spi_dev_t& SPI, const void *buf, uint32_t txlen, uint8_t txunitsize, void (*completeCallback)(void*), void *ud) { - volatile spi_async_process_t& proc = _current_spi_proc; +static void SPIStartRawAsync(volatile spi_dev_t& SPI, const void *buf, uint32_t txlen, uint8_t txunitsize, void (*completeCallback)(void*), void *ud) { + auto& proc = _current_spi_proc; spi_monitored_loop asyncw; while (proc.is_active) { asyncw.update(2); /* wait for any async process to conclude before we start another */ } @@ -1718,12 +2063,12 @@ static void SPIStartRawAsync(spi_dev_t& SPI, const void *buf, uint32_t txlen, ui static void SPIAbortRawAsync() { cli(); - volatile spi_async_process_t& proc = _current_spi_proc; + auto& proc = _current_spi_proc; if (proc.is_active) { proc.is_active = false; - spi_dev_t& SPI = *proc.current_spibus; + auto& SPI = *proc.current_spibus; SPI.SPI_SLAVE_REG.SPI_TRANS_INTEN = false; SPI.SPI_SLAVE_REG.SPI_TRANS_DONE = false; @@ -1743,14 +2088,15 @@ static void SPIAbortRawAsync() { // page 113 of ESP32 TRM. struct dma_descriptor_t { // Configuration bits. - volatile uint32_t size : 12; - volatile uint32_t length : 12; - volatile uint32_t reserved : 6; - volatile uint32_t eof : 1; - volatile uint32_t owner : 1; + uint32_t size : 12; + uint32_t length : 12; + uint32_t reserved : 5; + uint32_t sosf : 1; // start-of-sub-frame (undocumented) + uint32_t eof : 1; + uint32_t owner : 1; void *address; - dma_descriptor_t *next; + volatile dma_descriptor_t *next; }; static_assert(sizeof(dma_descriptor_t) == 12, "invalid size of ESP32 dma_descriptor_t"); @@ -1760,42 +2106,51 @@ static_assert(sizeof(dma_descriptor_t) == 12, "invalid size of ESP32 dma_descrip #endif #ifdef HALSPI_ESP32_STATIC_DMADESCS -static dma_descriptor_t _usable_dma_descs_static[HALSPI_ESP32_DMADESC_COUNT]; +static volatile dma_descriptor_t _usable_dma_descs_static[HALSPI_ESP32_DMADESC_COUNT]; #else -static dma_descriptor_t *_usable_dma_descs_dynamic = nullptr; +static volatile dma_descriptor_t *_usable_dma_descs_dynamic = nullptr; static uint32_t _usable_dma_descs_count = 0; #endif // Specifies the valid memory range for DMA descriptors (not specified if necessary for DMA buffers). -#define ESP32_DMA_BASE 0x3FF00000 -#define ESP32_DMA_SIZE (1<<20) -inline bool DMAIsValidDescriptor(dma_descriptor_t *desc) { - size_t addr = (size_t)desc; +// For ESP32 basic. +#define ESP32_DMADESC_HWPTR(ptr) ((uint32_t)ptr - 0x3FF00000) + +inline bool DMAIsValidPointer(volatile const void *ptr) noexcept { + size_t addr = (size_t)ptr; + + return ( addr >= SOC_DMA_LOW && addr <= SOC_DMA_HIGH ); +} - return ( addr >= ESP32_DMA_BASE && addr <= (ESP32_DMA_BASE + ESP32_DMA_SIZE) ); +inline bool DMAIsValidDescriptor(volatile dma_descriptor_t *desc) noexcept { + return DMAIsValidPointer(desc); } inline void DMAInitializeMachine() { #ifdef HALSPI_ESP32_STATIC_DMADESCS - for (dma_descriptor_t& desc : _usable_dma_descs_static) { + for (auto& desc : _usable_dma_descs_static) { if (DMAIsValidDescriptor(&desc) == false) { _spi_on_error(3); } desc.owner = SPIDMA_OWNER_CPU; + desc.reserved = 0; + desc.sosf = false; } #else void *dmabuf = heap_caps_malloc( sizeof(dma_descriptor_t)*HALSPI_ESP32_DMADESC_COUNT, MALLOC_CAP_DMA ); if (dmabuf == nullptr) _spi_on_error(3); - _usable_dma_descs_dynamic = (dma_descriptor_t*)dmabuf; + _usable_dma_descs_dynamic = (volatile dma_descriptor_t*)dmabuf; _usable_dma_descs_count = HALSPI_ESP32_DMADESC_COUNT; if (DMAIsValidDescriptor(_usable_dma_descs_dynamic) == false) _spi_on_error(3); for (uint32_t n = 0; n < _usable_dma_descs_count; n++) { - dma_descriptor_t& desc = _usable_dma_descs_dynamic[n]; + auto& desc = _usable_dma_descs_dynamic[n]; desc.owner = SPIDMA_OWNER_CPU; + desc.reserved = 0; + desc.sosf = false; } #endif } @@ -1806,17 +2161,28 @@ inline void DMAInitializeMachine() { -> each DMA-internal memory buffer accepting function has to deny the buffer if it does not match the requirements! */ -inline bool DMAIsValidDataBuffer(const void *buf, size_t bufsz) { - size_t bufaddr = (size_t)buf; +inline bool DMAIsValidWriteDataBuffer(const void *buf, size_t bufsz) noexcept { + if (DMAIsValidPointer(buf) == false) return false; + + size_t bufaddr = (size_t)buf; + + if (bufaddr % sizeof(uint32_t) != 0) return false; + if (bufsz % sizeof(uint32_t) != 0) return false; + + return true; +} +inline bool DMAIsValidReadDataBuffer(const void *buf) noexcept { + if (DMAIsValidPointer(buf) == false) return false; - if (bufaddr % sizeof(uint32_t) != 0) return false; - if (bufsz % sizeof(uint32_t) != 0) return false; + size_t bufaddr = (size_t)buf; - return true; + if (bufaddr % sizeof(uint32_t) != 0) return false; + + return true; } // Not every SPI bus is DMA-capable. -inline bool DMAIsCapableSPIBus(spi_dev_t& SPI) { +inline bool DMAIsCapableSPIBus(volatile spi_dev_t& SPI) { #ifdef HALSPI_ENABLE_INTERNBUS if (&SPI == &SPI1) return true; #endif @@ -1826,16 +2192,16 @@ inline bool DMAIsCapableSPIBus(spi_dev_t& SPI) { } struct dma_process_t { - const void *current_buffer; - size_t bufsize; - size_t txlen; - size_t curoff; - bool is_active; + const void *current_buffer; + size_t bufsize; + size_t txlen; + size_t curoff; + bool is_active; }; -static dma_process_t dma_current_process; +static volatile dma_process_t dma_current_process; -static void DMABusInitialize(spi_dev_t& SPI) { +static void DMABusInitialize(volatile spi_dev_t& SPI) { #ifdef HALSPI_DEBUG if (DMAIsCapableSPIBus(SPI) == false) _spi_on_error(4); @@ -1849,21 +2215,30 @@ static void DMABusInitialize(spi_dev_t& SPI) { // Select the SPI DMA channel. auto spibusIdx = SPIGetBusIndex(SPI); + unsigned int dma_chansel = +#ifdef HALSPI_ESP32_DMA_SELECT_CHAN1 + DPORT_SPI_DMA_CHAN_SEL_CHAN1 +#elif defined(HALSPI_ESP32_DMA_SELECT_CHAN2) + DPORT_SPI_DMA_CHAN_SEL_CHAN2 +#else + DPORT_SPI_DMA_CHAN_SEL_CHAN1 +#endif + ; #ifdef HALSPI_ESP32_ENABLE_INTERNBUS if (spibusIdx == 1) { - DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI1_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI1_DMA_CHAN_SEL = dma_chansel; } else #endif if (spibusIdx == 2) { - DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI2_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI2_DMA_CHAN_SEL = dma_chansel; } else if (spibusIdx == 3) { - DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI3_DMA_CHAN_SEL = DPORT_SPI_DMA_CHAN_SEL_CHAN1; + DPORT_SPI_DMA_CHAN_SEL_REG.DPORT_SPI_SPI3_DMA_CHAN_SEL = dma_chansel; } } -static void DMABusShutdown(spi_dev_t& SPI) { +static void DMABusShutdown(volatile spi_dev_t& SPI) { // Unselect the SPI DMA channel. auto spibusIdx = SPIGetBusIndex(SPI); @@ -1886,12 +2261,12 @@ static void DMABusShutdown(spi_dev_t& SPI) { // TODO: manage list of free descriptors to speed up the process of generating a DMA chain. -static dma_descriptor_t* DMAGetFreeDescriptor() { +static volatile dma_descriptor_t* DMAGetFreeDescriptor() noexcept { #ifdef HALSPI_ESP32_STATIC_DMADESCS - for (dma_descriptor_t& desc : _usable_dma_descs_static) { + for (auto& desc : _usable_dma_descs_static) { #else for (uint32_t _n = 0; _n < _usable_dma_descs_count; _n++) { - dma_descriptor_t& desc = _usable_dma_descs_dynamic[_n]; + auto& desc = _usable_dma_descs_dynamic[_n]; #endif if (desc.owner == SPIDMA_OWNER_CPU) { #ifdef HALSPI_DEBUG @@ -1905,38 +2280,22 @@ static dma_descriptor_t* DMAGetFreeDescriptor() { return nullptr; } -// UNSIGNED ONLY! -// (this would be much nicer with C++17 constexpr-if or C++20 concepts) -template -inline numberType _ALIGN(numberType val, numberType alignBy) { - numberType rem = (val % alignBy); - -#if 0 - if (rem < (numberType)0) rem = (numberType)-rem; -#endif - - return ( rem > 0 ? val + rem : val ); -} - -static dma_descriptor_t* DMAGenerateAcquireChain(dma_process_t& proc) { - dma_descriptor_t *startdesc = nullptr; - dma_descriptor_t *chainend = nullptr; +static volatile dma_descriptor_t* DMAGenerateAcquireChain(volatile dma_process_t& proc) noexcept { + volatile dma_descriptor_t *startdesc = nullptr; + volatile dma_descriptor_t *chainend = nullptr; while (proc.curoff < proc.txlen) { - dma_descriptor_t *freedesc = DMAGetFreeDescriptor(); + volatile dma_descriptor_t *freedesc = DMAGetFreeDescriptor(); if (freedesc == nullptr) break; size_t left_to_transmit = (proc.txlen - proc.curoff); - uint32_t txcount = (uint32_t)_MIN ((1<<12)-4, left_to_transmit); - uint32_t txbufsz = _ALIGN(txcount, (uint32_t)4u); + uint32_t txcount = eir::Minimum((1u<<12u)-4u, left_to_transmit); + uint32_t txbufsz = ALIGN_SIZE(txcount, (uint32_t)4u); freedesc->size = txbufsz; freedesc->length = txcount; - freedesc->reserved = 0; - freedesc->eof = true; freedesc->address = ((uint8_t*)proc.current_buffer + proc.curoff); - freedesc->next = nullptr; // Advance the process. proc.curoff += txcount; @@ -1956,57 +2315,222 @@ static dma_descriptor_t* DMAGenerateAcquireChain(dma_process_t& proc) { } } + if (chainend) { + chainend->eof = true; + chainend->next = nullptr; + } + return startdesc; } -static void DMASendBlocking(spi_dev_t& SPI, const void *buf, size_t bufsize, size_t txlen) { +static void DMASendBlocking(volatile spi_dev_t& SPI, const void *buf, size_t bufsize, size_t txlen) { DMABusInitialize(SPI); + // Reset the DMA state machine. + { + SPI.SPI_DMA_CONF_REG.SPI_OUT_RST = true; + SPI.SPI_DMA_CONF_REG.SPI_IN_RST = true; + SPI.SPI_DMA_CONF_REG.SPI_AHBM_RST = true; + SPI.SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = true; + + SPI.SPI_DMA_IN_LINK_REG.SPI_INLINK_START = false; + SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = false; + + SPI.SPI_DMA_CONF_REG.SPI_OUT_RST = false; + SPI.SPI_DMA_CONF_REG.SPI_IN_RST = false; + SPI.SPI_DMA_CONF_REG.SPI_AHBM_RST = false; + SPI.SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = false; + } + // Configure DMA for the SPI bus. spi_dma_conf_reg_t SPI_DMA_CONF_REG; SPI_DMA_CONF_REG.SPI_DMA_CONTINUE = false; SPI_DMA_CONF_REG.SPI_DMA_TX_STOP = false; SPI_DMA_CONF_REG.SPI_DMA_RX_STOP = false; - SPI_DMA_CONF_REG.SPI_OUT_DATA_BURST_EN = true; - SPI_DMA_CONF_REG.SPI_INDSCR_BURST_EN = true; - SPI_DMA_CONF_REG.SPI_OUTDSCR_BURST_EN = true; + SPI_DMA_CONF_REG.SPI_OUT_DATA_BURST_EN = false; + SPI_DMA_CONF_REG.SPI_INDSCR_BURST_EN = false; + SPI_DMA_CONF_REG.SPI_OUTDSCR_BURST_EN = false; SPI_DMA_CONF_REG.SPI_OUT_EOF_MODE = 1; SPI_DMA_CONF_REG.SPI_AHBM_RST = false; SPI_DMA_CONF_REG.SPI_AHBM_FIFO_RST = false; SPI_DMA_CONF_REG.SPI_OUT_RST = false; SPI_DMA_CONF_REG.SPI_IN_RST = false; - (spi_dma_conf_reg_t&)SPI.SPI_DMA_CONF_REG = SPI_DMA_CONF_REG; + SPI_DMA_CONF_REG.reserved1 = 0; + SPI_DMA_CONF_REG.reserved2 = 0; + SPI_DMA_CONF_REG.reserved3 = 0; + SPI_DMA_CONF_REG.reserved4 = 0; + dwrite(SPI.SPI_DMA_CONF_REG, SPI_DMA_CONF_REG); - dma_process_t& proc = dma_current_process; + auto& proc = dma_current_process; proc.is_active = true; proc.current_buffer = buf; proc.bufsize = bufsize; proc.txlen = txlen; proc.curoff = 0; +#if 0 + static volatile dma_descriptor_t _rxdesc; + _rxdesc.size = 0; + _rxdesc.length = 0; + _rxdesc.reserved = 0; + _rxdesc.sosf = false; + _rxdesc.eof = true; + _rxdesc.owner = SPIDMA_OWNER_DMAC; + _rxdesc.address = nullptr; + _rxdesc.next = nullptr; + { + // Workaround for SPI DMA hardware bug. + // (https://www.esp32.com/viewtopic.php?t=8433 spi_master.zip:spi_master.c:line 754) + // TODO: does it really matter??? + spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; + SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = ESP32_DMADESC_HWPTR(&_rxdesc); + SPI_DMA_IN_LINK_REG.SPI_INLINK_AUTO_RET = false; + SPI_DMA_IN_LINK_REG.reserved1 = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_STOP = false; + SPI_DMA_IN_LINK_REG.SPI_INLINK_START = true; + SPI_DMA_IN_LINK_REG.SPI_INLINK_RESTART = false; + SPI_DMA_IN_LINK_REG.reserved2 = 0; + dwrite(SPI.SPI_DMA_IN_LINK_REG, SPI_DMA_IN_LINK_REG); + } + + SPI.SPI_USER_REG.SPI_USR_MISO = true; + SPI.SPI_USER_REG.SPI_USR_MOSI = true; + SPI.SPI_CTRL_REG.SPI_FASTRD_MODE = false; + SPI.SPI_CTRL_REG.reserved2 = 0; + SPI.SPI_CTRL2_REG.SPI_SETUP_TIME = 0; + SPI.SPI_CTRL2_REG.SPI_HOLD_TIME = 0; + SPI.SPI_USER1_REG.SPI_USR_DUMMY_CYCLELEN = 0; + SPI.SPI_USER1_REG.SPI_USR_ADDR_BITLEN = 0; + SPI.SPI_USER2_REG.SPI_USR_COMMAND_BITLEN = 0; + SPI.SPI_SLAVE1_REG.SPI_SLV_STATUS_READBACK = 0; + SPI.SPI_DMA_INT_CLR_REG.SPI_INLINK_DSCR_ERROR_INT_CLR = true; + + SERIAL_ECHOLNPGM("RX CHAIN PTR: ", (uint32_t)&_rxdesc); + SERIAL_ECHOLNPGM("SOC_DMA: ", SOC_DMA_LOW, " to ", SOC_DMA_HIGH); + + SPI.SPI_MOSI_DLEN_REG.SPI_USR_MOSI_DBITLEN = 0u; + SPI.SPI_MISO_DLEN_REG.SPI_USR_MISO_DBITLEN = 0u; +#endif + +#if 0 + // DUMP MACHINE STATE. + { + static bool _dumped = false; + + if (_dumped == false) { + SPI.serial_dump(); + _dumped = true; + } + } +#endif + + //OUT_WRITE(BEEPER_PIN, HIGH); + // Is there data left to send? while (proc.curoff < proc.txlen) { // Generate a transfer chain. - dma_descriptor_t *chain = DMAGenerateAcquireChain(proc); + volatile dma_descriptor_t *chain = DMAGenerateAcquireChain(proc); if (chain == nullptr) _spi_on_error(14); + //SERIAL_ECHOLNPGM("TX CHAIN PTR: ", (uint32_t)chain); + //SERIAL_ECHOLNPGM("CHAIN TXCNT: ", chain->length); + //SERIAL_ECHOLNPGM("CHAIN SIZE: ", chain->size); + // Configure the transfer. - SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = ((uint32_t)chain - ESP32_DMA_BASE); - SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = true; + spi_dma_out_link_reg_t SPI_DMA_OUT_LINK_REG; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR = ESP32_DMADESC_HWPTR(chain);//(int)chain & 0xFFFFF; + SPI_DMA_OUT_LINK_REG.reserved1 = 0; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_STOP = false; + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_START = true; // cleared by hardware on TX termination. + SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_RESTART = false; + SPI_DMA_OUT_LINK_REG.reserved2 = 0; + dwrite(SPI.SPI_DMA_OUT_LINK_REG, SPI_DMA_OUT_LINK_REG); + +#if 0 + SPI.SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = ESP32_DMADESC_HWPTR(chain); // ??? + SPI.SPI_DMA_IN_LINK_REG.SPI_INLINK_START = true; +#elif 0 + { + // Workaround for SPI DMA hardware bug. + // (https://www.esp32.com/viewtopic.php?t=8433 spi_master.zip:spi_master.c:line 754) + // TODO: does it really matter??? + spi_dma_in_link_reg_t SPI_DMA_IN_LINK_REG; + SPI_DMA_IN_LINK_REG.SPI_INLINK_ADDR = ESP32_DMADESC_HWPTR(chain); + SPI_DMA_IN_LINK_REG.SPI_INLINK_AUTO_RET = false; + SPI_DMA_IN_LINK_REG.reserved1 = 0; + SPI_DMA_IN_LINK_REG.SPI_INLINK_STOP = false; + SPI_DMA_IN_LINK_REG.SPI_INLINK_START = true; + SPI_DMA_IN_LINK_REG.SPI_INLINK_RESTART = false; + SPI_DMA_IN_LINK_REG.reserved2 = 0; + dwrite(SPI.SPI_DMA_IN_LINK_REG, SPI_DMA_IN_LINK_REG); + } +#endif + + //SPI.SPI_DMA_RSTATUS_REG.serial_dump(); + //SPI.SPI_DMA_TSTATUS_REG.serial_dump(); + + //SERIAL_ECHOLNPGM("CUR INLINK DESCR PTR: ", SPI.SPI_INLINK_DSCR_REG); + //SERIAL_ECHOLNPGM("CUR OUTLINK DESCR PTR: ", SPI.SPI_OUTLINK_DSCR_REG); + //SERIAL_ECHOLNPGM("AFTER WRITE: ", SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR); + //SERIAL_ECHOLNPGM("TX DMA STATUS (kickoff): ", SPI.SPI_DMA_STATUS_REG.SPI_DMA_TX_EN); + //SERIAL_ECHOLNPGM("RX DMA STATUS (kickoff): ", SPI.SPI_DMA_STATUS_REG.SPI_DMA_RX_EN); + + //SERIAL_ECHOLNPGM("SPI STATE MACHINE ST (kickoff): ", SPI.SPI_EXT2_REG.SPI_ST); // Kick it off. SPI.SPI_CMD_REG.SPI_USR = true; + /* wait until DMA transfer has finished */ spi_monitored_loop usrw; +#if 0 + while (SPI.SPI_DMA_RSTATUS_REG.TX_FIFO_EMPTY == false) { + usrw.update(3); + } +#endif + while (SPI.SPI_DMA_STATUS_REG.SPI_DMA_TX_EN) { + usrw.update(3); + } while (SPI.SPI_CMD_REG.SPI_USR) { - /* wait until DMA transfer has finished */ usrw.update(3); } + +#if 0 + if (SPI.SPI_DMA_INT_RAW_REG.SPI_OUTLINK_DSCR_ERROR_INT_RAW) { + _spi_on_error(20); + } + if (SPI.SPI_DMA_INT_RAW_REG.SPI_INLINK_DSCR_ERROR_INT_RAW) { + //_spi_on_error(21); + SPI.SPI_DMA_INT_CLR_REG.SPI_INLINK_DSCR_ERROR_INT_CLR = true; + } + if (SPI.SPI_DMA_INT_RAW_REG.SPI_IN_ERR_EOF_INT_RAW) { + _spi_on_error(22); + } + if (SPI.SPI_DMA_INT_RAW_REG.SPI_INLINK_DSCR_EMPTY_INT_RAW) { + _spi_on_error(23); + } +#endif + + //SERIAL_ECHOLNPGM("CHAIN LENGTH (after tx): ", chain->length); + + // Free the DMA chain back to CPU ownership, since that is unfortunately NOT done by hardware! + while (chain) { + chain->owner = SPIDMA_OWNER_CPU; + chain = chain->next; + } } - _spi_infobeep(4); + //SERIAL_ECHOLNPGM("AFTER OP: ", SPI.SPI_DMA_OUT_LINK_REG.SPI_OUTLINK_ADDR); + //SERIAL_ECHOLNPGM("RSTATUS ADDR: ", SPI.SPI_DMA_RSTATUS_REG.TX_DES_ADDRESS); + //SERIAL_ECHOLNPGM("RSTATUS FIFO EMPTY: ", SPI.SPI_DMA_RSTATUS_REG.TX_FIFO_EMPTY); + //SERIAL_ECHOLNPGM("RSTATUS FIFO FULL: ", SPI.SPI_DMA_RSTATUS_REG.TX_FIFO_FULL); + //SERIAL_ECHOLNPGM("TX DMA STATUS (finish): ", SPI.SPI_DMA_STATUS_REG.SPI_DMA_TX_EN); + //SERIAL_ECHOLNPGM("RX DMA STATUS (finish): ", SPI.SPI_DMA_STATUS_REG.SPI_DMA_RX_EN); + ////SERIAL_ECHOLNPGM("SPI STATE MACHINE ST (finish): ", SPI.SPI_EXT2_REG.SPI_ST); + //SERIAL_ECHOLNPGM("TX COUNT: ", SPI.SPI_DMA_STATUS_REG.reserved1); + + //OUT_WRITE(BEEPER_PIN, LOW); proc.is_active = false; @@ -2100,7 +2624,7 @@ void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi uint8_t spibusIdx = _spi_gpiomap.spibusIdx; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(spibusIdx); // Enable the clock signal and reset the peripheral. #ifdef HALSPI_ESP32_ENABLE_INTERNBUS @@ -2157,9 +2681,9 @@ void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi // Enable full-duplex communication (4lines R/W) SPI.SPI_USER_REG.SPI_DOUTDIN = true; - // On ESP32 the input and output buffers of SPI are always being randomly overwritten/trashed. - // Thus it makes no sense to divide them! + // Thus it makes little sense to divide them! Purpose of half-half division is performance + // optimization using fill-while-writing. // Notes: // "If the data length is over 64 bytes, the extra part will be written from SPI_W0_REG." // - page 120 of ESP32 technical reference manual. @@ -2167,6 +2691,11 @@ void spiInitEx(uint32_t maxClockFreq, int hint_sck, int hint_miso, int hint_mosi SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART = false; SPI.SPI_USER_REG.SPI_USR_MISO_HIGHPART = false; + // Disable any hardware-chip-select. + SPI.SPI_PIN_REG.SPI_CS0_DIS = true; + SPI.SPI_PIN_REG.SPI_CS1_DIS = true; + SPI.SPI_PIN_REG.SPI_CS2_DIS = true; + _spi_transaction_is_running = false; } @@ -2231,7 +2760,7 @@ void spiClose() { void spiSetBitOrder(int bitOrder) { _spiAsyncBarrier(); - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); MarlinESP32::SPIConfigureBitOrder(SPI, bitOrder); } @@ -2239,7 +2768,7 @@ void spiSetBitOrder(int bitOrder) { void spiSetClockMode(int mode) { _spiAsyncBarrier(); - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); MarlinESP32::SPIConfigureClock(SPI, mode, _spi_gpiomap.datasig_is_direct_iomux, _spi_clkcnt); } @@ -2249,7 +2778,7 @@ void spiEstablish() { } void spiSend(uint8_t txval) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2257,13 +2786,14 @@ void spiSend(uint8_t txval) { _maybe_start_transaction(); - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); + + SPI.SPI_W_REG[start_num_idx] = txval; + MarlinESP32::SPITransaction(SPI, 1); } void spiSend16(uint16_t txval) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2271,13 +2801,19 @@ void spiSend16(uint16_t txval) { _maybe_start_transaction(); - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + eir::BitOrderingConverter bitconv( + ( SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == _ESP32_BIT_ORDER_MSB ? endian::eSpecificEndian::BIG_ENDIAN : endian::eSpecificEndian::LITTLE_ENDIAN ), + false // already done by HW + ); + + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); + + SPI.SPI_W_REG[start_num_idx] = bitconv.Identity( txval ); + MarlinESP32::SPITransaction(SPI, sizeof(uint16_t)); } uint8_t spiRec(uint8_t txval) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MISO == false) return 0; @@ -2286,21 +2822,19 @@ uint8_t spiRec(uint8_t txval) { _maybe_start_transaction(); if (SPI.SPI_USER_REG.SPI_USR_MOSI) { - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); + SPI.SPI_W_REG[start_num_idx] = txval; } MarlinESP32::SPITransaction(SPI, sizeof(uint8_t)); - uint8_t result; - uint16_t actualReadCount; - MarlinESP32::SPIReadDataFromTransfer(SPI, &result, 1, 0, 0, actualReadCount); + uint16_t start_num_idx = MarlinESP32::SPIGetReadBufferStartIndex(SPI); - return result; + return (uint8_t)SPI.SPI_W_REG[start_num_idx]; } uint16_t spiRec16(uint16_t txval) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MISO == false) return 0; @@ -2308,47 +2842,29 @@ uint16_t spiRec16(uint16_t txval) { _maybe_start_transaction(); + eir::BitOrderingConverter bitconv( + ( SPI.SPI_CTRL_REG.SPI_RD_BIT_ORDER == _ESP32_BIT_ORDER_MSB ? endian::eSpecificEndian::BIG_ENDIAN : endian::eSpecificEndian::LITTLE_ENDIAN ), + false // already done by HW + ); + if (SPI.SPI_USER_REG.SPI_USR_MOSI) { - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, &txval, 1, 0, 0, actualWriteCount); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); + SPI.SPI_W_REG[start_num_idx] = bitconv.Identity( txval ); } MarlinESP32::SPITransaction(SPI, sizeof(uint16_t)); - uint16_t result; - uint16_t actualReadCount; - MarlinESP32::SPIReadDataFromTransfer(SPI, &result, 1, 0, 0, actualReadCount); + uint16_t start_num_idx = MarlinESP32::SPIGetReadBufferStartIndex(SPI); - return result; -} + uint16_t bits = (uint16_t)SPI.SPI_W_REG[start_num_idx]; -template -inline void _spiWriteRepeatToBufferEx( - MarlinESP32::spi_dev_t& SPI, numberType val, uint32_t cnt_bytes, uint16_t& total_write_cnt_out, - uint16_t spi_writebuf_size, bool notrevbits, uint16_t spi_buf_numstartidx -) { - uint16_t txcount = (uint16_t)_MIN (cnt_bytes, spi_writebuf_size); - - for (uint16_t n = 0; n < txcount; n++) { - uint8_t byteval = MarlinESP32::SPIGetSingleByteToTransferEx(SPI, val, (n % sizeof(numberType)), notrevbits); - MarlinESP32::SPIWriteSingleByteToTransferEx(SPI, byteval, n, spi_buf_numstartidx); - } - total_write_cnt_out = txcount; -} - -template -inline void _spiWriteRepeatToBuffer(MarlinESP32::spi_dev_t& SPI, numberType val, uint32_t cnt_bytes, uint16_t& total_write_cnt_out) { - uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); - uint16_t spi_buf_numstartidx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); - - _spiWriteRepeatToBufferEx(SPI, val, cnt_bytes, total_write_cnt_out, spi_writebuf_size, notrevbits, spi_buf_numstartidx); + return bitconv.Identity( bits ); } void spiRead(uint8_t *buf, uint16_t cnt, uint8_t txval) { if (cnt == 0) return; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MISO == false) { spiWriteRepeat(txval, cnt); @@ -2361,7 +2877,7 @@ void spiRead(uint8_t *buf, uint16_t cnt, uint8_t txval) { #if 0 #ifndef HALSPI_DISABLE_DMA - if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt) + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidWriteDataBuffer(buf, cnt) #ifndef HALSPI_ESP32_DMA_ALWAYS && cnt > MarlinESP32::SPIGetReadBufferSize(SPI) #endif @@ -2376,27 +2892,37 @@ void spiRead(uint8_t *buf, uint16_t cnt, uint8_t txval) { #endif // The no-DMA version. - uint16_t txprogress = 0; + esp32BitManager recv_bitman( buf, cnt ); - while (txprogress < cnt) { - uint16_t txcount = _MIN(cnt - txprogress, MarlinESP32::SPIGetReadBufferSize(SPI)); + uint16_t start_num_idx = MarlinESP32::SPIGetReadBufferStartIndex(SPI); - if (SPI.SPI_USER_REG.SPI_USR_MOSI == true) { - uint16_t _tmp; - _spiWriteRepeatToBuffer(SPI, txval, txcount, _tmp); - } + esp32BitManager txbuf_bitman( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx ); - MarlinESP32::SPITransaction(SPI, txcount); + using reptx_t = typename eir::biggest_type ::type; - uint16_t actualWriteCount; - MarlinESP32::SPIReadDataFromTransfer(SPI, buf, cnt, txprogress, 0, actualWriteCount); + eir::BitRepetitionCache repcache( txval ); - txprogress += txcount; - } + bool is_write_avail = (SPI.SPI_USER_REG.SPI_USR_MOSI); + + eir::BitManagerTemplates::Receive( recv_bitman, txbuf_bitman, + [&] ( const auto& bititer ) LAINLINE + { + if (is_write_avail) { + eir::BitNumberIteratorForStruct repiter; + txbuf_bitman.PutRepeatable( repcache.GetData(), repiter, repiter, bititer ); + txbuf_bitman.Flush(); + } + auto bytecnt = bititer.getTotalByteOffset(); + MarlinESP32::SPITransaction(SPI, (uint32_t)bytecnt); + if (is_write_avail) { + txbuf_bitman.SetIterator({}); + } + } + ); } void spiSendBlock(uint8_t token, const uint8_t *buf) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2405,8 +2931,15 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { _maybe_start_transaction(); #ifndef HALSPI_DISABLE_DMA - if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, 512)) { + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidReadDataBuffer(buf) +#ifndef HALSPI_ESP32_DMA_ALWAYS +#ifdef HALSPI_DMA_THRESHOLD + && 512 > HALSPI_DMA_THRESHOLD +#endif +#endif + ) { // Only attempt DMA transfer if the buffer is valid. + spiSend(token); MarlinESP32::DMASendBlocking(SPI, buf, 512, 512); return; } @@ -2414,28 +2947,27 @@ void spiSendBlock(uint8_t token, const uint8_t *buf) { // Use direct SPI otherwise. #endif - uint16_t outbufprog = 0; - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, &token, 1, 0, 0, actualWriteCount); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); - outbufprog = actualWriteCount; + esp32BitManager src_bitman( buf, 512 ); - uint16_t bufprog = 0; + esp32BitManager buf_bitman( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx ); - while (bufprog < 512) { - MarlinESP32::SPIWriteDataToTransfer(SPI, buf, 512, bufprog, outbufprog, actualWriteCount); - outbufprog += actualWriteCount; - MarlinESP32::SPITransaction(SPI, outbufprog); + buf_bitman.Put( token ); - bufprog += outbufprog; - outbufprog = 0; - } + eir::BitManagerTemplates::Send( src_bitman, buf_bitman, + [&] ( void ) LAINLINE + { + auto bytecnt = buf_bitman.GetIterator().getTotalByteOffset(); + MarlinESP32::SPITransaction( SPI, (uint32_t)bytecnt ); + } + ); } void spiWrite(const uint8_t *buf, uint16_t cnt) { if (cnt == 0) return; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2444,34 +2976,39 @@ void spiWrite(const uint8_t *buf, uint16_t cnt) { _maybe_start_transaction(); #ifndef HALSPI_DISABLE_DMA - if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt) + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidReadDataBuffer(buf) #ifndef HALSPI_ESP32_DMA_ALWAYS +#ifdef HALSPI_DMA_THRESHOLD + && cnt > HALSPI_DMA_THRESHOLD +#else && cnt > MarlinESP32::SPIGetWriteBufferSize(SPI) +#endif //HALSPI_DMA_THRESHOLD #endif ) { // For bigger transfers we should use DMA. - MarlinESP32::DMASendBlocking(SPI, buf, cnt, cnt); + MarlinESP32::DMASendBlocking(SPI, buf, ALIGN_SIZE(cnt, (uint16_t)4u), cnt); return; } // Use direct SPI for small transfer sizes. #endif - uint16_t bufprog = 0; + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); - while (bufprog < cnt) { - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, buf, cnt, bufprog, 0, actualWriteCount); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + esp32BitManager src_bitMan( buf, cnt ); - bufprog += actualWriteCount; - } + eir::BitManagerTemplates::SendFixed( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx, src_bitMan, + [&] ( const auto& iter ) LAINLINE + { + MarlinESP32::SPITransaction( SPI, iter.getTotalByteOffset() ); + } + ); } void spiWrite16(const uint16_t *buf, uint16_t cnt) { if (cnt == 0) return; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2479,8 +3016,6 @@ void spiWrite16(const uint16_t *buf, uint16_t cnt) { _maybe_start_transaction(); - uint32_t cnt_bytes = (cnt * sizeof(uint16_t)); - // Problem: before we can kick-off the DMA transfer to the SPI device we have to FORMAT THE ENTIRE DMA BUFFER to match // the byte-by-byte requirement of the DMA-to-SPI-buffer filling! This is kind of a bummer because it means that DMA // transfers of color buffers have to be filled in a special way, at best directly when they are created. @@ -2490,9 +3025,11 @@ void spiWrite16(const uint16_t *buf, uint16_t cnt) { // specialized per architecture. // At least, ESP32 SPI is pretty fast as it currently stands, even without async DMA. + // LSBFIRST transfers can be pushed through the DMAC just fine because no bit-reversing/byte-swapping is necessary. + #if 0 #ifndef HALSPI_DISABLE_DMA - if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidDataBuffer(buf, cnt_bytes) && cnt > MarlinESP32::SPIGetWriteBufferSize(SPI)) { + if (MarlinESP32::DMAIsCapableSPIBus(SPI) && MarlinESP32::DMAIsValidReadDataBuffer(buf) && cnt > MarlinESP32::SPIGetWriteBufferSize(SPI)) { // For bigger transfers we should use DMA. //TODO. return; @@ -2502,21 +3039,24 @@ void spiWrite16(const uint16_t *buf, uint16_t cnt) { #endif #endif - uint32_t bufprog = 0; + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); - while (bufprog < cnt_bytes) { - uint16_t actualWriteCount; - MarlinESP32::SPIWriteDataToTransfer(SPI, buf, cnt, bufprog, 0, actualWriteCount); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + esp32BitManager src_bitMan( buf, cnt ); - bufprog += actualWriteCount; - } + MarlinESP32::SPIPrepareWriteBitManager( SPI, src_bitMan ); + + eir::BitManagerTemplates::SendFixed( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx, src_bitMan, + [&] ( const auto& iter ) LAINLINE + { + MarlinESP32::SPITransaction( SPI, iter.getTotalByteOffset() ); + } + ); } void spiWriteRepeat(uint8_t val, uint16_t repcnt) { if (repcnt == 0) return; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2527,26 +3067,23 @@ void spiWriteRepeat(uint8_t val, uint16_t repcnt) { // There is no good repetition output engine on the ESP32 DMAC. // Thus we have to use generic SPI. - uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); - uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); - - uint16_t txprog = 0; - - while (txprog < repcnt) { - uint16_t actualWriteCount; - _spiWriteRepeatToBufferEx(SPI, val, repcnt - txprog, actualWriteCount, spi_writebuf_size, notrevbits, start_num_idx); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + esp32BitManager buf_bitman( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx ); - txprog += actualWriteCount; - } + eir::BitManagerTemplates::RepeatSendCountTo( val, repcnt, buf_bitman, + [&] ( void ) LAINLINE + { + auto bytecnt = buf_bitman.GetIterator().getTotalByteOffset(); + MarlinESP32::SPITransaction( SPI, (uint32_t)bytecnt ); + } + ); } void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { if (repcnt == 0) return; - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2557,27 +3094,28 @@ void spiWriteRepeat16(uint16_t val, uint16_t repcnt) { // There is no good repetition output engine on the ESP32 DMAC. // Thus we have to use generic SPI. - uint16_t spi_writebuf_size = MarlinESP32::SPIGetWriteBufferSize(SPI); - bool notrevbits = (SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == 1); - uint16_t start_num_idx = ( SPI.SPI_USER_REG.SPI_USR_MOSI_HIGHPART == 1 ? 8 : 0 ); - - uint32_t txprog = 0; - uint32_t repcnt_bytes = repcnt * sizeof(uint16_t); + uint16_t start_num_idx = MarlinESP32::SPIGetWriteBufferStartIndex(SPI); - while (txprog < repcnt_bytes) { - uint16_t actualWriteCount; - _spiWriteRepeatToBufferEx(SPI, val, repcnt_bytes - txprog, actualWriteCount, spi_writebuf_size, notrevbits, start_num_idx); + esp32BitManager buf_bitman( &SPI.SPI_W_REG[start_num_idx], COUNT(SPI.SPI_W_REG) - start_num_idx ); - MarlinESP32::SPITransaction(SPI, actualWriteCount); + eir::BitOrderingConverter bitconv( + ( SPI.SPI_CTRL_REG.SPI_WR_BIT_ORDER == _ESP32_BIT_ORDER_MSB ? endian::eSpecificEndian::BIG_ENDIAN : endian::eSpecificEndian::LITTLE_ENDIAN ), + false // already done by HW + ); - txprog += actualWriteCount; - } + eir::BitManagerTemplates::RepeatSendCountTo( bitconv.Identity( val ), repcnt, buf_bitman, + [&] ( void ) LAINLINE + { + auto bytecnt = buf_bitman.GetIterator().getTotalByteOffset(); + MarlinESP32::SPITransaction( SPI, (uint32_t)bytecnt ); + } + ); } #ifdef HAL_SPI_SUPPORTS_ASYNC void spiWriteAsync(const uint8_t *buf, uint16_t nbyte, void (*completeCallback)(void*), void *ud) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; @@ -2596,7 +3134,7 @@ void spiWriteAsync(const uint8_t *buf, uint16_t nbyte, void (*completeCallback)( } void spiWriteAsync16(const uint16_t *buf, uint16_t txcnt, void (*completeCallback)(void*), void *ud) { - MarlinESP32::spi_dev_t& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); + auto& SPI = MarlinESP32::SPIGetBusFromIndex(_spi_gpiomap.spibusIdx); if (SPI.SPI_USER_REG.SPI_USR_MOSI == false) return; diff --git a/Marlin/src/HAL/ESP32/sdk/Arith.h b/Marlin/src/HAL/ESP32/sdk/Arith.h new file mode 100644 index 000000000000..ca39112c2049 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/Arith.h @@ -0,0 +1,62 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/Arith.h +* PURPOSE: Arithmetic helpers +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _EIRSDK_ARITH_HEADER_ +#define _EIRSDK_ARITH_HEADER_ + +#include "MetaHelpers.h" +#include "PlatformStrategy.h" + +namespace eir +{ + +template +AINLINE constexpr auto SIGNP_PROMOTE( inputType v ) noexcept +{ + if constexpr ( unsigned_integral ) + { + return (typename make_unsigned_integral ::type)v; + } + else + { + return v; + } +} + +// Performs logical bitwise left-shift but keeps the sign-specification for the result type. +template +AINLINE constexpr auto LSHIFT( T v, platformLocalBitcountType cnt ) noexcept +{ + return SIGNP_PROMOTE ( v ) << cnt; +} +// Performs logical bitwise right-shift but keeps the sign-specification for the result type. +template +AINLINE constexpr auto RSHIFT( T v, platformLocalBitcountType cnt ) noexcept +{ + return SIGNP_PROMOTE >cnt)> ( v ) >> cnt; +} + +template requires ( signed_integral == signed_integral ) +AINLINE constexpr auto ADD_SIGNP( LT left, RT right ) noexcept +{ + return ( SIGNP_PROMOTE ( left ) + SIGNP_PROMOTE ( right ) ); +} + +template requires ( signed_integral == signed_integral ) +AINLINE constexpr auto SUB_SIGNP( LT left, RT right ) noexcept +{ + return ( SIGNP_PROMOTE ( left ) - SIGNP_PROMOTE ( right ) ); +} + +} // namespace eir + +#endif //_EIRSDK_ARITH_HEADER_ \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/sdk/BitIteration.h b/Marlin/src/HAL/ESP32/sdk/BitIteration.h new file mode 100644 index 000000000000..dd805d8ca8a1 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/BitIteration.h @@ -0,0 +1,440 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/BitIteration.h +* PURPOSE: Bit-based iteration utilities +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#include "MetaHelpers.h" +#include "Tuple.h" +#include "Compare.h" +#include "PlatformStrategy.h" + +#include +#include + +#if __has_include() +#include +#endif + +#ifdef _DEBUG +#include +#endif + +namespace eir +{ + +// Type-trait. +template +struct is_bitnumberiterator : false_type {}; + +template +concept bitnumberiterator_type = is_bitnumberiterator ::value; + +// Represents an iterator over bit-arrays. Segments the bit array into "hostBitCount" slices, each referred to as +// "number" indexed in order of occurrence. +template +struct BitNumberIterator +{ + static constexpr platformLocalBitcountType hostBitCount = _hostBitCount; + + AINLINE constexpr BitNumberIterator( size_t numOffset = 0, platformLocalBitcountType bitOffset = 0 ) noexcept : numOffset( numOffset ), bitOffset( bitOffset ) + { +#ifdef _DEBUG + assert( bitOffset < hostBitCount ); +#endif + } + AINLINE BitNumberIterator( const BitNumberIterator& ) = default; + template requires ( same_as == false ) + AINLINE BitNumberIterator( const otherIterType& other ) noexcept + { + auto bitCnt = other.getTotalBitOffset(); + this->numOffset = (size_t)( bitCnt / hostBitCount ); + this->bitOffset = ( bitCnt % hostBitCount ); + } + + AINLINE BitNumberIterator& operator = ( const BitNumberIterator& ) = default; + + template requires ( same_as == false ) + AINLINE BitNumberIterator& operator = ( const otherIterType& other ) noexcept + { + auto bitCnt = other.getTotalBitOffset(); + this->numOffset = (size_t)( bitCnt / hostBitCount ); + this->bitOffset = ( bitCnt % hostBitCount ); + return *this; + } + + AINLINE constexpr void addBits( platformBitCountType bitCount ) noexcept + { + platformBitCountType numBitOff = this->getTotalBitOffset(); + + platformBitCountType newBitOff = numBitOff + bitCount; + + this->numOffset = (size_t)( newBitOff / hostBitCount ); + this->bitOffset = (platformLocalBitcountType)( newBitOff % hostBitCount ); + } + AINLINE constexpr void addBytes( size_t byteCount ) noexcept + { + const platformLocalBitcountType hostByteCount = ( hostBitCount / 8u ); + + size_t numCountByBytes = byteCount / hostByteCount; + size_t remainderByBytes = byteCount % hostByteCount; + + this->numOffset += numCountByBytes; + this->addBits( remainderByBytes * 8u ); + } + + AINLINE constexpr platformBitCountType distBits( const BitNumberIterator& right ) const noexcept + { + return ( this->getTotalBitOffset() - right.getTotalBitOffset() ); + } + AINLINE constexpr size_t distBytes( const BitNumberIterator& right ) const noexcept + { + return ( this->getTotalByteOffset() - right.getTotalByteOffset() ); + } + + AINLINE constexpr size_t getNumberOffset( void ) const noexcept + { + return this->numOffset; + } + AINLINE constexpr platformLocalBitcountType getLocalBitOffset( void ) const noexcept + { + return this->bitOffset; + } + AINLINE constexpr platformBitCountType getTotalBitOffset( void ) const noexcept + { + return ( (platformBitCountType)this->numOffset * hostBitCount + this->bitOffset ); + } + AINLINE constexpr size_t getTotalByteOffset( void ) const noexcept + { + if constexpr ( hostBitCount % 8u == 0 ) + { + if constexpr ( hostBitCount == 8u ) + { + return (size_t)( this->numOffset * ( hostBitCount / 8u ) ); + } + else + { + return (size_t)( this->numOffset * ( hostBitCount / 8u ) + this->bitOffset / 8u ); + } + } + else + { + return (size_t)( getTotalBitOffset() / 8u ); + } + } + + // Optimized variant. + AINLINE constexpr BitNumberIterator& operator += ( const BitNumberIterator& right ) noexcept + { + this->numOffset += right.numOffset; + this->addBits( right.bitOffset ); + return *this; + } + // Less-optimized variant. + template + AINLINE constexpr BitNumberIterator& operator += ( const RT& right ) noexcept + { + this->addBits( right.getTotalBitOffset() ); + return *this; + } + + AINLINE constexpr BitNumberIterator operator + ( const BitNumberIterator& right ) const noexcept + { + BitNumberIterator res = *this; + res += right; + return res; + } + + AINLINE constexpr BitNumberIterator& operator -= ( const BitNumberIterator& right ) noexcept + { + this->numOffset -= right.numOffset; + platformLocalBitcountType bitOffset = this->bitOffset; + platformLocalBitcountType subBitOffset = right.bitOffset; + + if (bitOffset < subBitOffset) + { + this->numOffset--; + this->bitOffset = ( hostBitCount - ( subBitOffset - bitOffset ) ); + } + else + { + this->bitOffset = ( bitOffset - subBitOffset ); + } + return *this; + } + template + AINLINE constexpr BitNumberIterator& operator -= ( const RT& right ) noexcept + { + platformBitCountType res_bitc = ( this->getTotalBitOffset() - right.getTotalBitOffset() ); + this->numOffset = (size_t)( res_bitc / hostBitCount ); + this->bitOffset = ( res_bitc % hostBitCount ); + return *this; + } + + AINLINE constexpr BitNumberIterator operator - ( const BitNumberIterator& right ) noexcept + { + BitNumberIterator res = *this; + res -= right; + return res; + } + + AINLINE friend constexpr bool operator == ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + return ( ( L.numOffset == R.numOffset ) && ( L.bitOffset == R.bitOffset ) ); + } + AINLINE static constexpr eCompResult compare( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + eCompResult numOff_cmpres = eir::DefaultValueCompare( L.numOffset, R.numOffset ); + + if ( numOff_cmpres != eCompResult::EQUAL ) + { + return numOff_cmpres; + } + + eCompResult bitOffset_cmpres = eir::DefaultValueCompare( L.bitOffset, R.bitOffset ); + + return bitOffset_cmpres; + } +#if defined(__cpp_impl_three_way_comparison) && !defined(_DEBUG_OLDSTYLE_COMPARISONS) + AINLINE friend constexpr auto operator <=> ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + return eir::cmpres_to_ordering ( compare( L, R ) ); + } +#else + // Required for old compilers. + AINLINE friend constexpr bool operator != ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + return !( operator == ( L, R ) ); + } + AINLINE friend constexpr bool operator < ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + return compare( L, R ) == eCompResult::LEFT_LESS; + } + AINLINE friend constexpr bool operator > ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + return compare( L, R ) == eCompResult::LEFT_GREATER; + } + AINLINE friend constexpr bool operator <= ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + auto res = compare( L, R ); + return ( res == eCompResult::LEFT_LESS || res == eCompResult::EQUAL ); + } + AINLINE friend constexpr bool operator >= ( const BitNumberIterator& L, const BitNumberIterator& R ) noexcept + { + auto res = compare( L, R ); + return ( res == eCompResult::LEFT_GREATER || res == eCompResult::EQUAL ); + } +#endif + +private: + size_t numOffset; + platformLocalBitcountType bitOffset; +}; +template +struct is_bitnumberiterator > : true_type {}; +template requires ( is_bitnumberiterator ::type>::value ) +struct is_bitnumberiterator : true_type {}; + +template requires ( same_as == false ) +AINLINE constexpr bool operator == ( const LT& L, const RT& R ) noexcept +{ + return L.getTotalBitOffset() == R.getTotalBitOffset(); +} +#if defined(__cpp_impl_three_way_comparison) && !defined(_DEBUG_OLDSTYLE_COMPARISONS) +template requires ( same_as == false ) +AINLINE constexpr auto operator <=> ( const LT& L, const RT& R ) noexcept +{ + return L.getTotalBitOffset() <=> R.getTotalBitOffset(); +} +#else +// Required for old compilers. +template requires ( same_as == false ) +AINLINE constexpr bool operator != ( const LT& L, const RT& R ) noexcept +{ + return L.getTotalBitOffset() != R.getTotalBitOffset(); +} +template requires ( same_as == false ) +AINLINE constexpr bool operator < ( const LT& L, const RT& R ) noexcept +{ + return ( L.getTotalBitOffset() < R.getTotalBitOffset() ); +} +template requires ( same_as == false ) +AINLINE constexpr bool operator > ( const LT& L, const RT& R ) noexcept +{ + return ( L.getTotalBitOffset() > R.getTotalBitOffset() ); +} +template requires ( same_as == false ) +AINLINE constexpr bool operator <= ( const LT& L, const RT& R ) noexcept +{ + return ( L.getTotalBitOffset() <= R.getTotalBitOffset() ); +} +template requires ( same_as == false ) +AINLINE constexpr bool operator >= ( const LT& L, const RT& R ) noexcept +{ + return ( L.getTotalBitOffset() >= R.getTotalBitOffset() ); +} +#endif + +// Helper for deciding a compatible iterator based on a type. +template +using BitNumberIteratorForStruct = BitNumberIterator ; + +namespace BitIterationUtils +{ + +template +concept bit_iterator_advance_min_iterType = + tuple_type ::type> && T::count == 2 && ( bitnumberiterator_type ::type> && bitnumberiterator_type ::type> ) || + unsigned_integral ::type>; + +} // namespace BitIterationUtils + +template +AINLINE platformBitCountType bit_advance_min( const iterTypes&... iterPairs ) noexcept +{ + if constexpr ( sizeof...(iterPairs) == 0 ) + { + return 0u; + } + else + { + platformBitCountType bitadv = 0u; + bool has_bitadv = false; + + auto lamb = [&] ( const T& iterPair ) LAINLINE + { + if constexpr ( tuple_type ) + { + if constexpr ( T::count == 2 ) + { + auto start = iterPair.template Get <0> ().getTotalBitOffset(); + auto end = iterPair.template Get <1> ().getTotalBitOffset(); + + platformBitCountType adv; + + if ( start < end ) + { + adv = ( end - start ); + } + else + { + adv = 0u; + } + + if (has_bitadv == false || bitadv > adv) + { + bitadv = adv; + has_bitadv = true; + } + } + } + else if constexpr ( unsigned_integral ) + { + if (has_bitadv == false || bitadv > iterPair) + { + bitadv = iterPair; + has_bitadv = true; + } + } + }; + ( lamb( iterPairs ), ... ); + + return bitadv; + } +} + +template +AINLINE startIterType bit_iterator_advance_min( const startIterType& iter, const iterTypes&... iterPairs ) noexcept +{ + if constexpr ( sizeof...(iterPairs) == 0 ) + { + return iter; + } + else + { + startIterType end_iter = iter; + + end_iter.addBits( bit_advance_min( iterPairs... ) ); + + return end_iter; + } +} + +template +AINLINE size_t bit_advance_min_bytes( const iterTypes&... iterPairs ) noexcept +{ + if constexpr ( sizeof...(iterPairs) == 0 ) + { + return 0u; + } + else + { + size_t bytesadv = 0u; + bool has_bytesadv = false; + + auto lamb = [&] ( const T& iterPair ) LAINLINE + { + if constexpr ( tuple_type ) + { + if constexpr ( T::count == 2 ) + { + auto start = iterPair.template Get <0> ().getTotalByteOffset(); + auto end = iterPair.template Get <1> ().getTotalByteOffset(); + + size_t adv; + + if ( start < end ) + { + adv = end - start; + } + else + { + adv = 0u; + } + + if (has_bytesadv == false || bytesadv > adv) + { + bytesadv = adv; + has_bytesadv = true; + } + } + } + else if constexpr ( unsigned_integral ) + { + if (has_bytesadv == false || bytesadv > iterPair) + { + bytesadv = iterPair; + has_bytesadv = true; + } + } + }; + ( lamb( iterPairs ), ... ); + + return bytesadv; + } +} + +template +AINLINE startIterType bit_iterator_advance_min_bytes( const startIterType& iter, const iterTypes&... iterPairs ) noexcept +{ + if constexpr ( sizeof...(iterPairs) == 0 ) + { + return iter; + } + else + { + startIterType end_iter = iter; + + end_iter.addBytes( bit_advance_min_bytes( iterPairs... ) ); + + return end_iter; + } +} + +} // namespace eir \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/sdk/BitManage.h b/Marlin/src/HAL/ESP32/sdk/BitManage.h new file mode 100644 index 000000000000..f574a6b095ce --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/BitManage.h @@ -0,0 +1,1442 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/BitManage.h +* PURPOSE: Low-level bit manipulation acceleration helpers +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _BIT_MANAGE_HEADER_ +#define _BIT_MANAGE_HEADER_ + +#include +#include // for size_t + +#include "MemoryRaw.h" +#include "Endian.h" +#include "MetaHelpers.h" // for no_volatile +#include "PlatformStrategy.h" +#include "Variant.h" +#include "BitManip.h" +#include "Tuple.h" +#include "Arith.h" +#include "BitIteration.h" + +// Feel the power of C++20 on the embedded side. +// Documentation Video: https://www.youtube.com/watch?v=L_o481OL0Xw (12th of January, 2023) + +namespace eir +{ + +#ifdef __cpp_if_constexpr +#define _BITMANAGE_IF_CONSTEXPR constexpr +#else +#define _BITMANAGE_IF_CONSTEXPR +#endif + +// During code-gen analysis I have detected that the inlining of the code-graphs does not lead to great results, especially +// because we use PlatformStrategy optimizations and those values are usually not retransformable by the compilers. +#ifdef _BITMANAGE_ALWAYS_INLINE +#define BM_AINLINE AINLINE +#else +#define BM_AINLINE inline +#endif + +// In comparison to the above always-inline guidelines, the "brutal" always-inline guide is applied to code-graph templates +// that are known to create a bigger mess. Thus be careful about applying this attribute! +#if defined(_BITMANAGE_ALWAYS_INLINE) && defined(_BITMANAGE_BRUTAL_ALWAYS_INLINE) +#define BM_BRUTAL_AINLINE AINLINE +#else +#define BM_BRUTAL_AINLINE inline +#endif + +template +struct identity_number_specificator +{ + typedef numberType type; +}; + +template +struct const_number_specificator +{ + typedef const T type; +}; + +template +struct volatile_number_specificator +{ + typedef volatile numberType type; +}; + +template +struct const_volatile_number_specificator +{ + typedef const volatile numberType type; +}; + +template +struct choose_default_number_specificator +{ + template + using spec = identity_number_specificator ; +}; +template +struct choose_default_number_specificator +{ + template + using spec = volatile_number_specificator ; +}; +template +struct choose_default_number_specificator +{ + template + using spec = const_number_specificator ; +}; +template +struct choose_default_number_specificator +{ + template + using spec = const_volatile_number_specificator ; +}; + +// The default type-list of hardware-supported native number types. +typedef typelist < +#if PLATFORM_WORDSIZE >= 8 + uint64_t, +#endif +#if PLATFORM_WORDSIZE >= 4 + uint32_t, +#endif +#if PLATFORM_WORDSIZE >= 2 + uint16_t, +#endif + uint8_t +> PlatformNumberTypeList; + +typedef OptTypeSelector PlatformNumberTypeSelector; + +template +AINLINE void SelectAlignedTypeAccess( numberType& loc, size_t bytes_left, callbackType&& cb ) +{ + using filteredSpecSuppTypes = typename no_volatile ::type>::type; + using distinctSuppTypes = typename types_distinct ::type; + using size_selected_types = typename sizeof_greaterequal_types ::type; + using forwardsSortedSuppTypes = typename sizeof_sorted_types ::type; + using sortedSuppTypes = typename types_reverse ::type; + + sortedSuppTypes::ForEach( + [&] () LAINLINE + { + if (is_same_as ::value || (bytes_left >= sizeof(T) && (uintptr_t)&loc % alignof(T) == 0)) + { + cb.template operator() (); + return true; + } + return false; + }); +} + +template < + template typename numberSpecific = identity_number_specificator, + typelist_type suppTypes = PlatformNumberTypeList, + template typename baseVariantType = BitfieldVariant +> +struct PlatformBitCache +{ + using filteredSpecSuppTypes = typename no_volatile ::type>::type; + using distinctSuppTypes = typename types_distinct ::type; + using forwardsSortedSuppTypes = typename sizeof_sorted_types ::type; + using sortedSuppTypes = typename types_reverse ::type; + + using distinct_t = typename numberSpecific ::type, + void>::type + >::type; + + BM_AINLINE PlatformBitCache( void ) = default; + BM_AINLINE PlatformBitCache( const PlatformBitCache& ) = default; + + BM_AINLINE PlatformBitCache& operator = ( const PlatformBitCache& ) = default; + + BM_AINLINE void Flush( void ) noexcept + { + if constexpr ( const_type == false ) + { + this->data.Visit( + [this]( auto& data ) LAINLINE + { + *(typename numberSpecific ::type>::type*PTR_NO_ALIAS)this->data_pointer = data; + } + ); + } + + this->data.Clear(); + } + BM_AINLINE void Invalidate( void ) noexcept + { + this->data.Clear(); + } + BM_AINLINE bool IsInitialized( void ) const noexcept { return ( this->data.IsEmpty() == false ); } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE void PutIntoCache( numberType& num ) noexcept + { + this->data.Store( num ); + this->data_pointer = # + } + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE numberType GetCacheValue( void ) noexcept + { + return this->data.template Get (); + } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE void CacheMemoryLocation( cacheNumType *PTR_NO_ALIAS loc, size_t bytes_left ) noexcept + { + SelectAlignedTypeAccess ( *loc, bytes_left, + [&] () LAINLINE + { + if constexpr ( no_read ) + { + this->data.Store( typename base_type ::type() ); + } + else + { + using acc_T = typename conditional <(is_volatile ::value), volatile T, T>::type; + this->data.Store( *(const acc_T*PTR_NO_ALIAS)loc ); + } + } + ); + this->data_pointer = loc; + } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE bool CanSatisfy( numberType& mem_val ) noexcept + { + if constexpr ( sortedSuppTypes::count == 1 ) + { + // Assume alignment guarantee. + return ( this->data_pointer == &mem_val ); + } + else + { + uintptr_t numloc = (uintptr_t)&mem_val; + uintptr_t cachenumloc = (uintptr_t)this->data_pointer; + + auto cache_size = this->data.GetSize(); + + // Structures must always be aligned but I can check for that anyway. + return /*(numloc % alignof(numberType) == 0) &&*/ (numloc >= cachenumloc && numloc + sizeof(numberType) <= cachenumloc + cache_size); + } + } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE void SelectRef( distinct_t *PTR_NO_ALIAS orig_ptr, callbackType&& cb ) noexcept + { + if constexpr ( sortedSuppTypes::count == 1 ) + { + cb( this->data.Get() ); + } + else + { + uintptr_t cachenumloc = (uintptr_t)this->data_pointer; + + uintptr_t byteoff = ( (uintptr_t)orig_ptr - cachenumloc ); + + if _ENDIAN_CONSTEXPR ( endian::get_current_endianness() == endian::eSpecificEndian::BIG_ENDIAN ) + { + byteoff = ( this->data.GetSize() - sizeof(numberType) ) - byteoff; + } + + this->data.VisitBitsFrom( byteoff, + [&]( auto& ref ) LAINLINE + { + StaticBitfieldNumberSelectionView ::type> bfacc( &ref ); + cb( bfacc ); + }); + } + } + BM_AINLINE distinct_t*PTR_NO_ALIAS GetStoragePointer( void ) const noexcept + { + return this->data_pointer; + } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE void SelectCachedBits( numberType& mem_val, size_t bytes_left, callbackType&& cb ) + { +#ifdef _DEBUG + assert( bytes_left >= sizeof(numberType) ); +#endif + + // All number types have a power-of-two size. + if (this->data.IsEmpty() == false) + { + if ( this->template CanSatisfy ( mem_val ) ) + { + goto returnResult; + } + + // We cannot use the previous cache anymore, so flush it. + Flush(); + } + + // Attempt to fill cache memory. + CacheMemoryLocation( &mem_val, bytes_left ); + + returnResult: + this->template SelectRef ( &mem_val, (callbackType&&)cb ); + } + + template + requires ( sequence_contains ::type, sortedSuppTypes>::value ) + BM_AINLINE typename no_const ::type>::type ReadCacheInto( numberType& mem_val, size_t bytes_left = sizeof(numberType) ) noexcept + { + typename no_const ::type>::type result = 0u; + + this->SelectCachedBits( mem_val, bytes_left, + [&]( auto& val ) LAINLINE + { + // Trim-off any bits that are too much, fill in any bits with zeroes that are missing. + result = (numberType)val; + } + ); + + return result; + } + + template + BM_AINLINE T ExtractNumberEndian( uint8_t byteoff ) const noexcept + { + unsigned int real_byteoff = byteoff; + + if _ENDIAN_CONSTEXPR ( endian::get_current_endianness() == endian::eSpecificEndian::BIG_ENDIAN ) + { + real_byteoff = ( this->data.GetSize() - sizeof(T) ) - real_byteoff; + } + + typename no_volatile ::type ret = 0u; + this->data.VisitBitsFrom( real_byteoff, + [&]( auto& ref ) LAINLINE + { + ret = (decltype(ret))ref; + }); + return ret; + } + + BM_AINLINE uint8_t GetCacheSize( void ) const noexcept + { + return this->data.GetSize(); + } + BM_AINLINE distinct_t* GetOriginalDataPointer( void ) const noexcept + { + return this->data_pointer; + } + +private: + typename conditional <(sortedSuppTypes::count == 1), + Variant , + baseVariantType + >::type data; + distinct_t *PTR_NO_ALIAS data_pointer = nullptr; +}; + +// Useful structure for performing the bit-ordering conversion on whole numbers outside of the BitManager class. +// You don't get the caching optimization of BitManager though so if you risk partial operations it is still preferable to use BitManager over directly this. +struct BitOrderingConverter +{ + AINLINE _ENDIAN_CONSTEXPR BitOrderingConverter( endian::eSpecificEndian storage_endianness = endian::eSpecificEndian::DEFAULT_ENDIAN, bool storage_msbfirst = false ) noexcept + { + bool is_diff_byteorder = ( storage_endianness != endian::get_current_endianness() ); + bool is_diff_bitorder = ( storage_msbfirst ); + + this->do_reverse_bitorder = ( is_diff_bitorder ); + this->do_reverse_byteorder = ( is_diff_byteorder != is_diff_bitorder ); +#if defined(_PLATFORM_HAS_FAST_REV16) + this->do_rev16 = false; +#endif + } + AINLINE constexpr BitOrderingConverter( bool revbits, bool revbytes, bool rev16 = false ) noexcept + : do_reverse_bitorder( revbits ), do_reverse_byteorder( revbytes ) +#if defined(_PLATFORM_HAS_FAST_REV16) + , do_rev16( rev16 ) +#endif + { + return; + } + AINLINE constexpr BitOrderingConverter( const BitOrderingConverter& ) = default; + + template + AINLINE constexpr numberType Identity( const numberType& val ) noexcept + { + numberType result = val; + if (this->do_reverse_byteorder) result = endian::byte_swap_fast( result ); + if (this->do_reverse_bitorder) result = reverse_bitorder( result ); +#if defined(_PLATFORM_HAS_FAST_REV16) + if constexpr ( __platform_number_supports_rev16 ::value ) + { + if (this->do_rev16) result = __platform_rev16( result ); + } +#endif + return result; + } + + AINLINE constexpr bool DoReverseBitorder( void ) const noexcept + { + return this->do_reverse_bitorder; + } + AINLINE constexpr bool DoReverseByteorder( void ) const noexcept + { + return this->do_reverse_byteorder; + } + +private: + bool do_reverse_bitorder, do_reverse_byteorder; +#if defined(_PLATFORM_HAS_FAST_REV16) + bool do_rev16; +#endif +}; + +// Takes a "unitNumberType" and a "containerNumberType". Returns a bitwise-operation if, performed on "containerNumberType", it's result is +// a bitwise-concatenation of "unitNumberType" entries - each solitarily assorted from LSB to MSB - in bit-index-ascending order. +struct BitVectorizedIdentityManager +{ + AINLINE _ENDIAN_CONSTEXPR BitVectorizedIdentityManager( BitOrderingConverter conv = {} ) noexcept : bitconv( conv ) + { + return; + } + AINLINE _ENDIAN_CONSTEXPR BitVectorizedIdentityManager( endian::eSpecificEndian endianness, bool msbfirst = false ) noexcept : BitVectorizedIdentityManager( BitOrderingConverter( endianness, msbfirst ) ) + { + return; + } + AINLINE BitVectorizedIdentityManager( const BitVectorizedIdentityManager& ) = default; + + template + AINLINE Variant VectorTransformGetConfig( void ) noexcept + { + if constexpr ( is_same_as ::value ) + { + return bitconv; + } + else + { +#if defined(_PLATFORM_FIXED_ENDIANNESS) + if constexpr ( sizeof(unitNumberType) == 1 ) + { + if constexpr ( endian::get_current_endianness() == endian::eSpecificEndian::BIG_ENDIAN ) + { + if ( bitconv.DoReverseBitorder() ) + { +#if defined(_PLATFORM_HAS_FAST_BITREVERSE) + if constexpr ( __platform_number_supports_bitreverse ::value ) + { + return BitOrderingConverter( true, false ); + } +#endif + } + else + { +#if defined(_PLATFORM_HAS_FAST_BYTESWAP) + if constexpr ( __platform_number_supports_byteswap ::value ) + { + return BitOrderingConverter( false, true ); + } +#endif + } + } + else + { + if ( bitconv.DoReverseBitorder() ) + { +#if defined(_PLATFORM_HAS_FAST_BITREVERSE) && defined(_PLATFORM_HAS_FAST_BYTESWAP) + if constexpr ( __platform_number_supports_byteswap ::value && __platform_number_supports_bitreverse ::value ) + { + return BitOrderingConverter( true, true ); + } +#endif + } + } + } + if constexpr ( sizeof(unitNumberType) == 2 ) + { + if constexpr ( endian::get_current_endianness() == endian::eSpecificEndian::LITTLE_ENDIAN ) + { + if ( bitconv.DoReverseByteorder() && bitconv.DoReverseBitorder() == false ) + { +#if defined(_PLATFORM_HAS_FAST_REV16) + if constexpr ( __platform_number_supports_rev16 ::value ) + { + return BitOrderingConverter( false, false, true ); + } +#endif + } + } + else + { + if ( bitconv.DoReverseByteorder() && bitconv.DoReverseBitorder() == false ) + { +#if defined(_PLATFORM_HAS_FAST_REV16) && defined(_PLATFORM_HAS_FAST_BYTESWAP) + if constexpr ( __platform_number_supports_byteswap ::value && __platform_number_supports_rev16 ::value ) + { + return BitOrderingConverter( false, true, true ); + } +#endif + } + } + } + if constexpr ( endian::get_current_endianness() == endian::eSpecificEndian::LITTLE_ENDIAN ) + { + if ( bitconv.DoReverseBitorder() == false && bitconv.DoReverseByteorder() == false ) + { + return BitOrderingConverter( false, false ); + } + } + else + { +#if defined(_PLATFORM_HAS_FAST_BYTESWAP) + if ( bitconv.DoReverseBitorder() == false && bitconv.DoReverseByteorder() == false ) + { + return BitOrderingConverter( false, true ); + } +#endif + } +#endif + // Unsupported transformation, related code-graphs should be deleted by compiler. + return {}; + } + } + template + AINLINE numberType VectorTransform( numberType val ) noexcept + { + if ( auto conf = VectorTransformGetConfig () ) + { + return conf.Get().Identity( val ); + } + // If everything else fails, do this. + // This code path should never be taken. + return 0u; + } + + // This method is required to be done using lambdas because in C++ it is currently ONLY possible to specialize DOWN the code-graph + // but NOT up (in the direction of the root of) the code-graph. + template + BM_AINLINE void Select( hostNumberType *vec, size_t num, callbackType&& cb ) noexcept + { + typedef typename no_volatile ::type hostFastNumberType; + + if (num == 0) return; + + // Check for support of FAST vectorized transformations. + using required_types_for_check = typename sizeof_greaterequal_types ::type; + using sorted_types_by_size = typename sizeof_sorted_types ::type; + using reversed_check_types = typename types_reverse ::type; + + reversed_check_types::ForEach( + [&] () LAINLINE + { + if ( sizeof(T) <= sizeof(hostNumberType) * num ) + { + if ( auto cfg = this->VectorTransformGetConfig () ) + { + const T& val = *(const T*)vec; + cb( cfg.Get().Identity( val ) ); + return true; + } + } + return false; + }); + } + +private: + BitOrderingConverter bitconv; +}; + +enum class eBitIdentityStorageIdentStrategy +{ + ALIASED, // uses memory-aliasing to fetch native integrals + BITFIELD // uses bitfield-extraction to fetch native integrals +}; + +inline constexpr eBitIdentityStorageIdentStrategy get_default_bit_identity_storage_ident_strategy( void ) noexcept +{ + endian::eSpecificEndian endianness = endian::eSpecificEndian::DEFAULT_ENDIAN; +#ifdef _PLATFORM_FIXED_ENDIANNESS + endianness = endian::get_current_endianness(); +#endif + + if (endianness == endian::eSpecificEndian::LITTLE_ENDIAN) + return eBitIdentityStorageIdentStrategy::BITFIELD; +#if !defined(_PLATFORM_HAS_FAST_BYTESWAP) + return eBitIdentityStorageIdentStrategy::ALIASED; +#else + return eBitIdentityStorageIdentStrategy::BITFIELD; +#endif +} + +// Storage that is identity-optimized on memory request, taking boundary specification into account, allowing flushing back +// of storage into fetched.from location. +// To identity-transform a bit-array is defined as permuting it so that the bits are assorted from LSB to MSB according +// to their indices. +// hostNumberType has to be unsigned integral. +template < + typename hostNumberType, + template typename numberSpecificator = identity_number_specificator, + typelist_type suppTypes = PlatformNumberTypeList, + template typename variantType = BitfieldVariant, + eBitIdentityStorageIdentStrategy idstrat = get_default_bit_identity_storage_ident_strategy(), + bool write_only = false +> requires ( write_only == false || mutable_type ) +struct BitIdentityStorage +{ + BM_AINLINE BitIdentityStorage( void ) = default; + BM_AINLINE BitIdentityStorage( const BitIdentityStorage& ) = default; + +private: + using amendedSuppTypes = typename eir::typelist_union ::type>>::type; + + BM_AINLINE void FlushIdCache( void ) noexcept + requires ( const_type == false ) + { + this->idcache.Visit( + [this]( auto& ref ) LAINLINE + { + typedef typename plain_type_bitfield ::type numType; + + numType data = ref; + + data = this->vecman.template VectorTransform ::type> ( data ); + + this->memcache.template SelectRef ( + this->idcache_pointer, + [&]( auto& cref ) LAINLINE + { + cref = data; + } + ); + } + ); + this->idcache.Clear(); + } + + using hostFastNumberType = typename no_volatile ::type>::type; + +public: + // Modelling assumption conflict: in the optimal BitManager implementation we base all of our memory requests on + // a fixed host-type that defines that bit-layout for all succeeding memory. Not having a fixed number type across requests + // does break the bit identity in certain operation orders. + // => That is why I have decided to introduce the template parameter "hostNumberType". + + template + BM_BRUTAL_AINLINE void Select( hostNumberType& num, size_t bytes_left, callbackType&& cb, bool cache_dirty ) + { + uintptr_t numloc = (uintptr_t)# + + if (this->idcache.IsEmpty() == false) + { + // Check whether the request is inside the identity cache. + uintptr_t cachenumloc = (uintptr_t)this->idcache_pointer; + + auto cache_size = this->idcache.GetSize(); + + if (numloc >= cachenumloc && numloc + sizeof(hostFastNumberType) <= cachenumloc + cache_size) + { + // Request is still within cache, so return it. + goto returnResult; + } + + if constexpr ( const_type == false ) + { + if ( cache_dirty ) + { + // Request fell outside of cache, so flush the cache. + this->FlushIdCache(); + } + else + { + this->idcache.Clear(); + } + } + else + { + // Just throw away const cache contents. + this->idcache.Clear(); + } + } + + // Invalidate the memory cache if the request is not inside of it. + if (this->memcache.IsInitialized() == false || this->memcache.template CanSatisfy ( num ) == false) + { + if constexpr ( const_type == false ) + { + if ( cache_dirty ) + { + this->memcache.Flush(); + } + else + { + this->memcache.Invalidate(); + } + } + else + { + this->memcache.Invalidate(); + } + this->memcache.template CacheMemoryLocation ( &num, bytes_left ); + } + + // Put new stuff into cache. + { + using required_types_for_check = typename sizeof_greaterequal_types ::type; + using sorted_types_by_size = typename sizeof_sorted_types ::type; + using reversed_check_types = typename types_reverse ::type; + + // Calculate the amount of bits that are possible to read at &num location. + auto boff = ( numloc - (uintptr_t)this->memcache.GetOriginalDataPointer() ); + auto bytecnt = ( this->memcache.GetCacheSize() - boff ); + + typename biggest_type ::type tmp = 0u; + uint8_t id_bytecnt = 0u; + + if constexpr ( idstrat == eBitIdentityStorageIdentStrategy::ALIASED ) + { + // Unused. + (void)tmp; (void)id_bytecnt; + +#ifndef _PLATFORM_SUPPORTS_UNALIGNED_MEMACCESS + // This aligned read check is only required if we use the memory-semantics-implementation of bit fetching. + // To support every hardware in existence we check that we can perform an aligned-read onto the memloc. + uint8_t aligncnt = 0u; + SelectAlignedTypeAccess ( num, bytecnt, + [&] () LAINLINE + { + aligncnt = alignof(T); + }); + + if (bytecnt > aligncnt) + { + bytecnt = aligncnt; + } +#endif //_PLATFORM_SUPPORTS_UNALIGNED_MEMACCESS + } + + reversed_check_types::ForEach( + [&] () LAINLINE + { + if ( sizeof(T) <= bytecnt ) + { + if ( auto vcfg = this->vecman.template VectorTransformGetConfig () ) + { + if constexpr ( idstrat == eBitIdentityStorageIdentStrategy::ALIASED ) + { + const auto& val = *(const T*PTR_NO_ALIAS)( (const char*PTR_NO_ALIAS)this->memcache.GetStoragePointer() + boff ); + this->idcache = vcfg.Get().Identity( val ); + } + else if constexpr ( idstrat == eBitIdentityStorageIdentStrategy::BITFIELD ) + { + T val = this->memcache.template ExtractNumberEndian ( (uint8_t)boff ); + tmp = vcfg.Get().Identity( val ); + id_bytecnt = sizeof(T); + } + return true; + } + } + return false; + }); + if constexpr ( idstrat == eBitIdentityStorageIdentStrategy::BITFIELD ) + { + this->idcache.StoreByBitfield( tmp, id_bytecnt ); + } + this->idcache_pointer = # + } + returnResult: + uint8_t idbyteoff = (uint8_t)( numloc - (uintptr_t)this->idcache_pointer ); + + this->idcache.VisitBitsFrom( idbyteoff, castforward ( cb ) ); + } + + BM_BRUTAL_AINLINE hostFastNumberType Read( hostFastNumberType& val, size_t bytes_left, bool cache_dirty ) noexcept + requires ( write_only == false ) + { + hostFastNumberType result = 0u; + + this->Select( val, bytes_left, + [&]( auto& data ) LAINLINE + { + result = (hostFastNumberType)data; + }, cache_dirty + ); + + return result; + } + BM_BRUTAL_AINLINE void Write( hostFastNumberType& val, hostFastNumberType write_to, size_t bytes_left, bool cache_dirty ) noexcept + requires ( const_type == false ) + { + this->Select( val, bytes_left, + [&]( auto& data ) LAINLINE + { + data = write_to; + }, cache_dirty + ); + } + + BM_AINLINE void Flush( void ) noexcept + { + if constexpr ( const_type == false ) + { + this->FlushIdCache(); + this->memcache.Flush(); + } + else + { + this->Invalidate(); + } + } + BM_AINLINE void Invalidate( void ) noexcept + { + this->idcache.Clear(); + this->memcache.Invalidate(); + } + + BM_AINLINE bool IsValid( void ) const noexcept + { + return ( this->idcache.IsEmpty() == false ); + } + + BM_AINLINE void SetStorageProperty( endian::eSpecificEndian endianness, bool msbfirst ) noexcept + { + this->Flush(); + this->vecman = { endianness, msbfirst }; + } + +private: + using size_feasible_supp_types = typename sizeof_greaterequal_types ::type; + + PlatformBitCache memcache; + variantType idcache; + typename decltype(memcache)::distinct_t *idcache_pointer; + BitVectorizedIdentityManager vecman; +public: + using supportedTypes = size_feasible_supp_types; +}; + +template + requires ( sizeof(containNumberType) >= sizeof(unitNumberType) ) +struct BitRepetitionCache +{ + static constexpr size_t count_contained = sizeof(containNumberType) / sizeof(unitNumberType); + + AINLINE BitRepetitionCache( unitNumberType val ) noexcept + { + BitIncrementalAccessor acc; + + for ( size_t n = 0; n < count_contained; n++ ) + { + acc.WriteBits( val, sizeof(unitNumberType)*8u ); + } + + this->data = acc.GetData(); + } + AINLINE BitRepetitionCache( const BitRepetitionCache& ) = default; + AINLINE BitRepetitionCache( BitRepetitionCache&& ) = default; + + AINLINE BitRepetitionCache& operator = ( const BitRepetitionCache& ) = default; + AINLINE BitRepetitionCache& operator = ( BitRepetitionCache&& ) = default; + + AINLINE const containNumberType& GetData( void ) const noexcept + { + return this->data; + } + +private: + containNumberType data; +}; + +#define BITMANAGER_REQUIREMENTS requires ( write_only == false || mutable_type ) +#define BITMANAGER_TEMPLARGS \ +template typename numberSpecificator = choose_default_number_specificator ::template spec, \ + typelist_type suppTypes = PlatformNumberTypeList, \ + template typename cacheVariantType = BitfieldVariant, \ + eBitIdentityStorageIdentStrategy idstrat = get_default_bit_identity_storage_ident_strategy(), \ + bool write_only = false \ + > BITMANAGER_REQUIREMENTS +#define BITMANAGER_TEMPLARGS_NODEF \ +template typename numberSpecificator, \ + typelist_type suppTypes, \ + template typename cacheVariantType, \ + eBitIdentityStorageIdentStrategy idstrat, \ + bool write_only \ + > BITMANAGER_REQUIREMENTS +#define BITMANAGER_TEMPLUSE + +// Takes a bit array as input. Allows bitwise read and write operations on the input bit array, using the +// optimized classes mentioned previously. +BITMANAGER_TEMPLARGS +struct BitManager +{ + static constexpr bool is_const_bitman = is_const ::value; + + BM_AINLINE BitManager( hostNumberType *buffer, size_t bufSize, size_t numOffset = 0, platformLocalBitcountType bitOffset = 0 ) noexcept + : buffer( buffer ), bufSize( bufSize ), iterator( numOffset, bitOffset ) + { + this->cache.SetStorageProperty( this->storage_endianness, this->storage_msbfirst ); + } + BM_AINLINE BitManager( const BitManager& ) = default; + + BM_AINLINE ~BitManager( void ) + { + if constexpr ( const_type == false ) + { + if (dirty_cache) + { + this->cache.Flush(); + } + } + } + + BM_AINLINE BitManager& operator = ( const BitManager& ) = default; + + BM_AINLINE size_t GetBufferSize( void ) const noexcept { return this->bufSize; } + +private: + typedef BitNumberIteratorForStruct iter_t; + + template + BM_AINLINE void SelectByIndex( size_t idx, callbackType&& cb ) + { + size_t bytes_left = sizeof(hostNumberType) * ( this->bufSize - idx ); + + this->cache.Select( this->buffer[ idx ], bytes_left, (callbackType&&)cb, this->dirty_cache ); + } + +public: + // I have decided to implement a true msbfirst parameter instead of reverse-bits because the reversing of entire hostNumberType bits would conflict + // with the reversing of bit-groups - the so called "byteswap" algorithm - in programming models. + // Read the algorithm proof inside the methods for further details. + + BM_AINLINE void Reset( void ) noexcept + { + this->Flush(); + this->iterator = iter_t(); + } + +private: + template + requires ( unsigned_integral ::type> ) + BM_AINLINE void _PutLoopImpl( const numberType& val, srcIterType& srcIter, iter_t& iter, endIterType& end_iter ) noexcept + requires ( const_type == false ) + { + while ( true ) + { + size_t numOff = iter.getNumberOffset(); + platformLocalBitcountType bitOff = iter.getLocalBitOffset(); + + platformBitCountType avail_bitCnt = ( end_iter - iter ).getTotalBitOffset(); + + if ( avail_bitCnt == 0 ) break; + + platformLocalBitcountType src_bitOff = srcIter.getLocalBitOffset(); + platformBitCountType src_bitCount = ( srcIterType::hostBitCount - src_bitOff ); + + platformLocalBitcountType bitCnt; + bool has_data = false; + + this->SelectByIndex( numOff, + [&]( auto& pnum ) LAINLINE + { + auto numBits = SUB_SIGNP( get_bitcount( pnum ), bitOff ); + + bitCnt = (platformLocalBitcountType)eir::Minimum( numBits, avail_bitCnt, src_bitCount ); + + // TODO: may think about implementing a rolling-replace algorithm to save invocations of the + // ROR/ROL instructions, improving performance. + + replace_bits( pnum, RSHIFT( val, src_bitOff ), bitOff, bitCnt ); + + has_data = true; + } + ); + if ( has_data ) + { + srcIter.addBits( bitCnt ); + iter.addBits( bitCnt ); + + this->dirty_cache = true; + } + } + this->iterator = end_iter; + } +public: + // Can be used across BitManager instances if their "shared-region" is calculated and passed as end-iter. + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutRepeatableSharedRemainder( const numberType& val, BitNumberIteratorForStruct & srcIter, const BitNumberIteratorForStruct & sharedIter_start, const BitNumberIteratorForStruct & sharedIter_end ) noexcept + { + auto iter = this->iterator; + + decltype(iter) end_iter; + + if constexpr ( byteOptimize ) + { + // Use this if you know that operations execute on multiples of bytes (8 bit packets). + end_iter = bit_iterator_advance_min_bytes( iter, + eir::Tuple( sharedIter_start, sharedIter_end ) + ); + } + else + { + end_iter = bit_iterator_advance_min( iter, + eir::Tuple( sharedIter_start, sharedIter_end ) + ); + } + + this->_PutLoopImpl( val, srcIter, iter, end_iter ); + } + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutRepeatable( const numberType& val, BitNumberIteratorForStruct & srcIter, const BitNumberIteratorForStruct & srcIter_start, const BitNumberIteratorForStruct & srcIter_end ) noexcept + { + auto iter = this->iterator; + + BitNumberIteratorForStruct dst_enditer( this->bufSize, 0 ); + + decltype(iter) end_iter; + + if constexpr ( byteOptimize ) + { + // Use this if you know that operations execute on multiples of bytes (8 bit packets). + end_iter = bit_iterator_advance_min_bytes( iter, + eir::Tuple( srcIter_start, srcIter_end ), + ( dst_enditer - iter ).getTotalByteOffset() + ); + } + else + { + end_iter = bit_iterator_advance_min( iter, + eir::Tuple( srcIter_start, srcIter_end ), + ( dst_enditer - iter ).getTotalBitOffset() + ); + } + + this->_PutLoopImpl( val, srcIter, iter, end_iter ); + } + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutSingle( const numberType& val, BitNumberIteratorForStruct & srcIter ) noexcept + requires ( const_type == false ) + { + BitNumberIteratorForStruct src_loopiter( 0, srcIter.getLocalBitOffset() ); + BitNumberIteratorForStruct src_enditer( 1, 0 ); + + this->template PutRepeatable ( val, srcIter, src_loopiter, src_enditer ); + } + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutPartialBits( const numberType& val, platformLocalBitcountType putBitcnt, BitNumberIteratorForStruct & srcIter ) noexcept + requires ( const_type == false ) + { + auto iter = this->iterator; + + BitNumberIteratorForStruct src_loopiter( 0, srcIter.getLocalBitOffset() ); + BitNumberIteratorForStruct src_enditer( 1, 0 ); + BitNumberIteratorForStruct dst_enditer( this->bufSize, 0 ); + + auto end_iter = bit_iterator_advance_min( iter, + ( src_enditer - src_loopiter ).getTotalBitOffset(), + ( dst_enditer - iter ).getTotalBitOffset(), + putBitcnt + ); + + this->_PutLoopImpl( val, srcIter, iter, end_iter ); + } + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutPartialBytes( const numberType& val, uint8_t putBytecnt, BitNumberIteratorForStruct & srcIter ) noexcept + requires ( const_type == false ) + { + auto iter = this->iterator; + + BitNumberIteratorForStruct src_loopiter( 0, srcIter.getLocalBitOffset() ); + BitNumberIteratorForStruct src_enditer( 1, 0 ); + BitNumberIteratorForStruct dst_enditer( this->bufSize, 0 ); + + auto end_iter = bit_iterator_advance_min_bytes( iter, + ( src_enditer - src_loopiter ).getTotalByteOffset(), + ( dst_enditer - iter ).getTotalByteOffset(), + putBytecnt + ); + + this->_PutLoopImpl( val, srcIter, iter, end_iter ); + } + template requires ( unsigned_integral ::type> ) + BM_AINLINE void PutSingle( const numberType& val, BitNumberIteratorForStruct & srcIter, endian::eSpecificEndian target_endianness, bool msbfirst = false ) noexcept + requires ( const_type == false ) + { + endian::eSpecificEndian prev_storage_endianness = this->storage_endianness; + bool prev_storage_msbfirst = this->storage_msbfirst; + + this->SetDefaultStorageProperty( target_endianness, msbfirst ); + + this->PutSingle( val, srcIter ); + + this->storage_endianness = prev_storage_endianness; + this->storage_msbfirst = prev_storage_msbfirst; + } + // Only use this function if you know that the put request will complete 100%. + // Otherwise you should use PutEx with the iterator, proceeding until the iterator is at it's end. + template requires ( unsigned_integral ::type> ) + BM_AINLINE void Put( const numberType& val, endian::eSpecificEndian target_endianness = endian::eSpecificEndian::DEFAULT_ENDIAN, bool msbfirst = false ) noexcept + requires ( const_type == false ) + { + BitNumberIteratorForStruct srcIter; + + this->PutSingle( val, srcIter, target_endianness, msbfirst ); + } +private: + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void _FetchLoopImpl( numberType& result, dstIterType& dstIter, iter_t& iter, endIterType& end_iter ) noexcept + { + while ( true ) + { + size_t numOff = iter.getNumberOffset(); + platformLocalBitcountType bitOff = iter.getLocalBitOffset(); + + platformBitCountType avail_bitCnt = ( end_iter - iter ).getTotalBitOffset(); + + if ( avail_bitCnt == 0 ) break; + + platformLocalBitcountType bitCnt; + bool has_data = false; + + this->SelectByIndex( numOff, + [&]( auto& pnum ) LAINLINE + { + auto numBits = SUB_SIGNP( get_bitcount( pnum ), bitOff ); + + bitCnt = (platformLocalBitcountType)eir::Minimum( numBits, avail_bitCnt ); + + auto wbits = extract_bits( pnum, bitOff, bitCnt ); + + result |= LSHIFT( wbits, dstIter.getLocalBitOffset() ); + + has_data = true; + } + ); + if ( has_data ) + { + dstIter.addBits( bitCnt ); + iter.addBits( bitCnt ); + } + } + this->iterator = end_iter; + } +public: + // Can be used across BitManager instances if their "shared-region" is calculated and passed as end-iter. + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void FetchSingleSharedRemainder( numberType& result, BitNumberIteratorForStruct & dstIter, const sharedEndIterType& sharedEndIter ) noexcept + { + auto iter = this->iterator; + + BitNumberIteratorForStruct dst_loopiter( 0, dstIter.getLocalBitOffset() ); + BitNumberIteratorForStruct dst_enditer( 1, 0 ); + + decltype(iter) end_iter; + + if constexpr ( byteOptimize ) + { + // Use this if you know that operations execute on multiples of bytes (8 bit packets). + end_iter = bit_iterator_advance_min_bytes( iter, + ( dst_enditer - dst_loopiter ).getTotalByteOffset(), + eir::Tuple( dstIter, sharedEndIter ) + ); + } + else + { + end_iter = bit_iterator_advance_min( iter, + ( dst_enditer - dst_loopiter ).getTotalBitOffset(), + eir::Tuple( dstIter, sharedEndIter ) + ); + } + + this->_FetchLoopImpl( result, dstIter, iter, end_iter ); + } + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void FetchSingle( numberType& result, BitNumberIteratorForStruct & dstIter ) noexcept + { + auto iter = this->iterator; + + BitNumberIteratorForStruct dst_loopiter( 0, dstIter.getLocalBitOffset() ); + BitNumberIteratorForStruct dst_enditer( 1, 0 ); + BitNumberIteratorForStruct src_enditer( this->bufSize, 0 ); + + decltype(iter) end_iter; + + if constexpr ( byteOptimize ) + { + // Use this if you know that operations execute on multiples of bytes (8 bit packets). + end_iter = bit_iterator_advance_min_bytes( iter, + ( dst_enditer - dst_loopiter ).getTotalByteOffset(), + ( src_enditer - iter ).getTotalByteOffset() + ); + } + else + { + end_iter = bit_iterator_advance_min( iter, + ( dst_enditer - dst_loopiter ).getTotalBitOffset(), + ( src_enditer - iter ).getTotalBitOffset() + ); + } + + this->_FetchLoopImpl( result, dstIter, iter, end_iter ); + } + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void FetchPartialBits( numberType& result, platformLocalBitcountType fetchBitCnt, BitNumberIteratorForStruct & dstIter ) noexcept + { + auto iter = this->iterator; + + BitNumberIteratorForStruct dst_loopiter( 0, dstIter.getLocalBitOffset() ); + BitNumberIteratorForStruct dst_enditer( 1, 0 ); + BitNumberIteratorForStruct src_enditer( this->bufSize, 0 ); + + auto end_iter = bit_iterator_advance_min( iter, + ( dst_enditer - dst_loopiter ).getTotalBitOffset(), + ( src_enditer - iter ).getTotalBitOffset(), + fetchBitCnt + ); + + this->_FetchLoopImpl( result, dstIter, iter, end_iter ); + } + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void FetchPartialBytes( numberType& result, uint8_t fetchByteCnt, BitNumberIteratorForStruct & dstIter ) noexcept + { + auto iter = this->iterator; + + BitNumberIteratorForStruct dst_loopiter( 0, dstIter.getLocalBitOffset() ); + BitNumberIteratorForStruct dst_enditer( 1, 0 ); + BitNumberIteratorForStruct src_enditer( this->bufSize, 0 ); + + auto end_iter = bit_iterator_advance_min_bytes( iter, + ( dst_enditer - dst_loopiter ).getTotalByteOffset(), + ( src_enditer - iter ).getTotalByteOffset(), + fetchByteCnt + ); + + this->_FetchLoopImpl( result, dstIter, iter, end_iter ); + } + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE void FetchSingle( numberType& result, BitNumberIteratorForStruct & dstIter, endian::eSpecificEndian target_endianness, bool msbfirst = false ) noexcept + { + endian::eSpecificEndian prev_storage_endianness = this->storage_endianness; + bool prev_storage_msbfirst = this->storage_msbfirst; + + this->SetDefaultStorageProperty( target_endianness, msbfirst ); + + // Cannot throw exceptions so we are safe. + this->FetchSingle( result, dstIter ); + + this->storage_endianness = prev_storage_endianness; + this->storage_msbfirst = prev_storage_msbfirst; + } + // Only use this function if you know that the fetch request will complete 100%. + // Otherwise you should use FetchEx with the iterator, proceeding until the iterator is at it's end. + template + requires ( write_only == false && unsigned_integral ::type> ) + BM_AINLINE numberType Fetch( endian::eSpecificEndian target_endianness = endian::eSpecificEndian::DEFAULT_ENDIAN, bool msbfirst = false ) noexcept + { + BitNumberIteratorForStruct dstIter; + + typename no_volatile ::type result = 0; + this->FetchSingle( result, dstIter, target_endianness, msbfirst ); + + return result; + } + inline void Flush( void ) noexcept + { + if constexpr ( const_type == false ) + { + if (this->dirty_cache) + { + this->cache.Flush(); + + this->dirty_cache = false; + } + else + { + this->cache.Invalidate(); + } + } + else + { + this->cache.Invalidate(); + } + } + + BM_AINLINE bool IsAtEnd( void ) const noexcept + { + return ( this->iterator.getNumberOffset() == this->bufSize ); + } + + BM_AINLINE void SetDefaultStorageProperty( endian::eSpecificEndian endianness, bool msbfirst ) noexcept + { + if (this->storage_endianness == endianness && this->storage_msbfirst == msbfirst) return; + + this->cache.SetStorageProperty( endianness, msbfirst ); + this->storage_endianness = endianness; + this->storage_msbfirst = msbfirst; + } + + BM_AINLINE void SetIterator( iter_t iter ) noexcept + { + this->iterator = castmove( iter ); + } + BM_AINLINE iter_t GetIterator( void ) const noexcept + { + return this->iterator; + } + + BM_AINLINE iter_t GetRemainderIterator( void ) const noexcept + { + return ( iter_t( this->bufSize, 0 ) - this->iterator ); + } + +private: + hostNumberType *buffer; + size_t bufSize; + iter_t iterator; + + // Endian properties of storage. + endian::eSpecificEndian storage_endianness = endian::eSpecificEndian::DEFAULT_ENDIAN; + bool storage_msbfirst = false; + + BitIdentityStorage cache; + bool dirty_cache = false; +public: + using supportedTypes = typename decltype(BitManager::cache)::supportedTypes; +}; +template +struct is_bitmanager : false_type {}; +BITMANAGER_TEMPLARGS_NODEF +struct is_bitmanager : true_type {}; +template requires ( is_bitmanager ::type>::value ) +struct is_bitmanager : true_type {}; + +template +concept bitmanager_type = is_bitmanager ::value; + +// Namespace that contains useful code-graph templates for use with BitManager instances. +namespace BitManagerTemplates +{ + +// Performs an one way transfer operation, fetching data from src_bitman and pushing it into dst_bitman. +// Use the commit operation to perform the hardware send request. +template + requires ( eir::typelist_shared ::type::count > 0 && dstBitManType::is_const_bitman == false && + requires ( commitCallbackType cb ) { cb(); } ) +BM_AINLINE void Send( srcBitManType& src_bitman, dstBitManType& dst_bitman, commitCallbackType&& cb ) + noexcept(requires(commitCallbackType cb) { { cb() } noexcept; }) +{ + using txitem_t = typename eir::biggest_type ::type>::type; + + while ( src_bitman.IsAtEnd() == false ) + { + while ( dst_bitman.IsAtEnd() == false && src_bitman.IsAtEnd() == false ) + { + BitNumberIteratorForStruct iter; + txitem_t raw = 0u; + src_bitman.FetchSingle( raw, iter ); + BitNumberIteratorForStruct dst_iter; + dst_bitman.PutPartialBytes( raw, (uint8_t)iter.getTotalByteOffset(), dst_iter ); + } + dst_bitman.Flush(); + // Commit. + cb(); + dst_bitman.SetIterator({}); + } +} + +template + requires requires ( commitCallbackType cb, const BitNumberIteratorForStruct ::type> iter ) { cb( iter ); } +BM_AINLINE void SendFixed( dstNumberType *txbuf, size_t txbuf_cnt, srcBitManType& src_bitMan, commitCallbackType&& cb ) + noexcept(requires ( commitCallbackType cb, const BitNumberIteratorForStruct ::type> iter ) { { cb( iter ) } noexcept; }) +{ + while ( src_bitMan.IsAtEnd() == false ) + { + BitNumberIteratorForStruct ::type> dst_iter; + while ( src_bitMan.IsAtEnd() == false && dst_iter.getNumberOffset() < txbuf_cnt ) + { + typename base_type ::type tmp = 0u; + size_t n = dst_iter.getNumberOffset(); + src_bitMan.FetchSingle( tmp, dst_iter ); + txbuf[n] = tmp; + } + // Commit. + cb( make_const_ref( dst_iter ) ); + } +} + +// Similar to the Send template but fills the buffer using repeated data. +template + requires ( bitmanType::is_const_bitman == false && + requires ( commitCallbackType cb ) { cb(); } ) +BM_AINLINE void RepeatSendCountTo( const putNumberType& val, const countNumberType& count_to, bitmanType& dst_bitman, commitCallbackType&& cb ) + noexcept(requires ( commitCallbackType cb ) { { cb() } noexcept; }) +{ + using bigtx_t = typename biggest_type ::type; + + BitRepetitionCache repcache( val ); + + BitNumberIteratorForStruct val_iter( 0, 0 ); + BitNumberIteratorForStruct val_enditer( count_to / decltype(repcache)::count_contained, 0 ); + + while ( val_iter != val_enditer ) + { + dst_bitman.PutRepeatable( repcache.GetData(), val_iter, val_iter, val_enditer ); + dst_bitman.Flush(); + // Commit. + cb(); + dst_bitman.SetIterator({}); + } +} + +// Performs an one-way receive operation, using a "kickoff"/fill callback. +// Inside the fill callback you can also send data, but this template is mainly designed for reception. +template + requires ( recvBitManType::is_const_bitman == false ) +BM_AINLINE void Receive( recvBitManType& recv_bitman, txbufBitManType& txbuf_bitman, kickoffCallbackType&& kickoffCB ) +{ + using txitem_t = typename eir::biggest_type ::type>::type; + + while ( recv_bitman.IsAtEnd() == false ) + { + // Perform the hardware operation that fills the txbuf_bitman. + auto sharedEndIter = Minimum( recv_bitman.GetRemainderIterator(), txbuf_bitman.GetRemainderIterator() ); + kickoffCB( make_const_ref( sharedEndIter ) ); + // Fetch the data from txbuf_bitman into recv_bitman. + BitNumberIteratorForStruct dst_iter; + BitNumberIteratorForStruct iter; + while ( dst_iter != sharedEndIter ) + { + txitem_t raw = 0u; + txbuf_bitman.FetchSingleSharedRemainder( raw, iter, sharedEndIter ); + recv_bitman.PutRepeatableSharedRemainder( raw, dst_iter, dst_iter, iter ); + } + txbuf_bitman.Reset(); + } +} + +} // namespace BitManagerTemplates + +} // namespace eir + +#endif //_BIT_MANAGE_HEADER_ diff --git a/Marlin/src/HAL/ESP32/sdk/BitManip.h b/Marlin/src/HAL/ESP32/sdk/BitManip.h new file mode 100644 index 000000000000..3588cebed4da --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/BitManip.h @@ -0,0 +1,515 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/BitManip.h +* PURPOSE: Low-level bit manipulation acceleration helpers +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _EIR_BITMANIP_HEADER_ +#define _EIR_BITMANIP_HEADER_ + +#include "MacroUtils.h" +#include "PlatformStrategy.h" +#include "Arith.h" + +#ifdef _DEBUG +#include +#endif + +namespace eir +{ + +template +AINLINE constexpr unsignedNumberType ROTL( unsignedNumberType value, platformLocalBitcountType rotBy ) noexcept +{ +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( __platform_number_supports_brotate ::value ) + { + return __platform_brotate_l( value, rotBy ); + } + else + { +#endif + constexpr platformLocalBitcountType bitCount = sizeof(value) * 8u; + + return ( value << rotBy ) | ( value >> ( bitCount - rotBy ) ); +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif +} +template +AINLINE constexpr unsignedNumberType ROTR( unsignedNumberType value, platformLocalBitcountType rotBy ) noexcept +{ +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( __platform_number_supports_brotate ::value ) + { + return __platform_brotate_r( value, rotBy ); + } + else + { +#endif + constexpr platformLocalBitcountType bitCount = sizeof(value) * 8u; + + return ( value >> rotBy ) | ( value << ( bitCount - rotBy ) ); +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif +} + +template +struct is_bitfield_view : public false_type {}; +template requires ( is_bitfield_view ::type>::value ) +struct is_bitfield_view : public true_type {}; +template +struct plain_type_bitfield : public plain_type {}; +template requires ( is_bitfield_view ::value && is_plain_type ::value == false ) +struct plain_type_bitfield : public plain_type_bitfield ::type> {}; + +// Replaces bits inside of a single unsigned integer. +template + requires ( is_unsigned_integral ::type>::value && + is_unsigned_integral ::type>::value ) +AINLINE constexpr void replace_bits( dstNumType& dst, const srcNumType& src, platformLocalBitcountType bitoff, platformLocalBitcountType bitcnt ) noexcept; + +// Extracts bits from a single unsigned integer. +template + requires ( is_unsigned_integral ::type>::value ) +AINLINE constexpr typename plain_type_bitfield ::type extract_bits( const numberType& val, platformLocalBitcountType bitoff, platformLocalBitcountType bitcnt ) noexcept; + +// numberType has to be unsigned integer. +template +struct BitfieldNumberSelectionView +{ + template friend struct StaticBitfieldNumberSelectionView; + + AINLINE BitfieldNumberSelectionView( numberType *num, platformLocalBitcountType bitoff = 0u, platformLocalBitcountType bitcnt = sizeof(numberType)*8u ) noexcept + : num( num ), bitoff( bitoff ), bitcnt( bitcnt ) + { + return; + } + AINLINE BitfieldNumberSelectionView( const BitfieldNumberSelectionView& view, platformLocalBitcountType bitoff, platformLocalBitcountType bitcnt = sizeof(numberType)*8u ) noexcept + : BitfieldNumberSelectionView( view.num, bitoff, bitcnt ) + { + return; + } + AINLINE BitfieldNumberSelectionView( const BitfieldNumberSelectionView& ) = default; + + AINLINE void Write( typename plain_type ::type val ) noexcept + { + replace_bits( *num, val, this->bitoff, this->bitcnt ); + } + + AINLINE typename plain_type ::type Read( void ) const noexcept + { + return extract_bits( *num, this->bitoff, this->bitcnt ); + } + + AINLINE platformLocalBitcountType GetBitOffset( void ) const noexcept + { + return bitoff; + } + AINLINE platformLocalBitcountType GetBitCount( void ) const noexcept + { + return bitcnt; + } + + // Helpers for nicety. + AINLINE BitfieldNumberSelectionView& operator = ( typename plain_type ::type val ) noexcept + { + this->Write( val ); + return *this; + } + AINLINE operator typename plain_type ::type ( void ) const noexcept + { + return this->Read(); + } + + AINLINE platformLocalBitcountType GetRegionStart( void ) const noexcept + { + return this->bitoff; + } + AINLINE platformLocalBitcountType GetRegionEnd( void ) const noexcept + { + return this->bitoff + this->bitcnt; + } + +private: + numberType *num; + platformLocalBitcountType bitoff; + platformLocalBitcountType bitcnt; +}; + +template +struct is_bitfield_view > : public true_type {}; + +template +struct StaticBitfieldNumberSelectionView +{ + static constexpr platformLocalBitcountType bitcnt = sizeof(insideNumberType)*8u; + + AINLINE StaticBitfieldNumberSelectionView( numberType *num, platformLocalBitcountType bitoff = 0u ) noexcept + : num( num ), bitoff( bitoff ) + { + return; + } + AINLINE StaticBitfieldNumberSelectionView( BitfieldNumberSelectionView *bview ) noexcept + : num( bview->num ), bitoff( bview->bitoff ) + { + return; + } + AINLINE StaticBitfieldNumberSelectionView( const StaticBitfieldNumberSelectionView& ) = default; + + AINLINE void Write( typename plain_type ::type val ) noexcept + { + replace_bits( *num, val, this->bitoff, bitcnt ); + } + + AINLINE typename plain_type ::type Read( void ) const noexcept + { + return (typename plain_type ::type)extract_bits( *num, this->bitoff, bitcnt ); + } + + AINLINE constexpr platformLocalBitcountType GetBitCount( void ) const noexcept + { + return bitcnt; + } + + // Helpers for nicety. + AINLINE StaticBitfieldNumberSelectionView& operator = ( typename plain_type ::type val ) noexcept + { + this->Write( val ); + return *this; + } + AINLINE operator typename plain_type ::type ( void ) const noexcept + { + return this->Read(); + } + + AINLINE platformLocalBitcountType GetRegionStart( void ) const noexcept + { + return this->bitoff; + } + AINLINE platformLocalBitcountType GetRegionEnd( void ) const noexcept + { + return this->bitoff + bitcnt; + } + + template + AINLINE BitfieldNumberSelectionView & SharedBitRegion( platformLocalBitcountType right_start, platformLocalBitcountType right_end ) noexcept + { + platformLocalBitcountType left_start = this->bitoff; + platformLocalBitcountType left_end = left_start + bitcnt; + + return BitfieldNumberSelectionView( this->num, left_start < right_start ? left_start : right_start, left_end < right_end ? left_end : right_end ); + } + +private: + numberType *num; + platformLocalBitcountType bitoff; +}; + +template +struct is_bitfield_view > : public true_type {}; + +// Helper to abstract away bitfield type checking. +template +struct plain_type_bitfield > : public plain_type {}; +template +struct plain_type_bitfield > : public plain_type {}; + +template +AINLINE constexpr platformLocalBitcountType get_bitcount( const numberType& v ) noexcept +{ + if constexpr ( is_bitfield_view ::value ) + { + return v.GetBitCount(); + } + else + { + return sizeof(numberType)*8u; + } +} + +template + requires ( is_unsigned_integral ::type>::value && + is_unsigned_integral ::type>::value ) +AINLINE constexpr void replace_bits( dstNumType& dst, const srcNumType& src, platformLocalBitcountType bitoff, platformLocalBitcountType bitcnt ) noexcept +{ + // bitoff between 0 and sizeof(numberType)*8u + // bitcnt between 1 and sizeof(numberType)*8u + + platformLocalBitcountType src_bitcount = get_bitcount( src ); + platformLocalBitcountType dst_bitcount = get_bitcount( dst ); + +#ifdef _DEBUG + assert( bitcnt <= dst_bitcount ); +#endif + + if ( bitcnt >= dst_bitcount ) + { + dst = (typename plain_type_bitfield ::type)src; + } + else + { + typedef typename plain_type_bitfield ::type srcFastNumType; + typedef typename plain_type_bitfield ::type dstFastNumType; + + // In case of bitfield, do not modify the original value, as the bitfield is a view. + srcFastNumType src_val = src; + + dstFastNumType dst_bitmask; + if ( bitcnt < src_bitcount ) + { + srcFastNumType bitmask = ((srcFastNumType)1u<::value ) + { + dst_val = (dstFastNumType)src_val; + tmp = __platform_brotate_r( dst, bitoff ); + } + else + { +#endif + dst_bitmask <<= bitoff; + dst_val = ((dstFastNumType)src_val << bitoff); + tmp = dst; +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif + tmp &= ~dst_bitmask; + tmp |= dst_val; +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( __platform_number_supports_brotate ::value ) + { + dst = __platform_brotate_l( tmp, bitoff ); + } + else + { +#endif + dst = tmp; +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif + } +} + +template + requires ( is_unsigned_integral ::type>::value ) +AINLINE constexpr typename plain_type_bitfield ::type extract_bits( const numberType& val, platformLocalBitcountType bitoff, platformLocalBitcountType bitcnt ) noexcept +{ + // bitoff between 0 and sizeof(numberType)*8u + // bitcnt between 1 and sizeof(numberType)*8u + + if constexpr ( is_bitfield_view ::value ) + { + return extract_bits( val.Read(), bitoff, bitcnt ); + } + else + { + if ( bitcnt == sizeof(numberType)*8u ) + { + return val; + } + else + { +#ifdef _PLATFORM_HAS_FAST_BITEXTRACT + if constexpr ( __platform_number_supports_bitextract ::value ) + { + return __platform_bitextract( val, bitoff, bitcnt ); + } + else + { +#endif + typedef typename no_volatile ::type fastNumberType; + + fastNumberType bitmask = ((fastNumberType)1u<>= bitoff; + tmp &= bitmask; + return tmp; + } +#ifdef _PLATFORM_HAS_FAST_BITEXTRACT + } +#endif + } +} + +#if defined(_PLATFORM_HAS_FAST_BITREVERSE) +AINLINE constexpr platformNativeWordType reverse_bitorder( platformNativeWordType v ) noexcept +{ + return __platform_bitreverse( v ); +} +template +AINLINE constexpr numberType reverse_bitorder( numberType v ) noexcept +{ + // IDEA: implement the other lesser-sized integer versions using the native word variant and then just perform + // a bit-shift to get the result, resulting in a two-op reverse_bitorder! + + // We assume that all numberType types are sized a power-of-two, meaning that each bigger sized number is + // also at least double the size of platformNativeWordType. + // This optional constexpr-if is fine because both code-graphs would compile anyway. + if constexpr (sizeof(v) > sizeof(platformNativeWordType)) + { + const size_t num_units = sizeof(v) / sizeof(platformNativeWordType); + + numberType result = 0u; + + for (size_t n = 0; n < num_units; n++) + { + platformNativeWordType buf = (platformNativeWordType)( v >> (n * (sizeof(platformNativeWordType)*8u)) ); + buf = __platform_bitreverse(buf); + result |= (numberType)buf << ( (num_units-1) - n ) * (sizeof(platformNativeWordType)*8u); + } + } + else + { + platformNativeWordType buf = v; + buf = __platform_bitreverse(buf); + return (numberType)( buf >> ((sizeof(platformNativeWordType) - sizeof(v)) * 8u) ); + } +} +#else +// Slow but generic variant. +template +constexpr AINLINE numberType reverse_bitorder( numberType v ) noexcept +{ + // MSVC cannot constant evaluate this function. Just wow. + numberType result = 0u; + + for ( platformLocalBitcountType n = 0; n < (platformLocalBitcountType)(sizeof(numberType) * 8u); n++ ) + { + result <<= 1; + result |= v & 0x1; + v >>= 1; + } + return result; +} +#endif + +template requires ( unsigned_integral ::type> ) +struct BitIncrementalAccessor +{ +private: + using fastNumberType = typename nospecmod_type ::type; + +public: + AINLINE BitIncrementalAccessor( void ) noexcept + : data( 0u ), bitoff( 0u ) + {} + AINLINE BitIncrementalAccessor( const BitIncrementalAccessor& ) = default; + AINLINE BitIncrementalAccessor( BitIncrementalAccessor&& ) = default; + + AINLINE BitIncrementalAccessor& operator = ( const BitIncrementalAccessor& ) = default; + AINLINE BitIncrementalAccessor& operator = ( BitIncrementalAccessor&& ) = default; + + AINLINE void SetData( const numberType& data ) noexcept + { + this->data = data; + this->bitoff = 0u; + } + + AINLINE fastNumberType GetData( void ) const noexcept + { +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( mutable_type && __platform_number_supports_brotate ::value ) + { + if ( this->bitoff == 0 ) + { + return this->data; + } + else + { + return __platform_brotate_l( this->data, this->bitoff ); + } + } + else + { +#endif + return this->data; +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif + } + + template + requires ( mutable_type && sizeof(writeNumType) <= sizeof(numberType) ) + AINLINE void WriteBits( writeNumType val, unsigned int bitcnt ) noexcept + { +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( __platform_number_supports_brotate ::value ) + { + if ( bitcnt == sizeof(numberType)*8u ) + { + this->data = val; + } + else + { + fastNumberType data = this->data; + fastNumberType bmask = ( (fastNumberType)1u << bitcnt ) - 1; + data &= ~bmask; + data |= ( val & (writeNumType)bmask ); + this->data = __platform_brotate_r( data, bitcnt ); + } + } + else + { +#endif + replace_bits( this->data, val, this->bitoff, (platformLocalBitcountType)bitcnt ); +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif + this->bitoff = ( this->bitoff + bitcnt ) % ( sizeof(numberType)*8u ); + } + + template requires ( sizeof(readNumType) <= sizeof(numberType) ) + AINLINE readNumType ReadBits( unsigned int bitcnt ) noexcept + { + readNumType val; +#ifdef _PLATFORM_HAS_FAST_BITROTATE + if constexpr ( mutable_type && __platform_number_supports_brotate ::value ) + { + if ( bitcnt == sizeof(numberType)*8u ) + { + val = this->data; + } + else + { + fastNumberType data = this->data; + fastNumberType bmask = ( (fastNumberType)1u << bitcnt ) - 1; + val = ( data & bmask ); + this->data = __platform_brotate_r( data, bitcnt ); + } + } + else + { +#endif + val = (readNumType)extract_bits( this->data, this->bitoff, (platformLocalBitcountType)bitcnt ); +#ifdef _PLATFORM_HAS_FAST_BITROTATE + } +#endif + this->bitoff = ( this->bitoff + bitcnt ) % ( sizeof(numberType)*8u ); + return val; + } + +private: + numberType data; + unsigned int bitoff; +}; + +} // namespace eir + +#endif //_EIR_BITMANIP_HEADER_ \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/sdk/Compare.h b/Marlin/src/HAL/ESP32/sdk/Compare.h new file mode 100644 index 000000000000..69d51439a0e9 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/Compare.h @@ -0,0 +1,231 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/Compare.h +* PURPOSE: Comparison handling helpers. +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _EIRSDK_COMPARE_HEADER_ +#define _EIRSDK_COMPARE_HEADER_ + +#include "MacroUtils.h" +#include "MetaHelpers.h" + +#if __has_include() +#include +#endif + +namespace eir +{ + +// Comparison results. +enum class eCompResult +{ + LEFT_LESS, + EQUAL, + LEFT_GREATER +}; + +#if defined(__cpp_impl_three_way_comparison) +template +static AINLINE orderingTypeName cmpres_to_ordering( eCompResult res ) +{ + switch( res ) + { + case eCompResult::LEFT_LESS: + return orderingTypeName::less; + case eCompResult::LEFT_GREATER: + return orderingTypeName::greater; + default: break; + } + + return orderingTypeName::equivalent; +} +#endif + +AINLINE eCompResult flip_comp_result( eCompResult res ) noexcept +{ + if ( res == eCompResult::LEFT_LESS ) + { + return eCompResult::LEFT_GREATER; + } + else if ( res == eCompResult::LEFT_GREATER ) + { + return eCompResult::LEFT_LESS; + } + + return eCompResult::EQUAL; +} + +#define EIR_VALCMP( left, right ) \ + { \ + auto cmpRes = eir::DefaultValueCompare( left, right ); \ + if ( cmpRes != eir::eCompResult::EQUAL ) \ + { \ + return cmpRes; \ + } \ + } +#define EIR_VALCMP_LT( _cmpVal ) \ + { \ + eir::eCompResult cmpVal = _cmpVal; \ + if ( cmpVal != eir::eCompResult::EQUAL ) \ + { \ + return ( cmpVal == eir::eCompResult::LEFT_LESS ); \ + } \ + } + +template +concept less_than_comparable = requires ( A a, B b ) { { a < b } -> same_as ; }; +template +concept nothrow_less_than_comparable = requires ( A a, B b ) { { a < b } noexcept -> same_as ; }; + +template +concept greater_than_comparable = requires ( A a, B b ) { { a > b } -> same_as ; }; +template +concept nothrow_greater_than_comparable = requires ( A a, B b ) { { a > b } noexcept -> same_as ; }; + +template +concept equality_comparable = requires ( A a, B b ) { { a == b } -> same_as ; }; +template +concept nothrow_equality_comparable = requires ( A a, B b ) { { a == b } noexcept -> same_as ; }; + +template +concept three_way_comparable = +#if defined(__cpp_impl_three_way_comparison) + requires( LT l, RT r ) { l <=> r; }; +#else + less_than_comparable && equality_comparable && greater_than_comparable ; +#endif +template +concept nothrow_three_way_comparable = +#if defined(__cpp_impl_three_way_comparison) + requires( LT l, RT r ) { { l <=> r } noexcept; }; +#else + nothrow_less_than_comparable && nothrow_equality_comparable && nothrow_greater_than_comparable ; +#endif + +// Basic function. +template requires ( three_way_comparable ) +AINLINE eCompResult DefaultValueCompare( const leftType& left, const rightType& right ) noexcept(nothrow_three_way_comparable ) +{ +#if defined(__cpp_impl_three_way_comparison) + auto wo = ( left <=> right ); + + if ( std::is_lt( wo ) ) + { + return eCompResult::LEFT_LESS; + } + else if ( std::is_gt( wo ) ) + { + return eCompResult::LEFT_GREATER; + } +#else + if ( left < right ) + { + return eCompResult::LEFT_LESS; + } + else if ( left > right ) + { + return eCompResult::LEFT_GREATER; + } +#endif + + // TODO: think about the case of comparing floats of the "partial ordering" scenario (NaN, etc). + + return eCompResult::EQUAL; +} + +namespace CompareUtils +{ + +template +struct select_minimum_target_type : types_find_conversion_target > {}; +template +struct select_minimum_target_type : smallest_type {}; + +} // namespace CompareUtils + +template +struct types_less_than_comparable : true_type {}; +template +struct types_less_than_comparable > : types_less_than_comparable {}; +template +struct types_less_than_comparable + : conditional && (less_than_comparable && ...), + types_less_than_comparable , + false_type + >::type {}; + +template +struct types_nothrow_less_than_comparable : true_type {}; +template +struct types_nothrow_less_than_comparable > : types_nothrow_less_than_comparable {}; +template +struct types_nothrow_less_than_comparable + : conditional && (nothrow_less_than_comparable && ...), + types_nothrow_less_than_comparable , + false_type + >::type {}; + +template + requires ( sizeof...(numberTypes) > 0 && types_find_conversion_target ::type...>>::value && types_less_than_comparable ::type...>::value ) +AINLINE auto Minimum( numberTypes&&... values ) + noexcept(types_nothrow_less_than_comparable ::type...>::value) +{ + typename types_find_conversion_target ::type...>>::type result = + select_from <0> ( castforward ( values )... ); + + auto metalamb = [&] ( index_sequence ) LAINLINE + { + auto lamb = [&] ( T&& val ) LAINLINE + { + if constexpr ( N > 0 ) + { + if ( val < result ) + { + result = castforward ( val ); + } + } + }; + ( lamb.template operator() ( castforward ( values ) ), ... ); + }; + metalamb( index_sequence_until () ); + + return (typename CompareUtils::select_minimum_target_type ::type...>::type)result; +} + +template + requires ( sizeof...(numberTypes) > 0 && types_find_conversion_target ::type...>>::value && types_less_than_comparable ::type...>::value ) +AINLINE auto Maximum( numberTypes&&... values ) + noexcept(types_nothrow_less_than_comparable ::type...>::value) +{ + typename types_find_conversion_target ::type...>>::type result = + select_from <0> ( castforward ( values )... ); + + auto metalamb = [&] ( index_sequence ) LAINLINE + { + auto lamb = [&] ( T&& val ) LAINLINE + { + if constexpr ( N > 0 ) + { + if ( result < val ) + { + result = castforward ( val ); + } + } + }; + ( lamb.template operator() ( castforward ( values ) ), ... ); + }; + metalamb( index_sequence_until () ); + + return result; +} + +} // namespace eir + +#endif //_EIRSDK_COMPARE_HEADER_ \ No newline at end of file diff --git a/Marlin/src/HAL/ESP32/sdk/Endian.h b/Marlin/src/HAL/ESP32/sdk/Endian.h new file mode 100644 index 000000000000..c4d170be19f2 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/Endian.h @@ -0,0 +1,258 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/Endian.h +* PURPOSE: Endianness utilities header +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _ENDIAN_COMPAT_HEADER_ +#define _ENDIAN_COMPAT_HEADER_ + +#include "MacroUtils.h" +#include "PlatformStrategy.h" // for _PLATFORM_FIXED_ENDIANNESS, intrinsics + +// For the inline functions. +#include +#include // for (u)int8/16/32/64_t + +#include +#if __has_include() +#include +#endif + +namespace eir +{ + +// Endianness compatibility definitions. +namespace endian +{ + +#ifdef _PLATFORM_FIXED_ENDIANNESS +#define _ENDIAN_CONSTEXPR constexpr +#else +#define _ENDIAN_CONSTEXPR +#endif + +#if defined(_PLATFORM_FIXED_ENDIANNESS) && defined(__cpp_if_constexpr) +#define _ENDIAN_IF_CONSTEXPR constexpr +#endif + +#if defined(__GNUC__) +#undef LITTLE_ENDIAN +#undef BIG_ENDIAN +#endif + + enum class eSpecificEndian + { + LITTLE_ENDIAN, + BIG_ENDIAN, +#if defined(_PLATFORM_FIXED_ENDIANNESS_ENFORCE_LE) + DEFAULT_ENDIAN = LITTLE_ENDIAN +#elif defined(_PLATFORM_FIXED_ENDIANNESS_ENFORCE_BE) + DEFAULT_ENDIAN = BIG_ENDIAN +#else + // Most of the systems are little-endian nowadays, which has advantages over big-endian. + DEFAULT_ENDIAN = LITTLE_ENDIAN +#endif + }; + + AINLINE static _ENDIAN_CONSTEXPR eSpecificEndian get_current_endianness( void ) noexcept + { +#ifdef _PLATFORM_FIXED_ENDIANNESS +#if defined(_PLATFORM_FIXED_ENDIANNESS_ENFORCE_LE) + return eSpecficEndian::LITTLE_ENDIAN; +#elif defined(_PLATFORM_FIXED_ENDIANNESS_ENFORCE_BE) + return eSpecificEndian::BIG_ENDIAN; +#else + // This does only make sense if the platform does specify endianness. + static_assert( std::endian::native == std::endian::little || std::endian::native == std::endian::big ); + + // Thanks to new C++ features we have this one in the bag! + return ( std::endian::native == std::endian::little ) ? eSpecificEndian::LITTLE_ENDIAN : eSpecificEndian::BIG_ENDIAN; +#endif +#else + // Calculate the endianness dynamically at run-time. + union + { + uint16_t val = 0x0102; + uint8_t low; + }; + return ( low == 0x02 ) ? eSpecificEndian::LITTLE_ENDIAN : eSpecificEndian::BIG_ENDIAN; +#endif + } + + AINLINE static _ENDIAN_CONSTEXPR bool is_little_endian( void ) noexcept + { + return ( get_current_endianness() == eSpecificEndian::LITTLE_ENDIAN ); + } + + template + AINLINE constexpr typename base_type ::type byte_swap_fast( numberType val ) noexcept + { +#ifdef _PLATFORM_HAS_FAST_BYTESWAP + if constexpr ( __platform_number_supports_byteswap ::value ) + { + return __platform_byteswap( val ); + } + else + { +#endif +#ifdef __cpp_lib_byteswap + // If we don't have the fast platform byteswap implementation then we could default to the C++ standard + // implementation which might not be as fast but still pretty fine. + return std::byteswap( val ); +#else + if constexpr ( sizeof(numberType) == 1 ) + { + return val; + } + else + { + // I guess that this version could be better because it does not force use of memory, or a compiler who could + // stil retranslate it back to register operations. + numberType result = 0; + + for ( unsigned int n = 0; n < sizeof(numberType); n++ ) + { + result |= val & 0xFF; + val >>= 8u; + result <<= 8u; + } + + return result; + } +#endif +#ifdef _PLATFORM_HAS_FAST_BYTESWAP + } +#endif + } + + // Aligned big_endian number type. + template + requires ( std::is_trivially_constructible ::value ) + struct big_endian + { + // Required to be default for POD handling. + inline big_endian( void ) = default; + inline big_endian( const big_endian& ) = default; + inline big_endian( big_endian&& ) = default; + + private: + AINLINE void assign_data( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + if _ENDIAN_IF_CONSTEXPR ( is_little_endian() ) + { + *(numberType*)&this->data[0] = byte_swap_fast( right ); + } + else + { + *(numberType*)&this->data[0] = right; + } + } + + public: + inline big_endian( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + assign_data( right ); + } + + inline operator numberType ( void ) const noexcept(nothrow_constructible_from ) + { + if _ENDIAN_IF_CONSTEXPR ( is_little_endian() ) + { + return byte_swap_fast( *(const numberType*)&this->data[0] ); + } + else + { + return *(numberType*)&this->data[0]; + } + } + + inline big_endian& operator = ( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + assign_data( right ); + + return *this; + } + + inline big_endian& operator = ( const big_endian& ) = default; + inline big_endian& operator = ( big_endian&& ) = default; + + private: + alignas(typename conditional ::type) char data[ sizeof(numberType) ]; + }; + + // Aligned little_endian number type. + template + requires ( std::is_trivially_constructible ::value ) + struct little_endian + { + // Required to be default for POD handling. + inline little_endian( void ) = default; + inline little_endian( const little_endian& ) = default; + inline little_endian( little_endian&& ) = default; + + private: + AINLINE void assign_data( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + if _ENDIAN_IF_CONSTEXPR ( !is_little_endian() ) + { + *(numberType*)&this->data[0] = byte_swap_fast( right ); + } + else + { + *(numberType*)&this->data[0] = right; + } + } + + public: + inline little_endian( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + assign_data( right ); + } + + inline operator numberType ( void ) const noexcept(nothrow_constructible_from ) + { + if _ENDIAN_IF_CONSTEXPR ( !is_little_endian() ) + { + return byte_swap_fast( *(const numberType*)&this->data[0] ); + } + else + { + return *(numberType*)&this->data[0]; + } + } + + inline little_endian& operator = ( const numberType& right ) noexcept(nothrow_copy_assignable_with ) + { + assign_data( right ); + + return *this; + } + + inline little_endian& operator = ( const little_endian& ) = default; + inline little_endian& operator = ( little_endian&& ) = default; + + private: + alignas(typename conditional ::type) char data[ sizeof(numberType) ]; + }; + + // Shortcuts for the packed endian structs for use in packed serialization structs. + template + using p_big_endian = big_endian ; + + template + using p_little_endian = little_endian ; +}; + +}; // namespace eir + +// For compatibility with older code. +namespace endian = eir::endian; + +#endif //_ENDIAN_COMPAT_HEADER_ diff --git a/Marlin/src/HAL/ESP32/sdk/MacroUtils.h b/Marlin/src/HAL/ESP32/sdk/MacroUtils.h new file mode 100644 index 000000000000..7b3dec0527a0 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/MacroUtils.h @@ -0,0 +1,72 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/MacroUtils.h +* PURPOSE: Common macros in the SDK +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _COMMON_MACRO_UTILITIES_ +#define _COMMON_MACRO_UTILITIES_ + +// Basic always inline definition. +#ifndef AINLINE +#ifdef _MSC_VER +#define AINLINE __forceinline +#elif defined(__GNUC__) +#ifdef _DEBUG +#define AINLINE inline +#else +#define AINLINE inline __attribute__((always_inline)) +#endif +#else +#define AINLINE inline +#endif +#endif + +#ifndef LAINLINE +#ifdef _MSC_VER +#define LAINLINE [[msvc::forceinline]] +#elif defined(__linux__) +#define LAINLINE __attribute__((always_inline)) +#else +#define LAINLINE +#endif +#endif + +#ifdef _MSC_VER +#define PTR_NO_ALIAS __restrict +#elif defined(__GNUC__) +#define PTR_NO_ALIAS __restrict__ +#else +#define PTR_NO_ALIAS +#endif + +#ifndef _MSC_VER +#define abstract +#endif + +#ifndef countof +#define countof(x) (sizeof(x)/sizeof(*x)) +#endif + +// Compatibility macros for certain compilers. +#ifdef __GNUC__ +#define _GCCCOMPAT_CONSTINIT_FUNCDECL_ +#else +#define _GCCCOMPAT_CONSTINIT_FUNCDECL_ constinit +#endif //_GCC_ + +// Fix bugs of the broken MSVC compiler that annoys me because they cannot get C++20 concept evaluation implemented properly. +// Their lexer fails anyway! +#ifdef _MSC_VER +#define _MSVC_BUGFIX(x) +#else +#define _MSVC_BUGFIX(x) x +#endif + +#endif //_COMMON_MACRO_UTILITIES_ diff --git a/Marlin/src/HAL/ESP32/sdk/MemoryRaw.h b/Marlin/src/HAL/ESP32/sdk/MemoryRaw.h new file mode 100644 index 000000000000..bc5aaad1ba58 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/MemoryRaw.h @@ -0,0 +1,135 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* FILE: eirrepo/sdk/MemoryRaw.h +* PURPOSE: Base memory management definitions for to-the-metal things +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* +*****************************************************************************/ + +#ifndef _MEMORY_RAW_DEFS_ +#define _MEMORY_RAW_DEFS_ + +#include +#if __has_include() +#include // for std::has_single_bit +#endif +#include + +#include "MetaHelpers.h" +#include "MacroUtils.h" + +// Macro that defines how alignment works. +// num: base of the number to be aligned +// sector: aligned-offset that should be added to num +// align: number of bytes to align to +// EXAMPLE: ALIGN( 0x1001, 4, 4 ) -> 0x1004 (equivalent of compiler structure padding alignment) +// ALIGN( 0x1003, 1, 4 ) -> 0x1000 +// ALIGN( 0x1003, 2, 4 ) -> 0x1004 +template +AINLINE numberType _ALIGN_GP( numberType num, numberType sector, numberType align ) +{ + // General purpose alignment routine. + // Not as fast as the bitfield version. + numberType sectorOffset = ((num) + (sector) - 1); + + return sectorOffset - ( sectorOffset % align ); +} + +template +AINLINE numberType _ALIGN_NATIVE( numberType num, numberType sector, numberType align ) +{ +#if defined(__cpp_lib_int_pow2) + // assume math based on x86 bits. + if ( std::has_single_bit( align ) ) + { + //bitfield version. not compatible with non-bitfield alignments. + return (((num) + (sector) - 1) & (~((align) - 1))); + } + else + { +#endif + return _ALIGN_GP( num, sector, align ); +#if defined(__cpp_lib_int_pow2) + } +#endif +} + +template +AINLINE numberType ALIGN( numberType num, numberType sector, numberType align ) +{ + if constexpr ( eir::same_as || + eir::same_as || + eir::same_as || + eir::same_as ) + { + return _ALIGN_NATIVE( num, sector, align ); + } + else + { + return _ALIGN_GP( num, sector, align ); + } +} + +// Helper macro (equivalent of EXAMPLE 1) +template +inline numberType ALIGN_SIZE( numberType num, numberType sector ) +{ + return ( ALIGN( (num), (sector), (sector) ) ); +} + +// Aligning things to the boundary below. +template +AINLINE numberType SCALE_DOWN( numberType value, numberType modval ) noexcept +{ + // This is faster than divide-and-multiply, plus it does exactly the same. + numberType rem = ( value % modval ); + + return ( value - rem ); +} + +template +AINLINE numberType CEIL_DIV( numberType val, divNumberType div ) +{ + return ( ( val + ( div - 1 ) ) / div ); +} + +// Safely casting integers between each others, with clamping to bounds. +template +AINLINE destIntegerType TRANSFORM_INT_CLAMP( srcIntegerType value ) +{ + typedef typename eir::make_signed ::type srcIntegerSigned_t; + typedef typename eir::make_unsigned ::type srcIntegerUnsigned_t; + + typedef typename eir::make_signed ::type destIntegerSigned_t; + typedef typename eir::make_unsigned ::type destIntegerUnsigned_t; + + constexpr srcIntegerUnsigned_t src_max = (srcIntegerUnsigned_t)eir::numeric_limits ::MAX; + constexpr srcIntegerSigned_t src_min = (srcIntegerSigned_t)eir::numeric_limits ::MIN; + + constexpr destIntegerUnsigned_t dest_max = (destIntegerUnsigned_t)eir::numeric_limits ::MAX; + constexpr destIntegerSigned_t dest_min = (destIntegerSigned_t)eir::numeric_limits ::MIN; + + // We assume that all unsigned integer types start at 0, all maximum values of ranges are non-negative. + + if constexpr ( dest_max < src_max ) + { + if ( value > (srcIntegerType)dest_max ) + { + return dest_max; + } + } + + if constexpr ( dest_min > src_min ) + { + if ( value < (srcIntegerType)dest_min ) + { + return dest_min; + } + } + + return (destIntegerType)value; +} + +#endif //_MEMORY_RAW_DEFS_ diff --git a/Marlin/src/HAL/ESP32/sdk/MetaHelpers.h b/Marlin/src/HAL/ESP32/sdk/MetaHelpers.h new file mode 100644 index 000000000000..b8834d3e1a36 --- /dev/null +++ b/Marlin/src/HAL/ESP32/sdk/MetaHelpers.h @@ -0,0 +1,1228 @@ +/***************************************************************************** +* +* PROJECT: Eir SDK +* LICENSE: See LICENSE in the top level directory +* FILE: eirrepo/sdk/MetaHelpers.h +* PURPOSE: Memory management templates and other utils. +* +* Find the Eir SDK at: https://osdn.net/projects/eirrepo/ +* Multi Theft Auto is available from http://www.multitheftauto.com/ +* +*****************************************************************************/ + +#ifndef _COMMON_META_PROGRAMMING_HELPERS_ +#define _COMMON_META_PROGRAMMING_HELPERS_ + +#if __has_include() +#include +#endif + +#if __has_include() +#include +#endif + +#include "MacroUtils.h" + +#if __has_include() +#include +#endif +#include +#include + +namespace eir +{ + +template +struct index_sequence {}; + +template +struct index_sequence_until {}; +template +struct index_sequence_until <0, IDX...> : index_sequence {}; +template +struct index_sequence_until : index_sequence_until {}; + + +template +struct type_identity +{ + typedef T type; +}; + +struct true_type +{ + static const constexpr bool value = true; +}; +struct false_type +{ + static const constexpr bool value = false; +}; + +template +struct is_same_as : public false_type {}; +template +struct is_same_as : public true_type {}; + +template +concept same_as = is_same_as ::value; + +template +struct typelist +{ + static constexpr auto count = sizeof...(Ts); + + template + AINLINE static constexpr bool ForEach( callbackType&& cb ) + { + bool success = false; + + if constexpr ( sizeof... (Ts) > 0 ) + { + auto lamb = [&] () LAINLINE + { + if ( success == false ) + { + if ( cb.template operator() () ) success = true; + } + }; + + ( lamb.template operator() (), ... ); + } + + return success; + } +}; +template +struct is_typelist : false_type {}; +template +struct is_typelist > : true_type {}; +// do not allow specialization-cv, references, pointers-to, etc.. + +template +concept typelist_type = is_typelist ::value; + +template +struct sequence_contains : public false_type {}; +template +struct sequence_contains > : public sequence_contains {}; +template +struct sequence_contains : public true_type {}; +template +struct sequence_contains : public sequence_contains {}; + +template +struct sequence_get {}; +template +struct sequence_get > : public sequence_get {}; +template +struct sequence_get <0, typelist > : public sequence_get <0, Ts...> {}; +template +struct sequence_get <0, T, Ts...> +{ + typedef T type; +}; +template +struct sequence_get : public sequence_get {}; + +template +struct remove_reference +{ + typedef T type; +}; +template +struct remove_reference : public remove_reference {}; +template +struct remove_reference : public remove_reference {}; + +template +AINLINE constexpr typename remove_reference ::type&& castmove( T&& v ) noexcept { return (typename remove_reference ::type&&)v; } + +template +struct is_any_ref : false_type {}; +template +struct is_any_ref : true_type {}; +template +struct is_any_ref : true_type {}; + +// You may be wondering why I called this "castforward" instead of the equivalent "forward". +// For once I wanted to combat the malicious "using namespace std;" statement. +// On the other hand, the MSVC compiler suffers from some ambiguity look-up issue regarding "forward" templated-specifier by itself, +// causing a misdetection of "std::forward" as possible candidate, causing compilation failure. +// So to be on the safe side avoid name-collision with std-namespace things! +template +AINLINE constexpr T&& castforward( typename remove_reference ::type& v ) noexcept { return static_cast ( v ); } +template +AINLINE constexpr T&& castforward( typename remove_reference ::type&& v ) noexcept { return static_cast ( v ); } + +template +concept nothrow_move_assignable_with = requires ( To& a, From b ) { { a = castmove(b) } noexcept; }; + +template +concept copy_assignable_with = requires ( To& a, const From b ) { a = b; }; + +template +concept nothrow_copy_assignable_with = requires ( To& a, const From b ) { { a = b } noexcept; }; + +template +struct no_volatile : type_identity {}; +template +struct no_volatile : public no_volatile {}; +template +struct no_volatile > + : public type_identity ::type...>> {}; + +template +struct is_volatile : false_type {}; +template +struct is_volatile : true_type {}; +template +struct is_volatile : true_type {}; +template +struct is_volatile : true_type {}; + +template +concept volatile_type = is_volatile ::value; + +template +struct no_const +{ + typedef T type; +}; +template +struct no_const : public no_const {}; +template +struct no_const > + : public type_identity ::type...>> {}; + +template +struct is_const : false_type {}; +template +struct is_const : true_type {}; +template +struct is_const : true_type {}; +template +struct is_const : true_type {}; + +template +concept const_type = is_const ::value; +template +concept mutable_type = ( is_const ::value == false ); + +template +AINLINE constexpr const T& make_const_ref( T& v ) noexcept { return v; } + +template requires ( sizeof...(Ts) > 0 && N < sizeof...(Ts) ) +AINLINE constexpr typename sequence_get ::type&& select_from( Ts&&... args ) noexcept +{ + auto lamb = [&] ( auto& lamb, T&& sel, subTs&&... next ) LAINLINE -> typename sequence_get ::type&& + { + if constexpr ( IDX == N ) + { + return castforward ( sel ); + } + else + { + return lamb.template operator() ( lamb, castforward ( next )... ); + } + }; + + return lamb.template operator() <0> ( lamb, castforward ( args )... ); +} + +typedef typelist known_signed_integrals; +typedef typelist known_unsigned_integrals; + +template +struct find_sizeof_equal_type : false_type {}; +template +struct find_sizeof_equal_type > : find_sizeof_equal_type {}; +template requires ( sizeof(T) == SZ ) +struct find_sizeof_equal_type : type_identity , true_type {}; +template requires ( sizeof(T) != SZ ) +struct find_sizeof_equal_type : find_sizeof_equal_type {}; + +template +concept sizeof_equal_type = find_sizeof_equal_type >::value; + +#if __has_include() && !defined(_EIRSDK_PREFER_NATIVE_IMPL) +template +struct is_unsigned_integral +{ + static constexpr bool value = ( std::is_unsigned ::value && std::is_integral ::value ); +}; +#else +template +struct is_unsigned_integral : sequence_contains {}; +#endif + +template +concept unsigned_integral = is_unsigned_integral ::value; + +#if __has_include() && !defined(_EIRSDK_PREFER_NATIVE_IMPL) +template +struct is_signed_integral +{ + static constexpr bool value = ( std::is_signed ::value && std::is_integral ::value ); +}; +#else +template +struct is_signed_integral : sequence_contains {}; +#endif + +template +concept signed_integral = is_signed_integral ::value; + +template +concept integral_type = unsigned_integral || signed_integral ; + +#if __has_include() && !defined(_EIRSDK_PREFER_NATIVE_IMPL) +template +struct make_signed_integral +{ + typedef typename std::enable_if ::value, typename std::make_signed ::type>::type type; +}; +#else +template +struct make_signed_integral {}; +template +struct make_signed_integral : type_identity {}; +template <> +struct make_signed_integral : type_identity {}; +template <> +struct make_signed_integral : type_identity {}; +template <> +struct make_signed_integral : type_identity {}; +template <> +struct make_signed_integral : type_identity {}; +template <> +struct make_signed_integral : type_identity {}; +#endif + +template +struct make_signed : type_identity {}; +template +struct make_signed : make_signed_integral {}; + +#if __has_include() && !defined(_EIRSDK_PREFER_NATIVE_IMPL) +template +struct make_unsigned_integral +{ + typedef typename std::enable_if ::value, typename std::make_unsigned ::type>::type type; +}; +#else +template +struct make_unsigned_integral {}; +template +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +template <> +struct make_unsigned_integral : type_identity {}; +#endif + +template +struct make_unsigned : type_identity {}; +template +struct make_unsigned : make_unsigned_integral {}; + +// Converts to the underlying type, throwing away any array-spec, pointer-spec, reference, etc. +template +struct plain_type +{ + typedef T type; +}; +template requires ( is_const ::value == false ) +struct plain_type : public plain_type {}; +template +struct plain_type : public plain_type {}; +template +struct plain_type : public plain_type {}; +template +struct plain_type : public plain_type {}; +template +struct plain_type : public plain_type {}; +template +struct plain_type : public plain_type {}; + +// Converts to the underlying type of const/volatile/reference types. +template +struct base_type +{ + typedef T type; +}; +template requires ( is_volatile ::value == false ) +struct base_type : public base_type {}; +template +struct base_type : public base_type {}; +template +struct base_type : public base_type {}; +template +struct base_type : public base_type {}; + +// Converts to the type without specification modification (const, volatile, etc). +template +struct nospecmod_type +{ + typedef T type; +}; +template requires ( is_volatile ::value == false ) +struct nospecmod_type : nospecmod_type {}; +template +struct nospecmod_type : nospecmod_type {}; + +// Checks if a type is POD. +template +struct is_pod_type : public false_type {}; +template +struct is_pod_type : public true_type {}; +template <> +struct is_pod_type : public true_type {}; +template <> +struct is_pod_type : public true_type {}; +template <> +struct is_pod_type : public true_type {}; +template +struct is_pod_type : public is_pod_type {}; +template +struct is_pod_type : public is_pod_type {}; +template +struct is_pod_type : public is_pod_type {}; +template +struct is_pod_type : public is_pod_type {}; +template +struct is_pod_type : public true_type {}; + +template +struct conditional +{ + typedef false_type type; +}; +template +struct conditional +{ + typedef true_type type; +}; + +// Returns the first biggest type in the list. +template +struct biggest_type +{ + typedef void type; +}; +template +struct biggest_type +{ + typedef BT type; +}; +template +struct biggest_type + : public biggest_type = sizeof(T)), BT, T>::type, Ts...> {}; + +template +struct biggest_type > : public biggest_type {}; + +// Returns the first smallest type in the list. +template +struct smallest_type +{ + typedef void type; +}; +template +struct smallest_type +{ + typedef ST type; +}; +template +struct smallest_type + : public smallest_type ::type, Ts...> {}; + +template +struct smallest_type > : public smallest_type {}; + +// Filter template for type-list operations. +template