diff --git a/Marlin/src/HAL/HC32F46x/HAL.cpp b/Marlin/src/HAL/HC32F46x/HAL.cpp index 94408afae321..c27f827a86ad 100644 --- a/Marlin/src/HAL/HC32F46x/HAL.cpp +++ b/Marlin/src/HAL/HC32F46x/HAL.cpp @@ -1,10 +1,12 @@ #include "HAL.h" +#include +#include // // Emergency Parser // #if ENABLED(EMERGENCY_PARSER) -extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart) +extern "C" void core_hook_usart_rx_irq(uint8_t ch, uint8_t usart) { // only handle receive on host serial ports if (false @@ -27,3 +29,16 @@ extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart) emergency_parser.update(MYSERIAL1.emergency_state, ch); } #endif + +// +// panic hook +// +extern "C" void core_hook_panic_end() +{ + // print '!!' to signal error to host + // do it 10x so it's not missed + for (int i = 0; i < 10; i++) + { + panic_printf("\n!!\n"); + } +} diff --git a/Marlin/src/HAL/HC32F46x/HAL.h b/Marlin/src/HAL/HC32F46x/HAL.h index 58fa7e3ea390..346b8085743f 100644 --- a/Marlin/src/HAL/HC32F46x/HAL.h +++ b/Marlin/src/HAL/HC32F46x/HAL.h @@ -21,8 +21,10 @@ * */ -/** - * HAL for stm32duino.com based on Libmaple and compatible (HC32F46x based on STM32F1) +/** + * HAL for HC32F46x based boards + * + * Note: MarlinHAL class is in MarlinHAL.h/cpp */ #define CPU_32_BIT @@ -103,7 +105,6 @@ extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart); // // Misc. Defines // -#define STM32_FLASH_SIZE 256 #define square(x) ((x) * (x)) #ifndef strncpy_P @@ -117,6 +118,7 @@ extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart); #define analogInputToDigitalPin(p) (p) #endif +//TODO: digitalPinHasPWM is not implemented #ifndef digitalPinHasPWM #define digitalPinHasPWM(P) (P) //(PIN_MAP[P].timer_device != nullptr) #endif diff --git a/Marlin/src/HAL/HC32F46x/HAL_SPI.cpp b/Marlin/src/HAL/HC32F46x/HAL_SPI.cpp deleted file mode 100644 index 4825373041eb..000000000000 --- a/Marlin/src/HAL/HC32F46x/HAL_SPI.cpp +++ /dev/null @@ -1,199 +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 TARGET_HC32F46x - -#include "../../inc/MarlinConfig.h" -#ifdef USE_SPI -#warning "'HAL_SPI' has not been tested to work as expected. Proceed at your own risk" - -#include - -// ------------------------ -// Public functions -// ------------------------ - -#if ENABLED(SOFTWARE_SPI) - -// ------------------------ -// Software SPI -// ------------------------ -#error "Software SPI not supported for HC32F46x. 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(SS) - OUT_WRITE(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) -{ -/** - * 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); -} - -/** - * @brief Receive a single byte from the SPI port. - * - * @return Byte received - * - * @details - */ -uint8_t spiRec() -{ - uint8_t returnByte = SPI.transfer(ff); - 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(ff); } - -// 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 -#endif // TARGET_HC32F46x diff --git a/Marlin/src/HAL/HC32F46x/MarlinHAL.cpp b/Marlin/src/HAL/HC32F46x/MarlinHAL.cpp index dcd19ecd07ca..34e768917163 100644 --- a/Marlin/src/HAL/HC32F46x/MarlinHAL.cpp +++ b/Marlin/src/HAL/HC32F46x/MarlinHAL.cpp @@ -4,47 +4,133 @@ #ifdef TARGET_HC32F46x #include "HAL.h" -#include "hc32f460_wdt.h" +#include +#include +#include #include "../../inc/MarlinConfig.h" -#include "soctemp.h" extern "C" char *_sbrk(int incr); -enum TEMP_PINS +void HAL_wdt_callback() { - TEMP_BED = 14, - TEMP_0 = 15, -}; + panic("WDT timeout"); + NVIC_SystemReset(); +} + +inline void HAL_clock_frequencies_dump() +{ + // 1. dump all clock frequencies + update_system_clock_frequencies(); + SERIAL_ECHOPGM("-- clocks dump -- \nSYS="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.system); + SERIAL_ECHOPGM("\nHCLK="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.hclk); + SERIAL_ECHOPGM("\nPCLK0="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.pclk0); + SERIAL_ECHOPGM("\nPCLK1="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.pclk1); + SERIAL_ECHOPGM("\nPCLK2="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.pclk2); + SERIAL_ECHOPGM("\nPCLK3="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.pclk3); + SERIAL_ECHOPGM("\nPCLK4="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.pclk4); + SERIAL_ECHOPGM("\nEXCLK="); + SERIAL_ECHO(SYSTEM_CLOCK_FREQUENCIES.exclk); + SERIAL_ECHOPGM("\nF_CPU="); + SERIAL_ECHO(F_CPU); + + // 2. dump current system clock source + en_clk_sys_source_t clkSrc = CLK_GetSysClkSource(); + SERIAL_ECHOPGM("\nSYSCLK="); + switch (clkSrc) + { + case ClkSysSrcHRC: + SERIAL_ECHOPGM("HRC"); + break; + case ClkSysSrcMRC: + SERIAL_ECHOPGM("MRC"); + break; + case ClkSysSrcLRC: + SERIAL_ECHOPGM("LRC"); + break; + case ClkSysSrcXTAL: + SERIAL_ECHOPGM("XTAL"); + break; + case ClkSysSrcXTAL32: + SERIAL_ECHOPGM("XTAL32"); + break; + case CLKSysSrcMPLL: + SERIAL_ECHOPGM("MPLL"); + + // 3. if MPLL is used, dump MPLL settings: + // (derived from CLK_SetPllSource and CLK_MpllConfig) + // source + switch (M4_SYSREG->CMU_PLLCFGR_f.PLLSRC) + { + case ClkPllSrcXTAL: + SERIAL_ECHOPGM(",XTAL"); + break; + case ClkPllSrcHRC: + SERIAL_ECHOPGM(",HRC"); + break; + default: + break; + } + + // PLL multiplies and dividers + SERIAL_ECHOPGM("\nP="); + SERIAL_ECHO(M4_SYSREG->CMU_PLLCFGR_f.MPLLP + 1ul); + SERIAL_ECHOPGM("\nQ="); + SERIAL_ECHO(M4_SYSREG->CMU_PLLCFGR_f.MPLLQ + 1ul); + SERIAL_ECHOPGM("\nR="); + SERIAL_ECHO(M4_SYSREG->CMU_PLLCFGR_f.MPLLR + 1ul); + SERIAL_ECHOPGM("\nN="); + SERIAL_ECHO(M4_SYSREG->CMU_PLLCFGR_f.MPLLN + 1ul); + SERIAL_ECHOPGM("\nM="); + SERIAL_ECHO(M4_SYSREG->CMU_PLLCFGR_f.MPLLM + 1ul); + break; + default: + break; + } + + // done + SERIAL_ECHOPGM("\n--\n"); +} + +// +// MarlinHAL class implementation +// -uint16_t MarlinHAL::adc_result; +pin_t MarlinHAL::last_adc_pin; MarlinHAL::MarlinHAL() {} void MarlinHAL::watchdog_init() { #if ENABLED(USE_WATCHDOG) - stc_wdt_init_t wdtConf = { - .enCountCycle = WdtCountCycle65536, - .enClkDiv = WdtPclk3Div8192, - .enRefreshRange = WdtRefresh100Pct, - .enSleepModeCountEn = Disable, - .enRequestType = WdtTriggerResetRequest}; - WDT_Init(&wdtConf); - WDT_RefreshCounter(); + // 5s timeout, panic on timeout + WDT.begin(5000, &HAL_wdt_callback); #endif } void MarlinHAL::watchdog_refresh() { #if ENABLED(USE_WATCHDOG) - WDT_RefreshCounter(); + WDT.reload(); #endif } void MarlinHAL::init() { NVIC_SetPriorityGrouping(0x3); - SOCTemp::init(); + + // print clock frequencies to host serial + HAL_clock_frequencies_dump(); + + // start OTS, min. 1s between reads + ChipTemperature.begin(); + ChipTemperature.setMinimumReadDeltaMillis(1000); } void MarlinHAL::init_board() {} @@ -79,54 +165,79 @@ void MarlinHAL::idletask() MarlinHAL::watchdog_refresh(); // monitor SOC temperature - if(SOCTemp::criticalTemperatureReached()) + // #define HAL_ALWAYS_PRINT_SOC_TEMP + float temp; + if (ChipTemperature.read(temp)) { - printf("SoC reached critical temperature, rebooting\n"); - MarlinHAL::reboot(); +#ifdef HAL_ALWAYS_PRINT_SOC_TEMP + // print SoC temperature on every read + char tempStr[10]; + dtostrf(temp, 8, 1, tempStr); + printf("SoC temperature is %sC\n", tempStr); +#endif + + // warn after reaching 60C + if (temp > 60) + { +#ifndef HAL_ALWAYS_PRINT_SOC_TEMP + char tempStr[10]; + dtostrf(temp, 8, 1, tempStr); +#endif + printf("SoC temperature %s is above 60C\n", tempStr); + } + + // panic after reaching 80C + if (temp > 80) + { + printf("SoC overheat! temperature is > 80C\n"); + MarlinHAL::reboot(); + } } } uint8_t MarlinHAL::get_reset_source() { - // query reset cause + // query reset cause from RMU stc_rmu_rstcause_t rstCause; - MEM_ZERO_STRUCT(rstCause); RMU_GetResetCause(&rstCause); - // map reset causes to those expected by Marlin + // map reset cause code to those expected by Marlin + // - reset causes are flags, so multiple can be set + printf("-- Reset Cause -- \n"); uint8_t cause = 0; -#define MAP_CAUSE(from, to) \ - if (rstCause.from == Set) \ - { \ - printf("GetResetCause " STRINGIFY(from) " set\n"); \ - cause |= to; \ +#define MAP_CAUSE(from, to) \ + if (rstCause.from == Set) \ + { \ + printf(" - " STRINGIFY(from) "\n"); \ + cause |= to; \ } + // power on + MAP_CAUSE(enPowerOn, RST_POWER_ON) // power on reset + // external - MAP_CAUSE(enRstPin, RST_EXTERNAL) - MAP_CAUSE(enPvd1, RST_EXTERNAL) - MAP_CAUSE(enPvd2, RST_EXTERNAL) + MAP_CAUSE(enRstPin, RST_EXTERNAL) // reset pin + MAP_CAUSE(enPvd1, RST_EXTERNAL) // program voltage detection reset + MAP_CAUSE(enPvd2, RST_EXTERNAL) // " // brown out - MAP_CAUSE(enBrownOut, RST_BROWN_OUT) + MAP_CAUSE(enBrownOut, RST_BROWN_OUT) // brown out reset // wdt - MAP_CAUSE(enWdt, RST_WATCHDOG) - MAP_CAUSE(enSwdt, RST_WATCHDOG) + MAP_CAUSE(enWdt, RST_WATCHDOG) // Watchdog reset + MAP_CAUSE(enSwdt, RST_WATCHDOG) // Special WDT reset // software - MAP_CAUSE(enPowerDown, RST_SOFTWARE) - MAP_CAUSE(enSoftware, RST_SOFTWARE) + MAP_CAUSE(enPowerDown, RST_SOFTWARE) // MCU power down (?) + MAP_CAUSE(enSoftware, RST_SOFTWARE) // software reset (e.g. NVIC_SystemReset()) - // other - MAP_CAUSE(enMpuErr, RST_BACKUP) - MAP_CAUSE(enRamParityErr, RST_BACKUP) - MAP_CAUSE(enRamEcc, RST_BACKUP) - MAP_CAUSE(enClkFreqErr, RST_BACKUP) - MAP_CAUSE(enXtalErr, RST_BACKUP) + // misc. + MAP_CAUSE(enMpuErr, RST_BACKUP) // MPU error + MAP_CAUSE(enRamParityErr, RST_BACKUP) // RAM parity error + MAP_CAUSE(enRamEcc, RST_BACKUP) // RAM ecc error + MAP_CAUSE(enClkFreqErr, RST_BACKUP) // clock frequency failure + MAP_CAUSE(enXtalErr, RST_BACKUP) // XTAL failure - // power on - MAP_CAUSE(enPowerOn, RST_POWER_ON) return cause; } @@ -145,44 +256,47 @@ void MarlinHAL::adc_init() {} void MarlinHAL::adc_enable(const pin_t pin) { + // just set pin mode to analog pinMode(pin, INPUT_ANALOG); } void MarlinHAL::adc_start(const pin_t pin) { - TEMP_PINS pin_index; - switch (pin) - { - default: - case TEMP_0_PIN: - pin_index = TEMP_0; - break; - case TEMP_BED_PIN: - pin_index = TEMP_BED; - break; - } + CORE_ASSERT(IS_GPIO_PIN(pin), "adc_start: invalid pin") + MarlinHAL::last_adc_pin = pin; - MarlinHAL::adc_result = adc_read(ADC1, (uint8_t)pin_index); + analogReadAsync(pin); } bool MarlinHAL::adc_ready() { - return true; + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_ready: invalid pin") + + return getAnalogReadComplete(MarlinHAL::last_adc_pin); } uint16_t MarlinHAL::adc_value() { - return MarlinHAL::adc_result; + // read conversion result + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_value: invalid pin") + + return getAnalogReadValue(MarlinHAL::last_adc_pin); } -void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t a, const bool b) +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) { - // TODO stub + // invert value if requested + uint16_t val = invert ? scale - value : value; + + // analogWrite the value, core handles the rest + // pin mode should be set by Marlin by calling SET_PWM() before calling this function + analogWriteScaled(pin, val, scale); } void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { // TODO stub + printf("set_pwm_frequency is not implemented yet\n"); } void flashFirmware(const int16_t) { MarlinHAL::reboot(); } diff --git a/Marlin/src/HAL/HC32F46x/MarlinHAL.h b/Marlin/src/HAL/HC32F46x/MarlinHAL.h index 05317a0138fc..cb480c655643 100644 --- a/Marlin/src/HAL/HC32F46x/MarlinHAL.h +++ b/Marlin/src/HAL/HC32F46x/MarlinHAL.h @@ -1,8 +1,8 @@ #pragma once - #include +#include -typedef int8_t pin_t; +typedef gpio_pin_t pin_t; class MarlinHAL { @@ -39,8 +39,6 @@ class MarlinHAL // ADC Methods // - static uint16_t adc_result; - // Called by Temperature::init once at startup static void adc_init(); @@ -62,13 +60,19 @@ class MarlinHAL * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. */ - static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t = 255, const bool = false); + static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255, const bool invert = false); /** * Set the frequency of the timer for the given pin. * All Timer PWM pins run at the same frequency. */ static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + +private: + /** + * pin number of the last pin that was used with adc_start() + */ + static pin_t last_adc_pin; }; // M997: trigger firmware update from sd card (after upload) diff --git a/Marlin/src/HAL/HC32F46x/MarlinSerial.cpp b/Marlin/src/HAL/HC32F46x/MarlinSerial.cpp index eb3d553a12c8..d471568dac04 100644 --- a/Marlin/src/HAL/HC32F46x/MarlinSerial.cpp +++ b/Marlin/src/HAL/HC32F46x/MarlinSerial.cpp @@ -49,9 +49,7 @@ constexpr bool serial_handles_emergency(int port) // #define DEFINE_HWSERIAL_MARLIN(name, n) \ MSerialT name(serial_handles_emergency(n), \ - USART##n, \ - BOARD_USART##n##_TX_PIN, \ - BOARD_USART##n##_RX_PIN); + &USART##n##_config, BOARD_USART##n##_TX_PIN, BOARD_USART##n##_RX_PIN); DEFINE_HWSERIAL_MARLIN(MSerial1, 1); DEFINE_HWSERIAL_MARLIN(MSerial2, 2); @@ -66,6 +64,7 @@ DEFINE_HWSERIAL_MARLIN(MSerial2, 2); template constexpr bool IsSerialClassAllowed(const T &) { return true; } constexpr bool IsSerialClassAllowed(const HardwareSerial &) { return false; } +constexpr bool IsSerialClassAllowed(const Usart &) { return false; } // If you encounter this error, replace SerialX with MSerialX, for example MSerial3. #define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly"); diff --git a/Marlin/src/HAL/HC32F46x/MarlinSerial.h b/Marlin/src/HAL/HC32F46x/MarlinSerial.h index 998152f90a16..ac7c65e036be 100644 --- a/Marlin/src/HAL/HC32F46x/MarlinSerial.h +++ b/Marlin/src/HAL/HC32F46x/MarlinSerial.h @@ -20,32 +20,34 @@ * */ #pragma once -#include "HardwareSerial.h" +#include #include "../../core/serial_hook.h" // optionally set uart IRQ priority to reduce overflow errors -// #define UART_IRQ_PRIO 1 +//#define UART_IRQ_PRIO 1 -struct MarlinSerial : public HardwareSerial +struct MarlinSerial : public Usart { - MarlinSerial(struct usart_dev *usart_device, uint8 tx_pin, uint8 rx_pin) : HardwareSerial(usart_device, tx_pin, rx_pin) {} + MarlinSerial(struct usart_config_t *usart_device, gpio_pin_t tx_pin, gpio_pin_t rx_pin) : Usart(usart_device, tx_pin, rx_pin) {} #ifdef UART_IRQ_PRIO void setPriority() { - NVIC_SetPriority(c_dev()->RX_IRQ, UART_IRQ_PRIO); - NVIC_SetPriority(c_dev()->TX_IRQ, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.rx_data_available.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.rx_error.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.tx_buffer_empty.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.tx_complete.interrupt_number, UART_IRQ_PRIO); } - void begin(uint32 baud) + void begin(uint32_t baud) { - HardwareSerial::begin(baud); + Usart::begin(baud); setPriority(); } - void begin(uint32 baud, uint8_t config) + void begin(uint32_t baud, uint8_t config) { - HardwareSerial::begin(baud, config); + Usart::begin(baud, config); setPriority(); } #endif diff --git a/Marlin/src/HAL/HC32F46x/SPI.cpp b/Marlin/src/HAL/HC32F46x/SPI.cpp deleted file mode 100644 index 32a95b4aaf9f..000000000000 --- a/Marlin/src/HAL/HC32F46x/SPI.cpp +++ /dev/null @@ -1,835 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ - -/** - * @author Marti Bolivar - * @brief Wirish SPI implementation. - */ - -#ifdef TARGET_HC32F46x - -#ifdef USE_SPI -#warning "'SPI' has not been tested to work as expected. Proceed at your own risk" - -#include "SPI.h" - -#include "../core/boards.h" -#include "../cores/wirish.h" - -/** Time in ms for DMA receive timeout */ -#define DMA_TIMEOUT 100 - -#if CYCLES_PER_MICROSECOND != 72 -#warning "Unexpected clock speed; SPI frequency calculation will be incorrect" -#endif - -struct spi_pins -{ - uint8_t nss, sck, miso, mosi; -}; - -static const spi_pins *dev_to_spi_pins(spi_dev *dev); -static void configure_gpios(spi_dev *dev, bool as_master); -static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq); - -#if BOARD_NR_SPI >= 3 && !defined(STM32_HIGH_DENSITY) -#error "The SPI library is misconfigured: 3 SPI ports only available on high density STM32 devices" -#endif - -static const spi_pins board_spi_pins[] __FLASH__ = { -#if BOARD_NR_SPI >= 1 - {BOARD_SPI1_NSS_PIN, - BOARD_SPI1_SCK_PIN, - BOARD_SPI1_MISO_PIN, - BOARD_SPI1_MOSI_PIN}, -#endif -#if BOARD_NR_SPI >= 2 - {BOARD_SPI2_NSS_PIN, - BOARD_SPI2_SCK_PIN, - BOARD_SPI2_MISO_PIN, - BOARD_SPI2_MOSI_PIN}, -#endif -#if BOARD_NR_SPI >= 3 - {BOARD_SPI3_NSS_PIN, - BOARD_SPI3_SCK_PIN, - BOARD_SPI3_MISO_PIN, - BOARD_SPI3_MOSI_PIN}, -#endif -}; - -#if BOARD_NR_SPI >= 1 -static void *_spi1_this; -#endif -#if BOARD_NR_SPI >= 2 -static void *_spi2_this; -#endif -#if BOARD_NR_SPI >= 3 -static void *_spi3_this; -#endif - -/** - * Constructor - */ -SPIClass::SPIClass(uint32_t spi_num) -{ - _currentSetting = &_settings[spi_num - 1]; // SPI channels are called 1 2 and 3 but the array is zero indexed - - switch (spi_num) - { -#if BOARD_NR_SPI >= 1 - case 1: - _currentSetting->spi_d = SPI1; - _spi1_this = (void *)this; - break; -#endif -#if BOARD_NR_SPI >= 2 - case 2: - _currentSetting->spi_d = SPI2; - _spi2_this = (void *)this; - break; -#endif -#if BOARD_NR_SPI >= 3 - case 3: - _currentSetting->spi_d = SPI3; - _spi3_this = (void *)this; - break; -#endif - default: - DDL_ASSERT(0); - } - -// 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 = SPI1; - _settings[0].clockDivider = determine_baud_rate(_settings[0].spi_d, _settings[0].clock); - _settings[0].spiDmaDev = DMA1; - _settings[0].spiTxDmaChannel = DMA_CH3; - _settings[0].spiRxDmaChannel = DMA_CH2; -#endif -#if BOARD_NR_SPI >= 2 - _settings[1].spi_d = SPI2; - _settings[1].clockDivider = determine_baud_rate(_settings[1].spi_d, _settings[1].clock); - _settings[1].spiDmaDev = DMA1; - _settings[1].spiTxDmaChannel = DMA_CH5; - _settings[1].spiRxDmaChannel = DMA_CH4; -#endif -#if BOARD_NR_SPI >= 3 - _settings[2].spi_d = SPI3; - _settings[2].clockDivider = determine_baud_rate(_settings[2].spi_d, _settings[2].clock); - _settings[2].spiDmaDev = DMA2; - _settings[2].spiTxDmaChannel = DMA_CH2; - _settings[2].spiRxDmaChannel = DMA_CH1; -#endif - - // added for DMA callbacks. - _currentSetting->state = SPI_STATE_IDLE; -} - -/** - * Set up/tear down - */ -void SPIClass::updateSettings() -{ - uint32_t flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize | SPI_SW_SLAVE | SPI_SOFT_SS); - spi_master_enable(_currentSetting->spi_d, (spi_baud_rate)_currentSetting->clockDivider, (spi_mode)_currentSetting->dataMode, flags); -} - -void SPIClass::begin() -{ - spi_init(_currentSetting->spi_d); - configure_gpios(_currentSetting->spi_d, 1); - updateSettings(); - // added for DMA callbacks. - _currentSetting->state = SPI_STATE_READY; -} - -void SPIClass::beginSlave() -{ - spi_init(_currentSetting->spi_d); - configure_gpios(_currentSetting->spi_d, 0); - uint32_t flags = ((_currentSetting->bitOrder == MSBFIRST ? SPI_FRAME_MSB : SPI_FRAME_LSB) | _currentSetting->dataSize); - spi_slave_enable(_currentSetting->spi_d, (spi_mode)_currentSetting->dataMode, flags); - // added for DMA callbacks. - _currentSetting->state = SPI_STATE_READY; -} - -void SPIClass::end() -{ - if (!spi_is_enabled(_currentSetting->spi_d)) - return; - - // Follows RM0008's sequence for disabling a SPI in master/slave - // full duplex mode. - while (spi_is_rx_nonempty(_currentSetting->spi_d)) - { - // FIXME [0.1.0] remove this once you have an interrupt based driver - volatile uint16_t rx __attribute__((unused)) = spi_rx_reg(_currentSetting->spi_d); - } - waitSpiTxEnd(_currentSetting->spi_d); - - spi_peripheral_disable(_currentSetting->spi_d); - // added for DMA callbacks. - // Need to add unsetting the callbacks for the DMA channels. - _currentSetting->state = SPI_STATE_IDLE; -} - -/* Roger Clark added 3 functions */ -void SPIClass::setClockDivider(uint32_t clockDivider) -{ - _currentSetting->clockDivider = clockDivider; - uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_BR); - _currentSetting->spi_d->regs->CR1 = cr1 | (clockDivider & SPI_CR1_BR); -} - -void SPIClass::setBitOrder(BitOrder bitOrder) -{ - _currentSetting->bitOrder = bitOrder; - uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_LSBFIRST); - if (bitOrder == LSBFIRST) - cr1 |= SPI_CR1_LSBFIRST; - _currentSetting->spi_d->regs->CR1 = cr1; -} - -/** - * Victor Perez. Added to test changing datasize from 8 to 16 bit modes on the fly. - * Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word. - */ -void SPIClass::setDataSize(uint32_t datasize) -{ - _currentSetting->dataSize = datasize; - uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_DFF); - uint8_t en = spi_is_enabled(_currentSetting->spi_d); - spi_peripheral_disable(_currentSetting->spi_d); - _currentSetting->spi_d->regs->CR1 = cr1 | (datasize & SPI_CR1_DFF) | en; -} - -void SPIClass::setDataMode(uint8_t dataMode) -{ - /** - * Notes: - * As far as we know the AVR numbers for dataMode match the numbers required by the STM32. - * From the AVR doc https://www.atmel.com/images/doc2585.pdf section 2.4 - * - * 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 - * - * On the STM32 it appears to be - * - * bit 1 - CPOL : Clock polarity - * (This bit should not be changed when communication is ongoing) - * 0 : CLK to 0 when idle - * 1 : CLK to 1 when idle - * - * bit 0 - CPHA : Clock phase - * (This bit should not be changed when communication is ongoing) - * 0 : The first clock transition is the first data capture edge - * 1 : The second clock transition is the first data capture edge - * - * If someone finds this is not the case or sees a logic error with this let me know ;-) - */ - _currentSetting->dataMode = dataMode; - uint32_t cr1 = _currentSetting->spi_d->regs->CR1 & ~(SPI_CR1_CPOL | SPI_CR1_CPHA); - _currentSetting->spi_d->regs->CR1 = cr1 | (dataMode & (SPI_CR1_CPOL | SPI_CR1_CPHA)); -} - -void SPIClass::beginTransaction(uint8_t pin, const SPISettings &settings) -{ - setBitOrder(settings.bitOrder); - setDataMode(settings.dataMode); - setDataSize(settings.dataSize); - setClockDivider(determine_baud_rate(_currentSetting->spi_d, settings.clock)); - begin(); -} - -void SPIClass::beginTransactionSlave(const SPISettings &settings) -{ - setBitOrder(settings.bitOrder); - setDataMode(settings.dataMode); - setDataSize(settings.dataSize); - beginSlave(); -} - -void SPIClass::endTransaction() {} - -/** - * I/O - */ - -uint16_t SPIClass::read() -{ - while (!spi_is_rx_nonempty(_currentSetting->spi_d)) - { /* nada */ - } - return (uint16_t)spi_rx_reg(_currentSetting->spi_d); -} - -void SPIClass::read(uint8_t *buf, uint32_t len) -{ - if (len == 0) - return; - spi_rx_reg(_currentSetting->spi_d); // clear the RX buffer in case a byte is waiting on it. - spi_reg_map *regs = _currentSetting->spi_d->regs; - // start sequence: write byte 0 - regs->DR = 0x00FF; // write the first byte - // main loop - while (--len) - { - while (!(regs->SR & SPI_SR_TXE)) - { /* nada */ - } // wait for TXE flag - noInterrupts(); // go atomic level - avoid interrupts to surely get the previously received data - regs->DR = 0x00FF; // write the next data item to be transmitted into the SPI_DR register. This clears the TXE flag. - while (!(regs->SR & SPI_SR_RXNE)) - { /* nada */ - } // wait till data is available in the DR register - *buf++ = (uint8)(regs->DR); // read and store the received byte. This clears the RXNE flag. - interrupts(); // let systick do its job - } - // read remaining last byte - while (!(regs->SR & SPI_SR_RXNE)) - { /* nada */ - } // wait till data is available in the Rx register - *buf++ = (uint8)(regs->DR); // read and store the received byte -} - -void SPIClass::write(uint16_t data) -{ - /* Added for 16bit data Victor Perez. Roger Clark - * Improved speed by just directly writing the single byte to the SPI data reg and wait for completion, - * by taking the Tx code from transfer(byte) - * This almost doubles the speed of this function. - */ - spi_tx_reg(_currentSetting->spi_d, data); // write the data to be transmitted into the SPI_DR register (this clears the TXE flag) - waitSpiTxEnd(_currentSetting->spi_d); -} - -void SPIClass::write16(uint16_t data) -{ - // Added by stevestrong: write two consecutive bytes in 8 bit mode (DFF=0) - spi_tx_reg(_currentSetting->spi_d, data >> 8); // write high byte - while (!spi_is_tx_empty(_currentSetting->spi_d)) - { /* nada */ - } // Wait until TXE=1 - spi_tx_reg(_currentSetting->spi_d, data); // write low byte - waitSpiTxEnd(_currentSetting->spi_d); -} - -void SPIClass::write(uint16_t data, uint32_t n) -{ - // Added by stevstrong: Repeatedly send same data by the specified number of times - spi_reg_map *regs = _currentSetting->spi_d->regs; - while (n--) - { - regs->DR = data; // write the data to be transmitted into the SPI_DR register (this clears the TXE flag) - while (!(regs->SR & SPI_SR_TXE)) - { /* nada */ - } // wait till Tx empty - } - while (regs->SR & SPI_SR_BSY) - { /* nada */ - } // wait until BSY=0 before returning -} - -void SPIClass::write(const void *data, uint32_t length) -{ - spi_dev *spi_d = _currentSetting->spi_d; - spi_tx(spi_d, data, length); // data can be array of bytes or words - waitSpiTxEnd(spi_d); -} - -uint8_t SPIClass::transfer(uint8_t byte) const -{ - spi_dev *spi_d = _currentSetting->spi_d; - spi_rx_reg(spi_d); // read any previous data - spi_tx_reg(spi_d, byte); // Write the data item to be transmitted into the SPI_DR register - waitSpiTxEnd(spi_d); - return (uint8)spi_rx_reg(spi_d); // "... and read the last received data." -} - -uint16_t SPIClass::transfer16(uint16_t data) const -{ - // Modified by stevestrong: write & read two consecutive bytes in 8 bit mode (DFF=0) - // This is more effective than two distinct byte transfers - spi_dev *spi_d = _currentSetting->spi_d; - spi_rx_reg(spi_d); // read any previous data - spi_tx_reg(spi_d, data >> 8); // write high byte - waitSpiTxEnd(spi_d); // wait until TXE=1 and then wait until BSY=0 - uint16_t ret = spi_rx_reg(spi_d) << 8; // read and shift high byte - spi_tx_reg(spi_d, data); // write low byte - waitSpiTxEnd(spi_d); // wait until TXE=1 and then wait until BSY=0 - ret += spi_rx_reg(spi_d); // read low byte - return ret; -} - -/** - * Roger Clark and Victor Perez, 2015 - * Performs a DMA SPI transfer with at least a receive buffer. - * If a TX buffer is not provided, FF is sent over and over for the lenght of the transfer. - * On exit TX buffer is not modified, and RX buffer cotains the received data. - * Still in progress. - */ -void SPIClass::dmaTransferSet(const void *transmitBuf, void *receiveBuf) -{ - dma_init(_currentSetting->spiDmaDev); - // spi_rx_dma_enable(_currentSetting->spi_d); - // spi_tx_dma_enable(_currentSetting->spi_d); - dma_xfer_size dma_bit_size = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS; - dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &_currentSetting->spi_d->regs->DR, - dma_bit_size, receiveBuf, dma_bit_size, (DMA_MINC_MODE | DMA_TRNS_CMPLT)); // receive buffer DMA - if (!transmitBuf) - { - transmitBuf = &ff; - dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, - dma_bit_size, (volatile void *)transmitBuf, dma_bit_size, (DMA_FROM_MEM)); // Transmit FF repeatedly - } - else - { - dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, - dma_bit_size, (volatile void *)transmitBuf, dma_bit_size, (DMA_MINC_MODE | DMA_FROM_MEM)); // Transmit buffer DMA - } - dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW); - dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, DMA_PRIORITY_VERY_HIGH); -} - -uint8_t SPIClass::dmaTransferRepeat(uint16_t length) -{ - if (length == 0) - return 0; - if (spi_is_rx_nonempty(_currentSetting->spi_d) == 1) - spi_rx_reg(_currentSetting->spi_d); - _currentSetting->state = SPI_STATE_TRANSFER; - dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, length); - dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length); - dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel); // enable receive - dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit - spi_rx_dma_enable(_currentSetting->spi_d); - spi_tx_dma_enable(_currentSetting->spi_d); - if (_currentSetting->receiveCallback) - return 0; - - // uint32_t m = millis(); - uint8_t b = 0; - uint32_t m = millis(); - while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) - { - // Avoid interrupts and just loop waiting for the flag to be set. - if ((millis() - m) > DMA_TIMEOUT) - { - b = 2; - break; - } - } - - waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0 - spi_tx_dma_disable(_currentSetting->spi_d); - spi_rx_dma_disable(_currentSetting->spi_d); - dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel); - dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel); - dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - _currentSetting->state = SPI_STATE_READY; - return b; -} - -/** - * Roger Clark and Victor Perez, 2015 - * Performs a DMA SPI transfer with at least a receive buffer. - * If a TX buffer is not provided, FF is sent over and over for the length of the transfer. - * On exit TX buffer is not modified, and RX buffer contains the received data. - * Still in progress. - */ -uint8_t SPIClass::dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length) -{ - dmaTransferSet(transmitBuf, receiveBuf); - return dmaTransferRepeat(length); -} - -/** - * Roger Clark and Victor Perez, 2015 - * Performs a DMA SPI send using a TX buffer. - * On exit TX buffer is not modified. - * Still in progress. - * 2016 - stevstrong - reworked to automatically detect bit size from SPI setting - */ -void SPIClass::dmaSendSet(const void *transmitBuf, bool minc) -{ - uint32_t flags = ((DMA_MINC_MODE * minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT); - dma_init(_currentSetting->spiDmaDev); - dma_xfer_size dma_bit_size = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS; - dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, dma_bit_size, - (volatile void *)transmitBuf, dma_bit_size, flags); // Transmit buffer DMA - dma_set_priority(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, DMA_PRIORITY_LOW); -} - -uint8_t SPIClass::dmaSendRepeat(uint16_t length) -{ - if (length == 0) - return 0; - - dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length); - _currentSetting->state = SPI_STATE_TRANSMIT; - dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit - spi_tx_dma_enable(_currentSetting->spi_d); - if (_currentSetting->transmitCallback) - return 0; - - uint32_t m = millis(); - uint8_t b = 0; - while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) - { - // Avoid interrupts and just loop waiting for the flag to be set. - if ((millis() - m) > DMA_TIMEOUT) - { - b = 2; - break; - } - } - waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0 - spi_tx_dma_disable(_currentSetting->spi_d); - dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - _currentSetting->state = SPI_STATE_READY; - return b; -} - -uint8_t SPIClass::dmaSend(const void *transmitBuf, uint16_t length, bool minc) -{ - dmaSendSet(transmitBuf, minc); - return dmaSendRepeat(length); -} - -uint8_t SPIClass::dmaSendAsync(const void *transmitBuf, uint16_t length, bool minc) -{ - uint8_t b = 0; - - if (_currentSetting->state != SPI_STATE_READY) - { - uint32_t m = millis(); - while (!(dma_get_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel) & DMA_ISR_TCIF1)) - { - // Avoid interrupts and just loop waiting for the flag to be set. - // delayMicroseconds(10); - if ((millis() - m) > DMA_TIMEOUT) - { - b = 2; - break; - } - } - waitSpiTxEnd(_currentSetting->spi_d); // until TXE=1 and BSY=0 - spi_tx_dma_disable(_currentSetting->spi_d); - dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - _currentSetting->state = SPI_STATE_READY; - } - - if (length == 0) - return 0; - uint32_t flags = ((DMA_MINC_MODE * minc) | DMA_FROM_MEM | DMA_TRNS_CMPLT); - - dma_init(_currentSetting->spiDmaDev); - // TX - dma_xfer_size dma_bit_size = (_currentSetting->dataSize == DATA_SIZE_16BIT) ? DMA_SIZE_16BITS : DMA_SIZE_8BITS; - dma_setup_transfer(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &_currentSetting->spi_d->regs->DR, - dma_bit_size, (volatile void *)transmitBuf, dma_bit_size, flags); // Transmit buffer DMA - dma_set_num_transfers(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, length); - dma_clear_isr_bits(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - dma_enable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); // enable transmit - spi_tx_dma_enable(_currentSetting->spi_d); - - _currentSetting->state = SPI_STATE_TRANSMIT; - return b; -} - -/** - * New functions added to manage callbacks. - * Victor Perez 2017 - */ -void SPIClass::onReceive(void (*callback)()) -{ - _currentSetting->receiveCallback = callback; - if (callback) - { - switch (_currentSetting->spi_d->clk_id) - { -#if BOARD_NR_SPI >= 1 - case RCC_SPI1: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi1EventCallback); - break; -#endif -#if BOARD_NR_SPI >= 2 - case RCC_SPI2: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi2EventCallback); - break; -#endif -#if BOARD_NR_SPI >= 3 - case RCC_SPI3: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel, &SPIClass::_spi3EventCallback); - break; -#endif - default: - DDL_ASSERT(0); - } - } - else - { - dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel); - } -} - -void SPIClass::onTransmit(void (*callback)()) -{ - _currentSetting->transmitCallback = callback; - if (callback) - { - switch (_currentSetting->spi_d->clk_id) - { -#if BOARD_NR_SPI >= 1 - case RCC_SPI1: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi1EventCallback); - break; -#endif -#if BOARD_NR_SPI >= 2 - case RCC_SPI2: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi2EventCallback); - break; -#endif -#if BOARD_NR_SPI >= 3 - case RCC_SPI3: - dma_attach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel, &SPIClass::_spi3EventCallback); - break; -#endif - default: - DDL_ASSERT(0); - } - } - else - { - dma_detach_interrupt(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - } -} - -/** - * TODO: check if better to first call the customer code, next disable the DMA requests. - * Also see if we need to check whether callbacks are set or not, may be better to be checked - * during the initial setup and only set the callback to EventCallback if they are set. - */ -void SPIClass::EventCallback() -{ - waitSpiTxEnd(_currentSetting->spi_d); - switch (_currentSetting->state) - { - case SPI_STATE_TRANSFER: - while (spi_is_rx_nonempty(_currentSetting->spi_d)) - { /* nada */ - } - _currentSetting->state = SPI_STATE_READY; - spi_tx_dma_disable(_currentSetting->spi_d); - spi_rx_dma_disable(_currentSetting->spi_d); - // dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - // dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiRxDmaChannel); - if (_currentSetting->receiveCallback) - _currentSetting->receiveCallback(); - break; - case SPI_STATE_TRANSMIT: - _currentSetting->state = SPI_STATE_READY; - spi_tx_dma_disable(_currentSetting->spi_d); - // dma_disable(_currentSetting->spiDmaDev, _currentSetting->spiTxDmaChannel); - if (_currentSetting->transmitCallback) - _currentSetting->transmitCallback(); - break; - default: - break; - } -} - -void SPIClass::attachInterrupt() -{ - // Should be enableInterrupt() -} - -void SPIClass::detachInterrupt() -{ - // Should be disableInterrupt() -} - -/** - * Pin accessors - */ - -uint8_t SPIClass::misoPin() -{ - return dev_to_spi_pins(_currentSetting->spi_d)->miso; -} - -uint8_t SPIClass::mosiPin() -{ - return dev_to_spi_pins(_currentSetting->spi_d)->mosi; -} - -uint8_t SPIClass::sckPin() -{ - return dev_to_spi_pins(_currentSetting->spi_d)->sck; -} - -uint8_t SPIClass::nssPin() -{ - return dev_to_spi_pins(_currentSetting->spi_d)->nss; -} - -/** - * Deprecated functions - */ -uint8_t SPIClass::send(uint8_t data) -{ - write(data); - return 1; -} -uint8_t SPIClass::send(uint8_t *buf, uint32_t len) -{ - write(buf, len); - return len; -} -uint8_t SPIClass::recv() { return read(); } - -/** - * DMA call back functions, one per port. - */ -#if BOARD_NR_SPI >= 1 -void SPIClass::_spi1EventCallback() -{ - reinterpret_cast(_spi1_this)->EventCallback(); -} -#endif -#if BOARD_NR_SPI >= 2 -void SPIClass::_spi2EventCallback() -{ - reinterpret_cast(_spi2_this)->EventCallback(); -} -#endif -#if BOARD_NR_SPI >= 3 -void SPIClass::_spi3EventCallback() -{ - reinterpret_cast(_spi3_this)->EventCallback(); -} -#endif - -/** - * Auxiliary functions - */ -static const spi_pins *dev_to_spi_pins(spi_dev *dev) -{ - switch (dev->clk_id) - { -#if BOARD_NR_SPI >= 1 - case RCC_SPI1: - return board_spi_pins; -#endif -#if BOARD_NR_SPI >= 2 - case RCC_SPI2: - return board_spi_pins + 1; -#endif -#if BOARD_NR_SPI >= 3 - case RCC_SPI3: - return board_spi_pins + 2; -#endif - default: - return NULL; - } -} - -static void disable_pwm(const stm32_pin_info *i) -{ - if (i->timer_device) - timer_set_mode(i->timer_device, i->timer_channel, TIMER_DISABLED); -} - -static void configure_gpios(spi_dev *dev, bool as_master) -{ - const spi_pins *pins = dev_to_spi_pins(dev); - if (!pins) - return; - - const stm32_pin_info *nssi = &PIN_MAP[pins->nss], - *scki = &PIN_MAP[pins->sck], - *misoi = &PIN_MAP[pins->miso], - *mosii = &PIN_MAP[pins->mosi]; - - disable_pwm(nssi); - disable_pwm(scki); - disable_pwm(misoi); - disable_pwm(mosii); - - spi_config_gpios(dev, as_master, nssi->gpio_device, nssi->gpio_bit, - scki->gpio_device, scki->gpio_bit, misoi->gpio_bit, - mosii->gpio_bit); -} - -static const spi_baud_rate baud_rates[8] __FLASH__ = { - SPI_BAUD_PCLK_DIV_2, - SPI_BAUD_PCLK_DIV_4, - SPI_BAUD_PCLK_DIV_8, - SPI_BAUD_PCLK_DIV_16, - SPI_BAUD_PCLK_DIV_32, - SPI_BAUD_PCLK_DIV_64, - SPI_BAUD_PCLK_DIV_128, - SPI_BAUD_PCLK_DIV_256, -}; - -/** - * Note: This assumes you're on a LeafLabs-style board - * (CYCLES_PER_MICROSECOND == 72, APB2 at 72MHz, APB1 at 36MHz). - */ -static spi_baud_rate determine_baud_rate(spi_dev *dev, uint32_t freq) -{ - uint32_t clock = 0; - switch (rcc_dev_clk(dev->clk_id)) - { - case RCC_AHB: - case RCC_APB2: - clock = STM32_PCLK2; - break; // 72 Mhz - case RCC_APB1: - clock = STM32_PCLK1; - break; // 36 Mhz - } - clock >>= 1; - - uint8_t i = 0; - while (i < 7 && freq < clock) - { - clock >>= 1; - i++; - } - return baud_rates[i]; -} - -SPIClass SPI(1); -#endif -#endif // TARGET_HC32F46x diff --git a/Marlin/src/HAL/HC32F46x/SPI.h b/Marlin/src/HAL/HC32F46x/SPI.h deleted file mode 100644 index a100caf05463..000000000000 --- a/Marlin/src/HAL/HC32F46x/SPI.h +++ /dev/null @@ -1,435 +0,0 @@ -/****************************************************************************** - * The MIT License - * - * Copyright (c) 2010 Perry Hung. - * - * Permission is hereby granted, free of charge, to any person - * obtaining a copy of this software and associated documentation - * files (the "Software"), to deal in the Software without - * restriction, including without limitation the rights to use, copy, - * modify, merge, publish, distribute, sublicense, and/or sell copies - * of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be - * included in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS - * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN - * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN - * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE - * SOFTWARE. - *****************************************************************************/ -#pragma once -#ifdef USE_SPI -#warning "'SPI' has not been tested to work as expected. Proceed at your own risk" - -#include "../cores/libmaple_types.h" -#include "../cores/spi.h" - -#include "../cores/boards.h" -#include -#include - -// SPI_HAS_TRANSACTION means SPI has -// - beginTransaction() -// - endTransaction() -// - usingInterrupt() -// - SPISetting(clock, bitOrder, dataMode) -// #define SPI_HAS_TRANSACTION - -#define SPI_CLOCK_DIV2 SPI_BAUD_PCLK_DIV_2 -#define SPI_CLOCK_DIV4 SPI_BAUD_PCLK_DIV_4 -#define SPI_CLOCK_DIV8 SPI_BAUD_PCLK_DIV_8 -#define SPI_CLOCK_DIV16 SPI_BAUD_PCLK_DIV_16 -#define SPI_CLOCK_DIV32 SPI_BAUD_PCLK_DIV_32 -#define SPI_CLOCK_DIV64 SPI_BAUD_PCLK_DIV_64 -#define SPI_CLOCK_DIV128 SPI_BAUD_PCLK_DIV_128 -#define SPI_CLOCK_DIV256 SPI_BAUD_PCLK_DIV_256 - -/* - * Roger Clark. 20150106 - * Commented out redundant AVR defined - * -#define SPI_MODE_MASK 0x0C // CPOL = bit 3, CPHA = bit 2 on SPCR -#define SPI_CLOCK_MASK 0x03 // SPR1 = bit 1, SPR0 = bit 0 on SPCR -#define SPI_2XCLOCK_MASK 0x01 // SPI2X = bit 0 on SPSR - -// define SPI_AVR_EIMSK for AVR boards with external interrupt pins -#ifdef EIMSK - #define SPI_AVR_EIMSK EIMSK -#elif defined(GICR) - #define SPI_AVR_EIMSK GICR -#elif defined(GIMSK) - #define SPI_AVR_EIMSK GIMSK -#endif -*/ - -#ifndef STM32_LSBFIRST -#define STM32_LSBFIRST 0 -#endif -#ifndef STM32_MSBFIRST -#define STM32_MSBFIRST 1 -#endif - -// PC13 or PA4 -#define BOARD_SPI_DEFAULT_SS PA4 -// #define BOARD_SPI_DEFAULT_SS PC13 - -#define SPI_MODE0 SPI_MODE_0 -#define SPI_MODE1 SPI_MODE_1 -#define SPI_MODE2 SPI_MODE_2 -#define SPI_MODE3 SPI_MODE_3 - -#define DATA_SIZE_8BIT SPI_CR1_DFF_8_BIT -#define DATA_SIZE_16BIT SPI_CR1_DFF_16_BIT - -typedef enum -{ - SPI_STATE_IDLE, - SPI_STATE_READY, - SPI_STATE_RECEIVE, - SPI_STATE_TRANSMIT, - SPI_STATE_TRANSFER -} spi_mode_t; - -class SPISettings -{ -public: - SPISettings(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode) - { - if (__builtin_constant_p(inClock)) - init_AlwaysInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT); - else - init_MightInline(inClock, inBitOrder, inDataMode, DATA_SIZE_8BIT); - } - SPISettings(uint32_t inClock, BitOrder 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(uint32_t inClock) - { - if (__builtin_constant_p(inClock)) - init_AlwaysInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); - else - init_MightInline(inClock, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); - } - SPISettings() - { - init_AlwaysInline(4000000, MSBFIRST, SPI_MODE0, DATA_SIZE_8BIT); - } - -private: - void init_MightInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) - { - init_AlwaysInline(inClock, inBitOrder, inDataMode, inDataSize); - } - void init_AlwaysInline(uint32_t inClock, BitOrder inBitOrder, uint8_t inDataMode, uint32_t inDataSize) __attribute__((__always_inline__)) - { - clock = inClock; - bitOrder = inBitOrder; - dataMode = inDataMode; - dataSize = inDataSize; - // state = SPI_STATE_IDLE; - } - uint32_t clock; - uint32_t dataSize; - uint32_t clockDivider; - BitOrder bitOrder; - uint8_t dataMode; - uint8_t _SSPin; - volatile spi_mode_t state; - spi_dev *spi_d; - dma_channel spiRxDmaChannel, spiTxDmaChannel; - dma_dev *spiDmaDev; - void (*receiveCallback)() = NULL; - void (*transmitCallback)() = NULL; - - friend class SPIClass; -}; - -/* - * Kept for compat. - */ -static const uint8_t ff = 0xFF; - -/** - * @brief Wirish SPI interface. - * - * 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(uint32_t spiPortNumber); - - /** - * @brief Equivalent to begin(SPI_1_125MHZ, MSBFIRST, 0). - */ - void begin(); - - /** - * @brief Turn on a SPI port and set its GPIO pin modes for use as a slave. - * - * SPI port is enabled in full duplex mode, with software slave management. - * - * @param bitOrder Either LSBFIRST (little-endian) or MSBFIRST(big-endian) - * @param mode SPI mode to use - */ - void beginSlave(uint32_t bitOrder, uint32_t mode); - - /** - * @brief Equivalent to beginSlave(MSBFIRST, 0). - */ - void beginSlave(); - - /** - * @brief Disables the SPI port, but leaves its GPIO pin modes unchanged. - */ - void end(); - - void beginTransaction(const SPISettings &settings) { beginTransaction(BOARD_SPI_DEFAULT_SS, settings); } - void beginTransaction(uint8_t pin, const SPISettings &settings); - void endTransaction(); - - void beginTransactionSlave(const SPISettings &settings); - - void setClockDivider(uint32_t clockDivider); - void setBitOrder(BitOrder bitOrder); - void setDataMode(uint8_t dataMode); - - // SPI Configuration methods - void attachInterrupt(); - void detachInterrupt(); - - /* Victor Perez. Added to change datasize from 8 to 16 bit modes on the fly. - * Input parameter should be SPI_CR1_DFF set to 0 or 1 on a 32bit word. - * Requires an added function spi_data_size on STM32F1 / cores / maple / libmaple / spi.c - */ - void setDataSize(uint32_t ds); - - /* Victor Perez 2017. Added to set and clear callback functions for callback - * on DMA transfer completion. - * onReceive used to set the callback in case of dmaTransfer (tx/rx), once rx is completed - * onTransmit used to set the callback in case of dmaSend (tx only). That function - * will NOT be called in case of TX/RX - */ - void onReceive(void (*)()); - void onTransmit(void (*)()); - - /* - * I/O - */ - - /** - * @brief Return the next unread byte/word. - * - * If there is no unread byte/word waiting, this function will block - * until one is received. - */ - uint16_t read(); - - /** - * @brief Read length bytes, storing them into buffer. - * @param buffer Buffer to store received bytes into. - * @param length Number of bytes to store in buffer. This - * function will block until the desired number of - * bytes have been read. - */ - void read(uint8_t *buffer, uint32_t length); - - /** - * @brief Transmit one byte/word. - * @param data to transmit. - */ - void write(uint16_t data); - void write16(uint16_t data); // write 2 bytes in 8 bit mode (DFF=0) - - /** - * @brief Transmit one byte/word a specified number of times. - * @param data to transmit. - */ - void write(uint16_t data, uint32_t n); - - /** - * @brief Transmit multiple bytes/words. - * @param buffer Bytes/words to transmit. - * @param length Number of bytes/words in buffer to transmit. - */ - void write(const void *buffer, uint32_t length); - - /** - * @brief Transmit a byte, then return the next unread byte. - * - * This function transmits before receiving. - * - * @param data Byte to transmit. - * @return Next unread byte. - */ - uint8_t transfer(uint8_t data) const; - uint16_t transfer16(uint16_t data) const; - - /** - * @brief Sets up a DMA Transfer for "length" bytes. - * The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting. - * - * This function transmits and receives to buffers. - * - * @param transmitBuf buffer Bytes to transmit. If passed as 0, it sends FF repeatedly for "length" bytes - * @param receiveBuf buffer Bytes to save received data. - * @param length Number of bytes in buffer to transmit. - */ - uint8_t dmaTransfer(const void *transmitBuf, void *receiveBuf, uint16_t length); - void dmaTransferSet(const void *transmitBuf, void *receiveBuf); - uint8_t dmaTransferRepeat(uint16_t length); - - /** - * @brief Sets up a DMA Transmit for SPI 8 or 16 bit transfer mode. - * The transfer mode (8 or 16 bit mode) is evaluated from the SPI peripheral setting. - * - * This function only transmits and does not care about the RX fifo. - * - * @param data buffer half words to transmit, - * @param length Number of bytes in buffer to transmit. - * @param minc Set to use Memory Increment mode, clear to use Circular mode. - */ - uint8_t dmaSend(const void *transmitBuf, uint16_t length, bool minc = 1); - void dmaSendSet(const void *transmitBuf, bool minc); - uint8_t dmaSendRepeat(uint16_t length); - - uint8_t dmaSendAsync(const void *transmitBuf, uint16_t length, bool minc = 1); - /* - * Pin accessors - */ - - /** - * @brief Return the number of the MISO (master in, slave out) pin - */ - uint8_t misoPin(); - - /** - * @brief Return the number of the MOSI (master out, slave in) pin - */ - uint8_t mosiPin(); - - /** - * @brief Return the number of the SCK (serial clock) pin - */ - uint8_t sckPin(); - - /** - * @brief Return the number of the NSS (slave select) pin - */ - uint8_t nssPin(); - - /* Escape hatch */ - - /** - * @brief Get a pointer to the underlying libmaple spi_dev for - * this HardwareSPI instance. - */ - spi_dev *c_dev() { return _currentSetting->spi_d; } - - spi_dev *dev() { return _currentSetting->spi_d; } - - /** - * @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(int spi_num) - { - _currentSetting = &_settings[spi_num - 1]; // SPI channels are called 1 2 and 3 but the array is zero indexed - } - - /* -- The following methods are deprecated --------------------------- */ - - /** - * @brief Deprecated. - * - * Use HardwareSPI::transfer() instead. - * - * @see HardwareSPI::transfer() - */ - uint8_t send(uint8_t data); - - /** - * @brief Deprecated. - * - * Use HardwareSPI::write() in combination with - * HardwareSPI::read() (or HardwareSPI::transfer()) instead. - * - * @see HardwareSPI::write() - * @see HardwareSPI::read() - * @see HardwareSPI::transfer() - */ - uint8_t send(uint8_t *data, uint32_t length); - - /** - * @brief Deprecated. - * - * Use HardwareSPI::read() instead. - * - * @see HardwareSPI::read() - */ - uint8_t recv(); - -private: - SPISettings _settings[BOARD_NR_SPI]; - SPISettings *_currentSetting; - - void updateSettings(); - - /* - * Functions added for DMA transfers with Callback. - * Experimental. - */ - - void EventCallback(); - -#if BOARD_NR_SPI >= 1 - static void _spi1EventCallback(); -#endif -#if BOARD_NR_SPI >= 2 - static void _spi2EventCallback(); -#endif -#if BOARD_NR_SPI >= 3 - static void _spi3EventCallback(); -#endif - /* - spi_dev *spi_d; - uint8_t _SSPin; - uint32_t clockDivider; - uint8_t dataMode; - BitOrder bitOrder; - */ -}; - -/** - * @brief Wait until TXE (tx empty) flag is set and BSY (busy) flag unset. - */ -static inline void waitSpiTxEnd(spi_dev *spi_d) -{ - while (spi_is_tx_empty(spi_d) == 0) - { /* nada */ - } // wait until TXE=1 - while (spi_is_busy(spi_d) != 0) - { /* nada */ - } // wait until BSY=0 -} - -extern SPIClass SPI; -#endif diff --git a/Marlin/src/HAL/HC32F46x/Servo.cpp b/Marlin/src/HAL/HC32F46x/Servo.cpp index fc656b6989c7..87611adb1b1c 100644 --- a/Marlin/src/HAL/HC32F46x/Servo.cpp +++ b/Marlin/src/HAL/HC32F46x/Servo.cpp @@ -1,351 +1,76 @@ -/** - * 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 TARGET_HC32F46x - -#include "../../inc/MarlinConfig.h" - -#if HAS_SERVOS - -uint8_t ServoCount = 0; - #include "Servo.h" -/* TIMERA unit and clock definition */ -#define TIMERA_UNIT1 M4_TMRA1 -#define TIMERA_UNIT1_CLOCK PWC_FCG2_PERIPH_TIMA1 -#define TIMERA_UNIT1_OVERFLOW_INT INT_TMRA1_OVF - -/* TIMERA channel 1 Port/Pin definition */ -#define TIMERA_UNIT1_CH_BL TimeraCh6 -#define TIMERA_UNIT1_CH1_PORT PortB -#define TIMERA_UNIT1_CH1_PIN Pin00 -#define TIMERA_UNIT1_CH1_FUNC Func_Tima0 - -#include "../../core/boards.h" -#include -#ifndef TARGET_HC32F46x -#include -#endif -#include - -#define CYCLES_PER_MICROSECOND (F_CPU / 1000000UL) - -/** - * 20 millisecond period config. For a 1-based prescaler, - * - * (prescaler * overflow / CYC_MSEC) msec = 1 timer cycle = 20 msec - * => prescaler * overflow = 20 * CYC_MSEC - * - * This uses the smallest prescaler that allows an overflow < 2^16. - */ -#define MAX_OVERFLOW UINT16_MAX //((1 << 16) - 1) -#define CYC_MSEC (1000 * CYCLES_PER_MICROSECOND) -#define TAU_MSEC 20 -#define TAU_USEC (TAU_MSEC * 1000) -#define TAU_CYC (TAU_MSEC * CYC_MSEC) -#define SERVO_PRESCALER (TAU_CYC / MAX_OVERFLOW + 1) -#define SERVO_OVERFLOW ((uint16_t)round((double)TAU_CYC / SERVO_PRESCALER)) - -// Unit conversions -#define US_TO_COMPARE(us) uint16_t(map((us), 0, TAU_USEC, 0, SERVO_OVERFLOW)) -#define COMPARE_TO_US(c) uint32_t(map((c), 0, SERVO_OVERFLOW, 0, TAU_USEC)) -#define ANGLE_TO_US(a) uint16_t(map((a), minAngle, maxAngle, SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW)) -#define US_TO_ANGLE(us) int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle)) - -void H32Servo::servoWrite(uint8_t inPin, uint16_t duty_cycle) -{ -#ifdef SERVO0_TIMER_NUM - if (servoIndex == 0) - { - pwmSetDuty(duty_cycle); - return; - } -#endif -#ifndef TARGET_HC32F46x - timer_dev *tdev = PIN_MAP[inPin].timer_device; - uint8_t tchan = PIN_MAP[inPin].timer_channel; - if (tdev) - timer_set_compare(tdev, tchan, duty_cycle); -#else - TIMERA_SetCompareValue(TIMERA_UNIT1, TIMERA_UNIT1_CH_BL, duty_cycle); // release -#endif -} - -H32Servo::H32Servo() -{ - servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO; -#ifndef TARGET_HC32F46x - timer_set_interrupt_priority(SERVO0_TIMER_NUM, SERVO0_TIMER_IRQ_PRIO); -#endif -} - #ifdef TARGET_HC32F46x -void TimeraUnit1_IrqCallback(void) -{ - TIMERA_ClearFlag(TIMERA_UNIT1, TimeraFlagOverflow); -} -#endif - -bool H32Servo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) -{ - if (servoIndex >= MAX_SERVOS) - return false; - if (inPin >= BOARD_NR_GPIO_PINS) - return false; - - minAngle = inMinAngle; - maxAngle = inMaxAngle; - angle = -1; - -#ifdef SERVO0_TIMER_NUM - if (servoIndex == 0 && setupSoftPWM(inPin)) - { - pin = inPin; // set attached() - return true; - } -#endif - -#ifndef TARGET_HC32F46x - - if (!PWM_PIN(inPin)) - return false; - - timer_dev *tdev = PIN_MAP[inPin].timer_device; - // uint8_t tchan = PIN_MAP[inPin].timer_channel; - - SET_PWM(inPin); - servoWrite(inPin, 0); - - timer_pause(tdev); - timer_set_prescaler(tdev, SERVO_PRESCALER - 1); // prescaler is 1-based - timer_set_reload(tdev, SERVO_OVERFLOW); - timer_generate_update(tdev); - timer_resume(tdev); - - pin = inPin; // set attached() - return true; -#else - stc_timera_base_init_t stcTimeraInit; - stc_timera_compare_init_t stcTimerCompareInit; - stc_irq_regi_conf_t stcIrqRegiConf; - stc_timera_hw_startup_config_t stcTimeraHwConfig; - stc_port_init_t stcPortInit; - - uint32_t u32Pclk1; - stc_clk_freq_t stcClkTmp; - - /* Get pclk1 */ - CLK_GetClockFreq(&stcClkTmp); - u32Pclk1 = stcClkTmp.pclk1Freq; // 84MHZ - - /* configuration structure initialization */ - MEM_ZERO_STRUCT(stcTimeraInit); - MEM_ZERO_STRUCT(stcIrqRegiConf); - MEM_ZERO_STRUCT(stcTimerCompareInit); - MEM_ZERO_STRUCT(stcTimeraHwConfig); - MEM_ZERO_STRUCT(stcPortInit); - - /* Configuration peripheral clock */ - PWC_Fcg2PeriphClockCmd(TIMERA_UNIT1_CLOCK, Enable); - PWC_Fcg0PeriphClockCmd(PWC_FCG0_PERIPH_AOS, Enable); - - /* Configuration TIMERA compare pin */ - PORT_SetFunc(TIMERA_UNIT1_CH1_PORT, TIMERA_UNIT1_CH1_PIN, TIMERA_UNIT1_CH1_FUNC, Disable); - - /* Configuration timera unit 1 base structure */ - stcTimeraInit.enClkDiv = TimeraPclkDiv16; - stcTimeraInit.enCntMode = TimeraCountModeTriangularWave; - stcTimeraInit.enCntDir = TimeraCountDirUp; - stcTimeraInit.enSyncStartupEn = Disable; - stcTimeraInit.u16PeriodVal = (uint16_t)((u32Pclk1 / 16) / (50 * 2)); // freq: 100Hz - TIMERA_BaseInit(TIMERA_UNIT1, &stcTimeraInit); - - /* Configuration timera unit 1 compare structure */ - stcTimerCompareInit.u16CompareVal = 0; - stcTimerCompareInit.enStartCountOutput = TimeraCountStartOutputLow; - stcTimerCompareInit.enStopCountOutput = TimeraCountStopOutputLow; - stcTimerCompareInit.enCompareMatchOutput = TimeraCompareMatchOutputLow; - stcTimerCompareInit.enPeriodMatchOutput = TimeraPeriodMatchOutputHigh; - stcTimerCompareInit.enSpecifyOutput = TimeraSpecifyOutputInvalid; - stcTimerCompareInit.enCacheEn = Enable; - stcTimerCompareInit.enTriangularTroughTransEn = Enable; - stcTimerCompareInit.enTriangularCrestTransEn = Disable; - stcTimerCompareInit.u16CompareCacheVal = stcTimerCompareInit.u16CompareVal; - /* Configure Channel 1 */ - TIMERA_CompareInit(TIMERA_UNIT1, TIMERA_UNIT1_CH_BL, &stcTimerCompareInit); - TIMERA_CompareCmd(TIMERA_UNIT1, TIMERA_UNIT1_CH_BL, Enable); +#if HAS_SERVOS - /* Enable period count interrupt */ - TIMERA_IrqCmd(TIMERA_UNIT1, TimeraIrqOverflow, Enable); - /* Interrupt of timera unit 1 */ - stcIrqRegiConf.enIntSrc = TIMERA_UNIT1_OVERFLOW_INT; - stcIrqRegiConf.enIRQn = Int006_IRQn; - stcIrqRegiConf.pfnCallback = &TimeraUnit1_IrqCallback; - enIrqRegistration(&stcIrqRegiConf); - NVIC_ClearPendingIRQ(stcIrqRegiConf.enIRQn); - NVIC_SetPriority(stcIrqRegiConf.enIRQn, DDL_IRQ_PRIORITY_15); - NVIC_EnableIRQ(stcIrqRegiConf.enIRQn); +static uint8_t servoCount = 0; +static MarlinServo *servos[NUM_SERVOS] = {0}; - /* Sync startup timera unit 2 when timera unit 1 startup */ - TIMERA_Cmd(TIMERA_UNIT1, Enable); - pin = inPin; - return true; -#endif -} +constexpr uint32_t servoDelays[] = SERVO_DELAY; +static_assert(COUNT(servoDelays) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); -bool H32Servo::detach() +// +// MarlinServo impl +// +MarlinServo::MarlinServo() { - if (!attached()) - return false; - angle = -1; - servoWrite(pin, 0); - return true; + this->channel = servoCount++; + servos[this->channel] = this; } -int32_t H32Servo::read() const +int8_t MarlinServo::attach(const pin_t apin) { - if (attached()) - { -#ifdef SERVO0_TIMER_NUM - if (servoIndex == 0) - return angle; -#endif -#ifndef TARGET_HC32F46x - timer_dev *tdev = PIN_MAP[pin].timer_device; - uint8_t tchan = PIN_MAP[pin].timer_channel; - return US_TO_ANGLE(COMPARE_TO_US(timer_get_compare(tdev, tchan))); -#else - return US_TO_ANGLE(TIMERA_GetCompareValue(TIMERA_UNIT1, TIMERA_UNIT1_CH_BL)); -#endif - } - return 0; + // use last pin if pin not given + if (apin >= 0) + { + this->pin = apin; + } + + // if attached, do nothing but no fail + if (this->servo.attached()) + { + return 0; + } + + // attach + uint8_t rc = this->servo.attach(this->pin); + return rc == INVALID_SERVO ? -1 : rc; } -void H32Servo::move(const int32_t value) +void MarlinServo::detach() { - constexpr uint16_t servo_delay[] = SERVO_DELAY; - static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); - - if (attached()) - { - angle = constrain(value, minAngle, maxAngle); - servoWrite(pin, US_TO_COMPARE(ANGLE_TO_US(angle))); - safe_delay(servo_delay[servoIndex]); - TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); - } + this->servo.detach(); } -#ifdef SERVO0_TIMER_NUM -extern "C" void Servo_IRQHandler() +bool MarlinServo::attached() { - static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); - uint16_t SR = timer_get_status(tdev); - if (SR & TIMER_SR_CC1IF) - { // channel 1 off -#ifdef SERVO0_PWM_OD - OUT_WRITE_OD(SERVO0_PIN, 1); // off -#else - OUT_WRITE(SERVO0_PIN, 0); -#endif - timer_reset_status_bit(tdev, TIMER_SR_CC1IF_BIT); - } - if (SR & TIMER_SR_CC2IF) - { // channel 2 resume -#ifdef SERVO0_PWM_OD - OUT_WRITE_OD(SERVO0_PIN, 0); // on -#else - OUT_WRITE(SERVO0_PIN, 1); -#endif - timer_reset_status_bit(tdev, TIMER_SR_CC2IF_BIT); - } + return this->servo.attached(); } -bool H32Servo::setupSoftPWM(const int32_t inPin) +void MarlinServo::write(servo_angle_t angle) { - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); - if (!tdev) - return false; -#ifdef SERVO0_PWM_OD - OUT_WRITE_OD(inPin, 1); -#else - OUT_WRITE(inPin, 0); -#endif - - timer_pause(tdev); - timer_set_mode(tdev, 1, TIMER_OUTPUT_COMPARE); // counter with isr - timer_oc_set_mode(tdev, 1, TIMER_OC_MODE_FROZEN, 0); // no pin output change - timer_oc_set_mode(tdev, 2, TIMER_OC_MODE_FROZEN, 0); // no pin output change - timer_set_prescaler(tdev, SERVO_PRESCALER - 1); // prescaler is 1-based - timer_set_reload(tdev, SERVO_OVERFLOW); - timer_set_compare(tdev, 1, SERVO_OVERFLOW); - timer_set_compare(tdev, 2, SERVO_OVERFLOW); - timer_attach_interrupt(tdev, 1, Servo_IRQHandler); - timer_attach_interrupt(tdev, 2, Servo_IRQHandler); - timer_generate_update(tdev); - timer_resume(tdev); - - return true; + this->angle = angle; + this->servo.write(angle); } -void H32Servo::pwmSetDuty(const uint16_t duty_cycle) +void MarlinServo::move(servo_angle_t angle) { - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); - timer_set_compare(tdev, 1, duty_cycle); - timer_generate_update(tdev); - if (duty_cycle) - { - timer_enable_irq(tdev, 1); - timer_enable_irq(tdev, 2); - } - else - { - timer_disable_irq(tdev, 1); - timer_disable_irq(tdev, 2); -#ifdef SERVO0_PWM_OD - OUT_WRITE_OD(pin, 1); // off -#else - OUT_WRITE(pin, 0); -#endif - } -} - -void H32Servo::pauseSoftPWM() -{ // detach - timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM); - timer_pause(tdev); - pwmSetDuty(0); + // attach with pin=-1 to use last pin attach() was called with + if (attach(-1) < 0) + { + // attach failed + return; + } + + write(angle); + safe_delay(servoDelays[this->channel]); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); } -#else - -bool H32Servo::setupSoftPWM(const int32_t inPin) +servo_angle_t MarlinServo::read() { - return false; + return TERN(OPTIMISTIC_SERVO_READ, this->angle, this->servo.read()); } -void H32Servo::pwmSetDuty(const uint16_t duty_cycle) {} -void H32Servo::pauseSoftPWM() {} - -#endif #endif // HAS_SERVOS -#endif // TARGET_HC32F46x +#endif // TARGET_HC32F46x \ No newline at end of file diff --git a/Marlin/src/HAL/HC32F46x/Servo.h b/Marlin/src/HAL/HC32F46x/Servo.h index 6fdd48a90572..a1271d11f427 100644 --- a/Marlin/src/HAL/HC32F46x/Servo.h +++ b/Marlin/src/HAL/HC32F46x/Servo.h @@ -1,68 +1,85 @@ -/** - * 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 . - * - */ -#pragma once +#include "../platforms.h" -// Pin number of unattached pins -#define NOT_ATTACHED (-1) -#define INVALID_SERVO 255 +#ifdef TARGET_HC32F46x -#ifndef MAX_SERVOS -#define MAX_SERVOS 3 -#endif +#include "../../inc/MarlinConfig.h" -#define SERVO_DEFAULT_MIN_PW 544 -#define SERVO_DEFAULT_MAX_PW 2400 -#define SERVO_DEFAULT_MIN_ANGLE 0 -#define SERVO_DEFAULT_MAX_ANGLE 180 +#if HAS_SERVOS -#define HAL_SERVO_LIB H32Servo +#include -#if defined(TARGET_HC32F46x) && NUM_SERVOS > 1 -#error "HC32F46x only supports one servo" -#endif +/** + * return last written value in servo.read instead of calculated value + */ +#define OPTIMISTIC_SERVO_READ -class H32Servo +/** + * @brief servo lib wrapper for marlin + */ +class MarlinServo { public: - H32Servo(); - bool attach(const int32_t pin, const int32_t minAngle = SERVO_DEFAULT_MIN_ANGLE, const int32_t maxAngle = SERVO_DEFAULT_MAX_ANGLE); - bool attached() const { return pin != NOT_ATTACHED; } - bool detach(); - void move(const int32_t value); - int32_t read() const; + MarlinServo(); + + /** + * @brief attach the pin to the servo, set pin mode, return channel number + * @param pin pin to attach to + * @return channel number, -1 if failed + */ + int8_t attach(const pin_t apin); + + /** + * @brief detach servo + */ + void detach(); + + /** + * @brief is servo attached? + */ + bool attached(); + + /** + * @brief set servo angle + * @param angle new angle + */ + void write(servo_angle_t angle); + + /** + * @brief attach servo, move to angle, delay then detach + * @param angle angle to move to + */ + void move(servo_angle_t angle); + + /** + * @brief read current angle + * @return current angle betwwne 0 and 180 degrees + */ + servo_angle_t read(); private: - void servoWrite(uint8_t pin, const uint16_t duty_cycle); + /** + * @brief internal servo object, provided by arduino core + */ + Servo servo; + + /** + * @brief virtual servo channel + */ + uint8_t channel; - uint8_t servoIndex; // index into the channel data for this servo - int32_t pin = NOT_ATTACHED; - int32_t minAngle; - int32_t maxAngle; - int32_t angle; + /** + * @brief pin the servo attached to last + */ + pin_t pin; - bool setupSoftPWM(const int32_t pin); - void pauseSoftPWM(); - void pwmSetDuty(const uint16_t duty_cycle); + /** + * @brief last known servo angle + */ + servo_angle_t angle; }; -typedef H32Servo hal_servo_t; +// alias for marlin HAL +typedef MarlinServo hal_servo_t; + +#endif // HAS_SERVOS +#endif // TARGET_HC32F46x \ No newline at end of file diff --git a/Marlin/src/HAL/HC32F46x/SoftwareSerial.cpp b/Marlin/src/HAL/HC32F46x/SoftwareSerial.cpp deleted file mode 100644 index dd2235115791..000000000000 --- a/Marlin/src/HAL/HC32F46x/SoftwareSerial.cpp +++ /dev/null @@ -1,59 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 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 . - * - */ -#if defined(TARGET_HC32F46x) && !defined(HAVE_SW_SERIAL) - -/* - * Stub class for SoftwareSerial - * - * TODO: if needed, may implement SoftwareSerial using https://github.com/FYSETC/SoftwareSerialM - */ -#include "SoftwareSerial.h" - -SoftwareSerial::SoftwareSerial(int8_t RX_pin, int8_t TX_pin) {} - -void SoftwareSerial::begin(const uint32_t baudrate) {} - -bool SoftwareSerial::available() -{ - return false; -} - -uint8_t SoftwareSerial::read() -{ - return 0; -} - -uint16_t SoftwareSerial::write(uint8_t byte) -{ - return 0; -} - -void SoftwareSerial::flush() {} - -void SoftwareSerial::listen() -{ - listening = true; -} - -void SoftwareSerial::stopListening() -{ - listening = false; -} - -#endif // TARGET_HC32F46x diff --git a/Marlin/src/HAL/HC32F46x/SoftwareSerial.h b/Marlin/src/HAL/HC32F46x/SoftwareSerial.h deleted file mode 100644 index 1d0c9d1e9627..000000000000 --- a/Marlin/src/HAL/HC32F46x/SoftwareSerial.h +++ /dev/null @@ -1,45 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 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 . - * - */ -#pragma once - -#include - -#ifndef HAVE_SW_SERIAL -#define SW_SERIAL_PLACEHOLDER 1 -#endif - -class SoftwareSerial -{ -public: - SoftwareSerial(int8_t RX_pin, int8_t TX_pin); - - void begin(const uint32_t baudrate); - - bool available(); - - uint8_t read(); - uint16_t write(uint8_t byte); - void flush(); - - void listen(); - void stopListening(); - -protected: - bool listening; -}; diff --git a/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_fsmc.cpp b/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_fsmc.cpp index f3f7898a9825..db9697b6910a 100644 --- a/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_fsmc.cpp +++ b/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_fsmc.cpp @@ -29,7 +29,7 @@ #include "../../../inc/MarlinConfig.h" #if defined(TARGET_HC32F46x) && PIN_EXISTS(FSMC_CS) // FSMC on 100/144 pins SoCs -#warning "'u8g_com_stm32duino_fsmc' has not been tested to work as expected. Proceed at your own risk" +#warning "'u8g_com_stm32duino_fsmc' has not been adapted to HC32F46x. Proceed at your own risk" #if HAS_GRAPHICAL_LCD @@ -320,8 +320,8 @@ void LCD_IO_Init(uint8_t cs, uint8_t rs) gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP); // FSMC_NOE gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP); // FSMC_NWE - gpio_set_mode(PIN_MAP[cs].gpio_device, PIN_MAP[cs].gpio_bit, GPIO_AF_OUTPUT_PP); // FSMC_CS_NEx - gpio_set_mode(PIN_MAP[rs].gpio_device, PIN_MAP[rs].gpio_bit, GPIO_AF_OUTPUT_PP); // FSMC_RS_Ax + gpio_set_mode(PIN_MAP[cs].gpio_device, PIN_MAP[cs].bit_pos, GPIO_AF_OUTPUT_PP); // FSMC_CS_NEx + gpio_set_mode(PIN_MAP[rs].gpio_device, PIN_MAP[rs].bit_pos, GPIO_AF_OUTPUT_PP); // FSMC_RS_Ax #if ENABLED(STM32_XL_DENSITY) FSMC_NOR_PSRAM4_BASE->BCR = FSMC_BCR_WREN | FSMC_BCR_MTYP_SRAM | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN; diff --git a/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_swspi.cpp b/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_swspi.cpp index 6b538aa9bc55..473741c073ae 100644 --- a/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_swspi.cpp +++ b/Marlin/src/HAL/HC32F46x/dogm/u8g_com_stm32duino_swspi.cpp @@ -21,7 +21,8 @@ #include "../../../inc/MarlinConfig.h" #if BOTH(HAS_GRAPHICAL_LCD, FORCE_SOFT_SPI) -#warning "'u8g_com_stm32duino_swspi' has not been tested to work as expected. Proceed at your own risk" +#warning "'u8g_com_stm32duino_swspi' has not been adapted to HC32F46x. Proceed at your own risk" + #include "../HAL.h" #include diff --git a/Marlin/src/HAL/HC32F46x/eeprom_flash.cpp b/Marlin/src/HAL/HC32F46x/eeprom_flash.cpp deleted file mode 100644 index 6ae352353f4b..000000000000 --- a/Marlin/src/HAL/HC32F46x/eeprom_flash.cpp +++ /dev/null @@ -1,129 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com - * Copyright (c) 2016 Victor Perez victor_pv@hotmail.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 . - * - */ - -/** - * persistent_store_flash.cpp - * HAL for stm32duino and compatible (HC32F46x based on STM32F1) - * Implementation of EEPROM settings in SDCard - */ - -#ifdef TARGET_HC32F46x - -#include "../../inc/MarlinConfig.h" - -#if ENABLED(FLASH_EEPROM_EMULATION) - -#include "../shared/eeprom_api.h" - -#include -#include - -// Store settings in the last two pages -#ifndef MARLIN_EEPROM_SIZE -#define MARLIN_EEPROM_SIZE ((EEPROM_PAGE_SIZE)*2) -#endif -size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } - -static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; -static bool eeprom_dirty = false; - -bool PersistentStore::access_start() -{ - const uint32_t *source = reinterpret_cast(EEPROM_PAGE0_BASE); - uint32_t *destination = reinterpret_cast(ram_eeprom); - - static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe - constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4; - - for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source) - *destination = *source; - - eeprom_dirty = false; - return true; -} - -bool PersistentStore::access_finish() -{ - - if (eeprom_dirty) - { - FLASH_Status status; - - // Instead of erasing all (both) pages, maybe in the loop we check what page we are in, and if the - // data has changed in that page. We then erase the first time we "detect" a change. In theory, if - // nothing changed in a page, we wouldn't need to erase/write it. - // Or, instead of checking at this point, turn eeprom_dirty into an array of bool the size of number - // of pages. Inside write_data, we set the flag to true at that time if something in that - // page changes...either way, something to look at later. - FLASH_Unlock(); - -#define ACCESS_FINISHED(TF) \ - { \ - FLASH_Lock(); \ - eeprom_dirty = false; \ - return TF; \ - } - - status = FLASH_ErasePage(EEPROM_PAGE0_BASE); - if (status != FLASH_COMPLETE) - ACCESS_FINISHED(true); - status = FLASH_ErasePage(EEPROM_PAGE1_BASE); - if (status != FLASH_COMPLETE) - ACCESS_FINISHED(true); - - const uint16_t *source = reinterpret_cast(ram_eeprom); - for (size_t i = 0; i < MARLIN_EEPROM_SIZE; i += 2, ++source) - { - if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE) - ACCESS_FINISHED(false); - } - - ACCESS_FINISHED(true); - } - - return true; -} - -bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) -{ - for (size_t i = 0; i < size; ++i) - ram_eeprom[pos + i] = value[i]; - eeprom_dirty = true; - crc16(crc, value, size); - pos += size; - return false; // return true for any error -} - -bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing /*=true*/) -{ - const uint8_t *const buff = writing ? &value[0] : &ram_eeprom[pos]; - if (writing) - for (size_t i = 0; i < size; i++) - value[i] = ram_eeprom[pos + i]; - crc16(crc, buff, size); - pos += size; - return false; // return true for any error -} - -#endif // FLASH_EEPROM_EMULATION -#endif // TARGET_HC32F46x diff --git a/Marlin/src/HAL/HC32F46x/eeprom_sdcard.cpp b/Marlin/src/HAL/HC32F46x/eeprom_sdcard.cpp index 2c248f513c54..96e2c41a5f85 100644 --- a/Marlin/src/HAL/HC32F46x/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/HC32F46x/eeprom_sdcard.cpp @@ -21,7 +21,6 @@ */ /** - * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) * Implementation of EEPROM settings in SD Card */ @@ -55,7 +54,7 @@ bool PersistentStore::access_start() return false; } - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) { return true; // false aborts the save @@ -83,7 +82,7 @@ bool PersistentStore::access_finish() return false; } - SdFile file, root = card.getroot(); + MediaFile file, root = card.getroot(); int bytes_written = 0; if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { diff --git a/Marlin/src/HAL/HC32F46x/eeprom_wired.cpp b/Marlin/src/HAL/HC32F46x/eeprom_wired.cpp index 46bc66cba315..ade288ded9f5 100644 --- a/Marlin/src/HAL/HC32F46x/eeprom_wired.cpp +++ b/Marlin/src/HAL/HC32F46x/eeprom_wired.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" #if USE_WIRED_EEPROM -#warning "'eeprom_wired' has not been tested to work as expected. Proceed at your own risk" +#warning "'eeprom_wired' has not been tested on HC32F46x. Please report any issues." /** * PersistentStore for Arduino-style EEPROM interface diff --git a/Marlin/src/HAL/HC32F46x/endstop_interrupts.cpp b/Marlin/src/HAL/HC32F46x/endstop_interrupts.cpp index fdc2b09b1d8d..e027fa1d5a63 100644 --- a/Marlin/src/HAL/HC32F46x/endstop_interrupts.cpp +++ b/Marlin/src/HAL/HC32F46x/endstop_interrupts.cpp @@ -1,39 +1,41 @@ #include "endstop_interrupts.h" #include "../../module/endstops.h" -#include "interrupts.h" +#include + +#define ENDSTOP_IRQ_PRIORITY DDL_IRQ_PRIORITY_06 // // IRQ handler // void endstopIRQHandler() { - bool flag = false; + bool flag = false; // check all irq flags -#define CHECK(name) TERN_(USE_##name, flag |= checkAndClearExtIRQFlag(name##_PIN)) +#define CHECK(name) TERN_(USE_##name, flag |= checkIRQFlag(name##_PIN, /*clear*/ true)) - CHECK(X_MAX); - CHECK(X_MIN); + CHECK(X_MAX); + CHECK(X_MIN); - CHECK(Y_MAX); - CHECK(Y_MIN); + CHECK(Y_MAX); + CHECK(Y_MIN); - CHECK(Z_MAX); - CHECK(Z_MIN); + CHECK(Z_MAX); + CHECK(Z_MIN); - CHECK(Z2_MAX); - CHECK(Z2_MIN); + CHECK(Z2_MAX); + CHECK(Z2_MIN); - CHECK(Z3_MAX); - CHECK(Z3_MIN); + CHECK(Z3_MAX); + CHECK(Z3_MIN); - CHECK(Z_MIN_PROBE); + CHECK(Z_MIN_PROBE); - // update endstops - if (flag) - { - endstops.update(); - } + // update endstops + if (flag) + { + endstops.update(); + } } // @@ -41,24 +43,24 @@ void endstopIRQHandler() // void setup_endstop_interrupts() { -#define SETUP(name) TERN_(USE_##name, attachInterrupt(name##_PIN, endstopIRQHandler, CHANGE)) +#define SETUP(name) TERN_(USE_##name, attachInterrupt(name##_PIN, endstopIRQHandler, CHANGE); setInterruptPriority(name##_PIN, ENDSTOP_IRQ_PRIORITY)) - SETUP(X_MAX); - SETUP(X_MIN); + SETUP(X_MAX); + SETUP(X_MIN); - SETUP(Y_MAX); - SETUP(Y_MIN); + SETUP(Y_MAX); + SETUP(Y_MIN); - SETUP(Z_MAX); - SETUP(Z_MIN); + SETUP(Z_MAX); + SETUP(Z_MIN); - SETUP(Z2_MAX); - SETUP(Z2_MIN); + SETUP(Z2_MAX); + SETUP(Z2_MIN); - SETUP(Z3_MAX); - SETUP(Z3_MIN); + SETUP(Z3_MAX); + SETUP(Z3_MIN); - SETUP(Z_MIN_PROBE); + SETUP(Z_MIN_PROBE); } // ensure max. 10 irqs are registered diff --git a/Marlin/src/HAL/HC32F46x/endstop_interrupts.h b/Marlin/src/HAL/HC32F46x/endstop_interrupts.h index 3826654372c3..575edc5cebb8 100644 --- a/Marlin/src/HAL/HC32F46x/endstop_interrupts.h +++ b/Marlin/src/HAL/HC32F46x/endstop_interrupts.h @@ -23,14 +23,13 @@ #pragma once /** - * Endstop interrupts for Libmaple HC32F46x based on STM32F1 based targets. - * - * On STM32F, all pins support external interrupt capability. - * Any pin can be used for external interrupts, but there are some restrictions. - * At most 16 different external interrupts can be used at one time. - * Further, you can’t just pick any 16 pins to use. This is because every pin on the STM32 - * connects to what is called an EXTI line, and only one pin per EXTI line can be used for external interrupts at a time - * Check the Reference Manual of the MCU to confirm which line is used by each pin + * Endstop interrupts for HC32F46x based targets. + * + * On HC32F46x, all pins support external interrupt capability, with some restrictions. + * See the documentation of WInterrupts#attachInterrupt() for details. + * + * TL;DR + * any 16 pins can be used, but only one pin per EXTI line (so PA0 and PB0 are no-good). */ /** diff --git a/Marlin/src/HAL/HC32F46x/fastio.h b/Marlin/src/HAL/HC32F46x/fastio.h index 90bf6c332e87..b09e0071a8f6 100644 --- a/Marlin/src/HAL/HC32F46x/fastio.h +++ b/Marlin/src/HAL/HC32F46x/fastio.h @@ -24,16 +24,18 @@ /** * Fast I/O interfaces for HC32F46x - * These use GPIO functions instead of Direct Port Manipulation, as on AVR. + * These use GPIO functions instead of Direct Port Manipulation. */ -#include "io.h" +#include +#include +#include -#define READ(IO) (PORT_GetBitGPIO(IO) ? HIGH : LOW) -#define WRITE(IO, V) (((V) > 0) ? PORT_SetBitsGPIO(IO) : PORT_ResetBitsGPIO(IO)) -#define TOGGLE(IO) (PORT_ToggleGPIO(IO)) +#define READ(IO) (GPIO_GetBit(IO) ? HIGH : LOW) +#define WRITE(IO, V) (((V) > 0) ? GPIO_SetBits(IO) : GPIO_ResetBits(IO)) +#define TOGGLE(IO) (GPIO_Toggle(IO)) -#define _GET_MODE(IO) gpio_get_mode(IO) -#define _SET_MODE(IO, M) gpio_set_mode(IO, M) +#define _GET_MODE(IO) getPinMode(IO) +#define _SET_MODE(IO, M) pinMode(IO, M) #define _SET_OUTPUT(IO) _SET_MODE(IO, OUTPUT) #define OUT_WRITE(IO, V) \ @@ -47,12 +49,13 @@ #define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) #define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) #define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_PWM(IO) _SET_MODE(IO, OUTPUT_PWM) #define IS_INPUT(IO) (_GET_MODE(IO) == INPUT || _GET_MODE(IO) == INPUT_FLOATING || _GET_MODE(IO) == INPUT_ANALOG || _GET_MODE(IO) == INPUT_PULLUP || _GET_MODE(IO) == INPUT_PULLDOWN) -#define IS_OUTPUT(IO) (_GET_MODE(IO) == OUTPUT || _GET_MODE(IO) == OUTPUT_OPEN_DRAIN) +#define IS_OUTPUT(IO) (_GET_MODE(IO) == OUTPUT || || _GET_MODE(IO) == OUTPUT_PWM || _GET_MODE(IO) == OUTPUT_OPEN_DRAIN) -// TODO: #warning "PWM_PIN(IO) is not implemented" -#define PWM_PIN(IO) (false) +#define PWM_PIN(IO) isAnalogWritePin(IO) +#define NO_COMPILE_TIME_PWM // cannot check for PWM at compile time #define extDigitalRead(IO) digitalRead(IO) #define extDigitalWrite(IO, V) digitalWrite(IO, V) diff --git a/Marlin/src/HAL/HC32F46x/inc/SanityCheck.h b/Marlin/src/HAL/HC32F46x/inc/SanityCheck.h index 8eefe38aed4a..d32972eacb2b 100644 --- a/Marlin/src/HAL/HC32F46x/inc/SanityCheck.h +++ b/Marlin/src/HAL/HC32F46x/inc/SanityCheck.h @@ -21,10 +21,6 @@ */ #pragma once -/** - * Test HC32F46x-specific configuration values for errors at compile-time. - */ - #if ENABLED(FAST_PWM_FAN) #error "FAST_PWM_FAN is not yet implemented for this platform." #endif diff --git a/Marlin/src/HAL/HC32F46x/pinsDebug.h b/Marlin/src/HAL/HC32F46x/pinsDebug.h index 05ba975a88ce..3cdde53a7929 100644 --- a/Marlin/src/HAL/HC32F46x/pinsDebug.h +++ b/Marlin/src/HAL/HC32F46x/pinsDebug.h @@ -19,9 +19,7 @@ #pragma once #include "fastio.h" #include "../../inc/MarlinConfig.h" - -// allow pins with potentially unsafe FuncSel -// #define ALLOW_UNSAFE_FUNCTION_PINS +#include // // Translation of routines & variables used by pinsDebug.h @@ -32,9 +30,8 @@ #define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS #define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS -#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS) +#define VALID_PIN(pin) IS_GPIO_PIN(pin) #define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin) -#define pwm_status(pin) PWM_PIN(pin) #define digitalRead_mod(p) extDigitalRead(p) #define PRINT_PIN(p) \ do \ @@ -61,21 +58,16 @@ // pins that will cause a hang / reset / disconnect in M43 Toggle and Watch utils // #ifndef M43_NEVER_TOUCH -// do not touch any pin not defined as gpio or sdio function, -// (explicitly) host serial pins, and -// pins related to the oscillator +// do not touch any of the following pins: +// - host serial pins, and +// - pins that could be connected to oscillators (see datasheet, Table 2.1): +// - XTAL = PH0, PH1 +// - XTAL32 = PC14, PC15 #define IS_HOST_USART_PIN(Q) (Q == BOARD_USART2_TX_PIN || Q == BOARD_USART2_RX_PIN) -#define IS_OSC_PIN(Q) (Q == PH0 || Q == PH1 || Q == PH2) -#define IS_PIN_FUNC(Q, FUNC) (PIN_MAP[Q].function == en_port_func_t::Func_##FUNC) - -#ifndef ALLOW_UNSAFE_FUNCTION_PINS -#define IS_SAFE_PIN_FUNC(Q) (IS_PIN_FUNC(Q, Gpio) || IS_PIN_FUNC(Q, Sdio)) -#else -#define IS_SAFE_PIN_FUNC(Q) (true) -#endif +#define IS_OSC_PIN(Q) (Q == PH0 || Q == PH1 || Q == PC14 || Q == PC15) #define M43_NEVER_TOUCH(Q) ( \ - !IS_SAFE_PIN_FUNC(Q) || IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q)) + IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q)) #endif // static int8_t get_pin_mode(pin_t pin) { @@ -86,7 +78,7 @@ static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { if (!VALID_PIN(pin)) return -1; - int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel); + int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel); return pin_t(adc_channel); } @@ -94,7 +86,8 @@ static bool IS_ANALOG(pin_t pin) { if (!VALID_PIN(pin)) return false; - if (PIN_MAP[pin].adc_channel != ADC_PIN_INVALID) + + if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID) { return _GET_MODE(pin) == INPUT_ANALOG && !M43_NEVER_TOUCH(pin); } @@ -113,15 +106,95 @@ static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) return (!IS_ANALOG(pin)); } +/** + * @brief print pin PWM status + * @return true if pin is currently a PWM pin, false otherwise + */ +static bool pwm_status(const pin_t pin) +{ + // get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == NULL) + { + // no pwm pin or no unit assigned + return false; + } + + // a pin that is PWM output is: + // - assigned to a timerA unit (tested above) + // - unit is initialized + // - channel is active + // - GPIO function is set to assigned port_function (cannot test this) + // TODO: check GPIO function is set to assigned port_function + return timera_is_unit_initialized(unit) && timera_is_channel_active(unit, channel); +} + static void pwm_details(const pin_t pin) { - // TODO stub + // get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == NULL) + { + // no pwm pin or no unit assigned + return; + } + + // print timer assignment of pin, eg. "TimerA1Ch2 Func4" + SERIAL_ECHOPGM("TimerA"); + SERIAL_ECHO(TIMERA_REG_TO_X(unit->peripheral.register_base)); + SERIAL_ECHOPGM("Ch"); + SERIAL_ECHO(TIMERA_CHANNEL_TO_X(channel)); + SERIAL_ECHOPGM(" Func"); + SERIAL_ECHO(int(port_function)); + + SERIAL_ECHO_SP(3); // 3 spaces + + // print timer unit state, eg. "1/16 PERAR=1234" OR "N/A" + if (timera_is_unit_initialized(unit)) + { + // unit initialized, print + // - timer clock divider + // - timer period value (PERAR) + const uint8_t clock_divider = timera_clk_div_to_n(unit->state.base_init->enClkDiv); + const uint16_t period = TIMERA_GetPeriodValue(unit->peripheral.register_base); + SERIAL_ECHOPGM("1/"); + SERIAL_ECHO(clock_divider); + SERIAL_ECHOPGM(" PERAR="); + SERIAL_ECHO(period); + } + else + { + // unit not initialized + SERIAL_ECHOPGM("N/A"); + return; + } + + SERIAL_ECHO_SP(3); // 3 spaces + + // print timer channel state, e.g. "CMPAR=1234" OR "N/A" + if (timera_is_channel_active(unit, channel)) + { + // channel active, print + // - channel compare value + const uint16_t compare = TIMERA_GetCompareValue(unit->peripheral.register_base, channel); + SERIAL_ECHOPGM("CMPAR="); + SERIAL_ECHO(compare); + } + else + { + // channel inactive + SERIAL_ECHOPGM("N/A"); + } } static void print_port(pin_t pin) { const char port = 'A' + char(pin >> 4); // pin div 16 - const int16_t gbit = PIN_MAP[pin].gpio_bit; + const int16_t gbit = PIN_MAP[pin].bit_pos; char buffer[8]; sprintf_P(buffer, PSTR("P%c%hd "), port, gbit); if (gbit < 10) diff --git a/Marlin/src/HAL/HC32F46x/printf_retarget.cpp b/Marlin/src/HAL/HC32F46x/printf_retarget.cpp index 31debbafe40e..8abd9accb55f 100644 --- a/Marlin/src/HAL/HC32F46x/printf_retarget.cpp +++ b/Marlin/src/HAL/HC32F46x/printf_retarget.cpp @@ -1,50 +1,40 @@ #ifdef REDIRECT_PRINTF_TO_SERIAL -#include -#include -#include "../../inc/MarlinConfig.h" - -// do printf retargeting using stdio hooks (_write or fputc) -// #define PRINTF_STDIO_RETARGET - -// target for printf retargeting -#ifndef PRINTF_TARGET -#define PRINTF_TARGET MYSERIAL1 +#if !defined(__GNUC__) +#error "only GCC is supported" #endif -#ifdef PRINTF_STDIO_RETARGET -#if defined(__GNUC__) && !defined(__CC_ARM) -extern "C" int _write(int fd, char *pBuffer, int size) +#include "../../inc/MarlinConfig.h" + +/** + * @brief implementation of _write that redirects everything to the host serial(s) + * @param file file descriptor. don't care + * @param ptr pointer to the data to write + * @param len length of the data to write + * @return number of bytes written + * + * @note + * i'm not sure if ptr is guaranteed to be null-terminated, so i'm copying the data to a buffer + * and adding a null terminator just in case + */ +extern "C" int _write(int file, char *ptr, int len) { - for (int i = 0; i < size; i++) + //SERIAL_ECHO_START(); // echo: + for(int i = 0; i < len; i++) { - PRINTF_TARGET.write(pBuffer[i]); + SERIAL_CHAR(ptr[i]); } - return size; + return len; } -#else -extern "C" int32_t fputc(int32_t ch, FILE *f) + +/** + * @brief implementation of _isatty that always returns 1 + * @param file file descriptor. don't care + * @return everything is a tty. there are no files to be had + */ +extern "C" int _isatty(int file) { - PRINTF_TARGET.write(pBuffer[i]); - return ch; + return 1; } -#endif -#else -extern "C" int printf(const char *fmt, ...) -{ - va_list argv; - va_start(argv, fmt); - -// format using vsprintf -#define PRINTF_BUFFER_SIZE 512 - char buffer[PRINTF_BUFFER_SIZE]; - int len = vsnprintf(buffer, PRINTF_BUFFER_SIZE, fmt, argv); - // print to target - PRINTF_TARGET.print(buffer); - - va_end(argv); - return len; -} -#endif -#endif +#endif // REDIRECT_PRINTF_TO_SERIAL diff --git a/Marlin/src/HAL/HC32F46x/sdio.cpp b/Marlin/src/HAL/HC32F46x/sdio.cpp index f3c17dfaec88..86d1f6cdf56e 100644 --- a/Marlin/src/HAL/HC32F46x/sdio.cpp +++ b/Marlin/src/HAL/HC32F46x/sdio.cpp @@ -1,53 +1,72 @@ #ifdef TARGET_HC32F46x #include "sdio.h" +#include #include -#define SDIO_INTERFACE M4_SDIOC1 +// +// SDIO configuration +// +#define SDIO_PERIPHERAL M4_SDIOC1 + +// DMA1 is used by ADC (in arduino core), so we use DMA2 CH0 +#define SDIO_DMA_PERIPHERAL M4_DMA2 +#define SDIO_DMA_CHANNEL DmaCh0 + +// SDIO read/write operation retries and timeouts #define SDIO_READ_RETRIES 3 +#define SDIO_READ_TIMEOUT 100 // ms + #define SDIO_WRITE_RETRIES 1 -#define SDIO_TIMEOUT 100u +#define SDIO_WRITE_TIMEOUT 100 // ms + +// +// HAL functions +// #define WITH_RETRY(retries, fn) \ for (int retry = 0; retry < (retries); retry++) \ { \ MarlinHAL::watchdog_refresh(); \ + yield(); \ fn \ } -static stc_sd_handle_t cardHandle; - -const stc_sdcard_dma_init_t dmaConf = { - .DMAx = M4_DMA2, - .enDmaCh = DmaCh0, -}; - -const stc_sdcard_init_t cardConf = { - .enBusWidth = SdiocBusWidth4Bit, - .enClkFreq = SdiocClk400K, - .enSpeedMode = SdiocNormalSpeedMode, - .pstcInitCfg = NULL, -}; +stc_sd_handle_t *handle; bool SDIO_Init() { // configure SDIO pins - PORT_SetFuncGPIO(BOARD_SDIO_D0, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_D1, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_D2, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_D3, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_CLK, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_CMD, Disable); - PORT_SetFuncGPIO(BOARD_SDIO_DET, Disable); - - // create sdio handle - MEM_ZERO_STRUCT(cardHandle); - cardHandle.SDIOCx = SDIO_INTERFACE; - cardHandle.enDevMode = SdCardDmaMode; - cardHandle.pstcDmaInitCfg = &dmaConf; + GPIO_SetFunc(BOARD_SDIO_D0, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D1, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D2, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D3, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CLK, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CMD, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_DET, Func_Sdio); + + // create DMA configuration + stc_sdcard_dma_init_t *dmaConf = new stc_sdcard_dma_init_t; + dmaConf->DMAx = SDIO_DMA_PERIPHERAL; + dmaConf->enDmaCh = SDIO_DMA_CHANNEL; + + // create handle in DMA mode + handle = new stc_sd_handle_t; + handle->SDIOCx = SDIO_PERIPHERAL; + handle->enDevMode = SdCardDmaMode; + handle->pstcDmaInitCfg = dmaConf; + + // create card configuration + // this should be a fairly safe configuration for most cards + stc_sdcard_init_t cardConf = { + .enBusWidth = SdiocBusWidth4Bit, + .enClkFreq = SdiocClk400K, + .enSpeedMode = SdiocNormalSpeedMode, + //.pstcInitCfg = NULL, + }; // initialize sd card - en_result_t rc = SDCARD_Init(&cardHandle, &cardConf); + en_result_t rc = SDCARD_Init(handle, &cardConf); if (rc != Ok) { printf("SDIO_Init() error (rc=%u)\n", rc); @@ -58,15 +77,18 @@ bool SDIO_Init() bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + CORE_ASSERT(dst != NULL, "SDIO_ReadBlock dst is NULL"); + WITH_RETRY(SDIO_READ_RETRIES, { - en_result_t rc = SDCARD_ReadBlocks(&cardHandle, block, 1, dst, SDIO_TIMEOUT); + en_result_t rc = SDCARD_ReadBlocks(handle, block, 1, dst, SDIO_READ_TIMEOUT); if (rc == Ok) { return true; } else { - printf("SDIO_ReadBlock error (rc=%u)\n", rc); + printf("SDIO_ReadBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); } }) @@ -75,15 +97,18 @@ bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + CORE_ASSERT(src != NULL, "SDIO_WriteBlock src is NULL"); + WITH_RETRY(SDIO_WRITE_RETRIES, { - en_result_t rc = SDCARD_WriteBlocks(&cardHandle, block, 1, (uint8_t *)src, SDIO_TIMEOUT); + en_result_t rc = SDCARD_WriteBlocks(handle, block, 1, (uint8_t *)src, SDIO_WRITE_TIMEOUT); if (rc == Ok) { return true; } else { - printf("SDIO_WriteBlock error (rc=%u)\n", rc); + printf("SDIO_WriteBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); } }) @@ -92,16 +117,19 @@ bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) bool SDIO_IsReady() { - return bool(cardHandle.stcCardStatus.READY_FOR_DATA); + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + return bool(handle->stcCardStatus.READY_FOR_DATA); } uint32_t SDIO_GetCardSize() { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + // multiply number of blocks with block size to get size in bytes - uint64_t cardSizeBytes = uint64_t(cardHandle.stcSdCardInfo.u32LogBlockNbr) * uint64_t(cardHandle.stcSdCardInfo.u32LogBlockSize); + uint64_t cardSizeBytes = uint64_t(handle->stcSdCardInfo.u32LogBlockNbr) * uint64_t(handle->stcSdCardInfo.u32LogBlockSize); // if the card is bigger than ~4Gb (maximum a 32bit integer can hold), clamp to the maximum value of a 32 bit integer - if(cardSizeBytes >= UINT32_MAX) + if (cardSizeBytes >= UINT32_MAX) { return UINT32_MAX; } diff --git a/Marlin/src/HAL/HC32F46x/soctemp.cpp b/Marlin/src/HAL/HC32F46x/soctemp.cpp deleted file mode 100644 index f741cfc4b8be..000000000000 --- a/Marlin/src/HAL/HC32F46x/soctemp.cpp +++ /dev/null @@ -1,51 +0,0 @@ -#include "soctemp.h" -#include - -#define _MK_STRING(M) #M -#define MK_STRING(M) _MK_STRING(M) -#define SOC_WARN_TEMP_STR MK_STRING(SOC_WARN_TEMP) - -uint32_t SOCTemp::lastCheckMillis = 0; - -void SOCTemp::init() -{ - H32OTS::init(); -} - -bool SOCTemp::criticalTemperatureReached() -{ - if (shouldCheck()) - { - float temperature = -1; - if (H32OTS::read(temperature)) - { - // print warning using printf - if (temperature >= SOC_WARN_TEMP) - { - char buf[10]; - dtostrf(temperature, 8, 1, buf); - printf("SoC temperature %s C is above warning treshold " SOC_WARN_TEMP_STR " C\n", buf); - } - - // check critical temperature - if (temperature >= SOC_CRITICAL_TEMP) - { - return true; - } - } - } - - return false; -} - -bool SOCTemp::shouldCheck() -{ - uint32_t now = millis(); - if (now > (lastCheckMillis + SOC_TEMP_CHECK_INTERVAL)) - { - lastCheckMillis = now; - return true; - } - - return false; -} diff --git a/Marlin/src/HAL/HC32F46x/soctemp.h b/Marlin/src/HAL/HC32F46x/soctemp.h deleted file mode 100644 index 777d9ada5f3e..000000000000 --- a/Marlin/src/HAL/HC32F46x/soctemp.h +++ /dev/null @@ -1,22 +0,0 @@ -#pragma once -#include -#include "Arduino.h" - -#define SOC_WARN_TEMP 75 -#define SOC_CRITICAL_TEMP 90 -#define SOC_TEMP_CHECK_INTERVAL 1000 - -class SOCTemp -{ -public: - static void init(); - static bool criticalTemperatureReached(); - -private: - static bool shouldCheck(); - static uint32_t lastCheckMillis; -}; - -#if SOC_CRITICAL_TEMP < SOC_WARN_TEMP -#error "SOC_CRITICAL_TEMP must be higher than SOC_WARN_TEMP" -#endif diff --git a/Marlin/src/HAL/HC32F46x/spi_pins.h b/Marlin/src/HAL/HC32F46x/spi_pins.h index bf2a89655e18..dca306f3b41c 100644 --- a/Marlin/src/HAL/HC32F46x/spi_pins.h +++ b/Marlin/src/HAL/HC32F46x/spi_pins.h @@ -17,22 +17,3 @@ * */ #pragma once - -/** - * HAL for stm32duino.com based on Libmaple and compatible (HC32F46x based on STM32F1) - */ - -/** - * STM32F1 Default SPI Pins - * - * SS SCK MISO MOSI - * +-----------------------------+ - * SPI1 | PA4 PA5 PA6 PA7 | - * SPI2 | PB12 PB13 PB14 PB15 | - * SPI3 | PA15 PB3 PB4 PB5 | - * +-----------------------------+ - * Any pin can be used for Chip Select (SS_PIN) - * SPI1 is enabled by default - */ - -#define SPI_DEVICE 1 diff --git a/Marlin/src/HAL/HC32F46x/sysclock.cpp b/Marlin/src/HAL/HC32F46x/sysclock.cpp new file mode 100644 index 000000000000..890d4cc1917e --- /dev/null +++ b/Marlin/src/HAL/HC32F46x/sysclock.cpp @@ -0,0 +1,98 @@ +/** + * HC32f460 system clock configuration + */ +#include +#include + +// get BOARD_XTAL_FREQUENCY from configuration / pins +#include "../../inc/MarlinConfig.h" + +void core_hook_sysclock_init() +{ + // set wait cycles, as we are about to switch to 200 MHz HCLK + sysclock_configure_flash_wait_cycles(); + sysclock_configure_sram_wait_cycles(); + + // configure MPLLp to 200 MHz output, with different settings depending on XTAL availability +#if BOARD_XTAL_FREQUENCY == 8000000 // 8 MHz XTAL + // - M = 1 => 8 MHz / 1 = 8 MHz + // - N = 50 => 8 MHz * 50 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 50u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_xtal(); + sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf); + +#elif BOARD_XTAL_FREQUENCY == 16000000 // 16 MHz XTAL + // - M = 1 => 16 MHz / 1 = 16 MHz + // - N = 50 => 16 MHz * 25 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 50u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_xtal(); + sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf); + +#warning "16 MHz XTAL is not tested yet, please check clock dump on startup and report any issues" + +#else // HRC (16 MHz) + // - M = 1 => 16 MHz / 1 = 16 MHz + // - N = 25 => 16 MHz * 25 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 25u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_hrc(); + sysclock_configure_mpll(ClkPllSrcHRC, &pllConf); + + // HRC could have been configured by ICG to 20 MHz + // TODO: handle this gracefully + if (1UL != (HRC_FREQ_MON() & 1UL)) + { + panic("HRC is not 16 MHz"); + } + +#if defined(BOARD_XTAL_FREQUENCY) +#warning "no valid XTAL frequency defined, falling back to HRC. please submit a PR or issue to add support for your XTAL frequency" +#endif +#endif + + // setup clock divisors for sysclk = 200 MHz: + // note: PCLK1 is used for step+temp timers, and need to be kept at 50 MHz (until there is a better solution) + stc_clk_sysclk_cfg_t sysClkConf = { + .enHclkDiv = ClkSysclkDiv1, // HCLK = 200 MHz (CPU) + .enExclkDiv = ClkSysclkDiv2, // EXCLK = 100 MHz (SDIO) + .enPclk0Div = ClkSysclkDiv1, // PCLK0 = 200 MHz (Timer6 (not used)) + .enPclk1Div = ClkSysclkDiv4, // PCLK1 = 50 MHz (USART, SPI, I2S, Timer0 (step+temp), TimerA (Servo)) + .enPclk2Div = ClkSysclkDiv4, // PCLK2 = 50 MHz (ADC) + .enPclk3Div = ClkSysclkDiv4, // PCLK3 = 50 MHz (I2C, WDT) + .enPclk4Div = ClkSysclkDiv2, // PCLK4 = 100 MHz (ADC ctl) + }; + sysclock_set_clock_dividers(&sysClkConf); + + // set power mode +#define POWER_MODE_SYSTEM_CLOCK 200000000 // 200 MHz + power_mode_update_pre(POWER_MODE_SYSTEM_CLOCK); + + // switch to MPLL as sysclk source + CLK_SetSysClkSource(CLKSysSrcMPLL); + + // set power mode + power_mode_update_post(POWER_MODE_SYSTEM_CLOCK); +} diff --git a/Marlin/src/HAL/HC32F46x/timers.cpp b/Marlin/src/HAL/HC32F46x/timers.cpp index 7a767af9bc0f..10396afe3c5e 100644 --- a/Marlin/src/HAL/HC32F46x/timers.cpp +++ b/Marlin/src/HAL/HC32F46x/timers.cpp @@ -1,137 +1,32 @@ #include "timers.h" -#include "hc32f460_clk.h" -#include "hc32f460_pwc.h" -#include "hc32f460_timer0.h" -#include "hc32f460_interrupts.h" +#include -#define TMR_UNIT M4_TMR02 +/** + * Timer0 Unit 2 Channel A is used for Temperature interrupts + */ +Timer0 temp_timer(&TIMER02A_config, &Temp_Handler); -// -// Util -// - -inline void setupTimer(const en_tim0_channel_t channel, const uint32_t frequency, const uint32_t prescaler) -{ - // get pclk1 frequency - stc_clk_freq_t clkInfo; - CLK_GetClockFreq(&clkInfo); - uint32_t pclk1Freq = clkInfo.pclk1Freq; - - // enable Timer0 peripheral - PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIM02, Enable); - - // configure timer channel - stc_tim0_base_init_t timerConf; - MEM_ZERO_STRUCT(timerConf); - timerConf.Tim0_CounterMode = Tim0_Sync; - timerConf.Tim0_SyncClockSource = Tim0_Pclk1; - timerConf.Tim0_ClockDivision = Tim0_ClkDiv16; - timerConf.Tim0_CmpValue = (uint16_t)((pclk1Freq / prescaler) / frequency); - - TIMER0_BaseInit(TMR_UNIT, channel, &timerConf); -} - -inline void setupTimerIRQ(const en_tim0_channel_t channel, const IRQn irq, const en_int_src_t source, const uint32_t priority, const func_ptr_t handler) -{ - // enable timer interrupt - TIMER0_IntCmd(TMR_UNIT, channel, Enable); - - stc_irq_regi_conf_t irqConf; - MEM_ZERO_STRUCT(irqConf); - - // register timer interrupt on choosen irq - irqConf.enIRQn = irq; - irqConf.enIntSrc = source; - - // set irq handler - irqConf.pfnCallback = handler; - - // register the irq - enIrqRegistration(&irqConf); - - // clear pending irq, set priority and enable - NVIC_ClearPendingIRQ(irqConf.enIRQn); - NVIC_SetPriority(irqConf.enIRQn, priority); - NVIC_EnableIRQ(irqConf.enIRQn); -} - -// -// HAL -// +/** + * Timer0 Unit 2 Channel B is used for Step interrupts + */ +Timer0 step_timer(&TIMER02B_config, &Step_Handler); void HAL_timer_start(const timer_channel_t timer_num, const uint32_t frequency) { - switch (timer_num) + if (timer_num == TEMP_TIMER_NUM) { - case STEP_TIMER_NUM: - setupTimer(STEP_TIMER_NUM, frequency, STEPPER_TIMER_PRESCALE); - setupTimerIRQ(STEP_TIMER_NUM, IRQn::Int000_IRQn, en_int_src_t::INT_TMR02_GCMB, DDL_IRQ_PRIORITY_01, &Step_Handler); - break; - case TEMP_TIMER_NUM: - setupTimer(TEMP_TIMER_NUM, frequency, TEMP_TIMER_PRESCALE); - setupTimerIRQ(TEMP_TIMER_NUM, IRQn::Int001_IRQn, en_int_src_t::INT_TMR02_GCMA, DDL_IRQ_PRIORITY_02, &Temp_Handler); - break; + CORE_DEBUG_PRINTF("HAL_timer_start: temp timer, f=%ld\n", long(frequency)); + timer_num->start(frequency, TEMP_TIMER_PRESCALE); + timer_num->setCallbackPriority(TEMP_TIMER_PRIORITY); } -} - -void HAL_timer_enable_interrupt(const timer_channel_t timer_num) -{ - switch (timer_num) + else if (timer_num == STEP_TIMER_NUM) { - case STEP_TIMER_NUM: - TIMER0_Cmd(TMR_UNIT, STEP_TIMER_NUM, Enable); - break; - case TEMP_TIMER_NUM: - TIMER0_Cmd(TMR_UNIT, TEMP_TIMER_NUM, Enable); - break; + CORE_DEBUG_PRINTF("HAL_timer_start: step timer, f=%ld\n", long(frequency)); + timer_num->start(frequency, STEPPER_TIMER_PRESCALE); + timer_num->setCallbackPriority(STEP_TIMER_PRIORITY); } -} - -void HAL_timer_disable_interrupt(const timer_channel_t timer_num) -{ - switch (timer_num) - { - case STEP_TIMER_NUM: - TIMER0_Cmd(TMR_UNIT, STEP_TIMER_NUM, Disable); - break; - case TEMP_TIMER_NUM: - TIMER0_Cmd(TMR_UNIT, TEMP_TIMER_NUM, Disable); - break; - } -} - -bool HAL_timer_interrupt_enabled(const timer_channel_t timer_num) -{ - switch (timer_num) + else { - case STEP_TIMER_NUM: - return bool(TMR_UNIT->BCONR_f.CSTB); - case TEMP_TIMER_NUM: - return bool(TMR_UNIT->BCONR_f.CSTA); - default: - return false; + CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_num") } } - -hal_timer_t lastCompare = 0x0; - -void HAL_timer_set_compare(const timer_channel_t timer_num, const hal_timer_t compare) -{ - if (lastCompare != compare) - { - lastCompare = compare; - TIMER0_WriteCmpReg(TMR_UNIT, (en_tim0_channel_t)timer_num, compare); - } -} - -hal_timer_t HAL_timer_get_count(const timer_channel_t timer_num) -{ - return TIMER0_GetCntReg(TMR_UNIT, (en_tim0_channel_t)timer_num); -} - -void HAL_timer_isr_prologue(const timer_channel_t timer_num) -{ - TIMER0_ClearFlag(M4_TMR02, (en_tim0_channel_t)timer_num); -} - -void HAL_timer_isr_epilogue(const timer_channel_t timer_num) {} diff --git a/Marlin/src/HAL/HC32F46x/timers.h b/Marlin/src/HAL/HC32F46x/timers.h index 0c9018ebd071..8612390bce1d 100644 --- a/Marlin/src/HAL/HC32F46x/timers.h +++ b/Marlin/src/HAL/HC32F46x/timers.h @@ -17,58 +17,107 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see . - * */ #pragma once #include -#include "hc32f460_timer0.h" +#include // -// Misc. +// Timer Types // -typedef en_tim0_channel_t timer_channel_t; +typedef Timer0 *timer_channel_t; typedef uint16_t hal_timer_t; #define HAL_TIMER_TYPE_MAX 0xFFFF -// frequency of the timer peripheral -#define HAL_TIMER_RATE uint32_t(F_CPU) +// +// Timer instances +// +extern Timer0 temp_timer; +extern Timer0 step_timer; // -// Timer Channels and Configuration +// Timer Configurations // -#define STEP_TIMER_NUM Tim0_ChannelB -#define TEMP_TIMER_NUM Tim0_ChannelA -#define PULSE_TIMER_NUM STEP_TIMER_NUM -// channel aliases -#define MF_TIMER_STEP STEP_TIMER_NUM -#define MF_TIMER_TEMP TEMP_TIMER_NUM -#define MF_TIMER_PULSE PULSE_TIMER_NUM +// TODO: some calculations (step irq min_step_rate) require the timer rate to be known at compile time +// this is not possible with the HC32F46x, as the timer rate depends on PCLK1 +// as a workaround, PCLK1 = 50MHz is assumed (check with clock dump in MarlinHAL::init()) +// #define HAL_TIMER_RATE 50000000 // 50MHz +// #define HAL_TIMER_RATE TIMER0_BASE_FREQUENCY -#define TEMP_TIMER_FREQUENCY 1000 +// temperature timer +#define TEMP_TIMER_NUM (&temp_timer) +#define TEMP_TIMER_PRIORITY DDL_IRQ_PRIORITY_02 #define TEMP_TIMER_PRESCALE 16ul +#define TEMP_TIMER_RATE 1000 // 1kHz +#define TEMP_TIMER_FREQUENCY TEMP_TIMER_RATE // alias for Marlin +// stepper timer +#define STEP_TIMER_NUM (&step_timer) +#define STEP_TIMER_PRIORITY DDL_IRQ_PRIORITY_01 #define STEPPER_TIMER_PRESCALE 16ul -//TODO: derive this from the timer rate and prescale -// since F_CPU is not constant, it cannot be used here... -#define STEPPER_TIMER_RATE 2000000 // (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) +// FIXME: this manually sets the stepper rate to 2MHz, even tho it actually runs at 3.125MHz +// this is a workaround because otherwise, prints fail with weird print artifacts... +// this could probably be solved by adjusting the steps/mm values, but idk how to do that yet... +#define STEPPER_TIMER_RATE 2000000 +// #define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) +// pulse timer (== stepper timer) +#define PULSE_TIMER_NUM STEP_TIMER_NUM #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +// +// channel aliases +// +#define MF_TIMER_TEMP TEMP_TIMER_NUM +#define MF_TIMER_STEP STEP_TIMER_NUM +#define MF_TIMER_PULSE PULSE_TIMER_NUM + // // HAL functions // void HAL_timer_start(const timer_channel_t timer_num, const uint32_t frequency); -void HAL_timer_enable_interrupt(const timer_channel_t timer_num); -void HAL_timer_disable_interrupt(const timer_channel_t timer_num); -bool HAL_timer_interrupt_enabled(const timer_channel_t timer_num); -void HAL_timer_set_compare(const timer_channel_t timer_num, const hal_timer_t compare); -hal_timer_t HAL_timer_get_count(const timer_channel_t timer_num); -void HAL_timer_isr_prologue(const timer_channel_t timer_num); -void HAL_timer_isr_epilogue(const timer_channel_t timer_num); + +// inlined since they are somewhat critical +#define MARLIN_HAL_TIMER_INLINE_ATTR __attribute__((always_inline)) inline + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_enable_interrupt(const timer_channel_t timer_num) +{ + timer_num->resume(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_disable_interrupt(const timer_channel_t timer_num) +{ + timer_num->pause(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR bool HAL_timer_interrupt_enabled(const timer_channel_t timer_num) +{ + return timer_num->isPaused(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_set_compare(const timer_channel_t timer_num, const hal_timer_t compare) +{ + timer_num->setCompareValue(compare); +} + +MARLIN_HAL_TIMER_INLINE_ATTR hal_timer_t HAL_timer_get_count(const timer_channel_t timer_num) +{ + return timer_num->getCount(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_prologue(const timer_channel_t timer_num) +{ + timer_num->clearInterruptFlag(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_epilogue(const timer_channel_t timer_num) +{ + // nothing +} // // HAL function aliases @@ -87,8 +136,8 @@ void Step_Handler(); void Temp_Handler(); #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() void Step_Handler() +#define HAL_STEP_TIMER_ISR() void Step_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() void Temp_Handler() +#define HAL_TEMP_TIMER_ISR() void Temp_Handler() #endif diff --git a/Marlin/src/pins/hc32f46x/pins_Aquila_V101.h b/Marlin/src/pins/hc32f46x/pins_Aquila_V101.h index 1dd39983eb38..c76df909ab0e 100644 --- a/Marlin/src/pins/hc32f46x/pins_Aquila_V101.h +++ b/Marlin/src/pins/hc32f46x/pins_Aquila_V101.h @@ -22,7 +22,7 @@ #pragma once // -// Voxelab Aquila V1.0.1 (HC32F460) as found in the Voxelab Aquila X2 +// Voxelab Aquila V1.0.1 and V1.0.2 (HC32F460) as found in the Voxelab Aquila X2 // #include "env_validate.h" @@ -37,6 +37,13 @@ #define DEFAULT_MACHINE_NAME "Aquila" #endif +// +// on-board crystal oscillator +// +#ifndef BOARD_XTAL_FREQUENCY + #define BOARD_XTAL_FREQUENCY 8000000 // 8 MHz XTAL +#endif + // // EEPROM // @@ -154,7 +161,6 @@ #ifndef FAN_PIN #define FAN0_PIN PA0 // FAN0 #endif -#define FAN_SOFT_PWM_REQUIRED // // SD Card @@ -167,32 +173,47 @@ // // Screen Pins // -// Screen Port Pinout: -// TODO: check screen port pinout -// ------ -// ? | 1 2 | ? -// ? | 3 4 | ? -// ? 5 6 | ? -// ? | 7 8 | ? -// ? | 9 10 | ? -// ------ +// ------ +// PC6 | 1 2 | PB2 +// PC0 | 3 4 | PC1 +// PB14 5 6 | PB13 +// PB12 | 7 8 | PB15 +// GND | 9 10 | +5V +// ------ +#define EXP_01_PIN PC6 +#define EXP_02_PIN PB2 +#define EXP_03_PIN PC0 +#define EXP_04_PIN PC1 +#define EXP_05_PIN PB14 +#define EXP_06_PIN PB13 +#define EXP_07_PIN PB12 +#define EXP_08_PIN PB15 #if ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) - #define BTN_ENC PB14 - #define BTN_EN1 PB15 - #define BTN_EN2 PB12 + // screen pinout (screen side, so RX/TX are swapped) + // ------ + // NC | 1 2 | NC + // RX | 3 4 | TX + // EN 5 6 | BEEP + // B | 7 8 | A + // GND | 9 10 | +5V + // ------ + + #define BTN_ENC EXP_05_PIN // EN + #define BTN_EN1 EXP_08_PIN // A + #define BTN_EN2 EXP_07_PIN // B #ifndef BEEPER_PIN - #define BEEPER_PIN PB13 + #define BEEPER_PIN EXP_06_PIN // BEEP #endif + + #define BOARD_USART1_RX_PIN EXP_04_PIN // screen TX + #define BOARD_USART1_TX_PIN EXP_03_PIN // screen RX #endif // -// Pins for documentation and sanity checks -// Changing these will NOT change the pin they are on -// - // SDIO Pins +// #define BOARD_SDIO_D0 PC8 #define BOARD_SDIO_D1 PC9 #define BOARD_SDIO_D2 PC10 @@ -201,15 +222,26 @@ #define BOARD_SDIO_CMD PD2 #define BOARD_SDIO_DET PA10 -// USARTS -#define BOARD_USART1_TX_PIN PC0 -#define BOARD_USART1_RX_PIN PC1 +// +// USART Pins +// +// Screen +#ifndef BOARD_USART1_TX_PIN + #define BOARD_USART1_TX_PIN PC0 +#endif +#ifndef BOARD_USART1_RX_PIN + #define BOARD_USART1_RX_PIN PC1 +#endif +// Host #define BOARD_USART2_TX_PIN PA9 #define BOARD_USART2_RX_PIN PA15 +// Unused / Debug #define BOARD_USART3_TX_PIN PE5 #define BOARD_USART3_RX_PIN PE4 -// on-board LED (?) -// #define LED PA3 +// on-board LED (HIGH = off, LOW = on) +#ifndef LED_BUILTIN + #define LED_BUILTIN PA3 +#endif diff --git a/ini/hc32.ini b/ini/hc32.ini index b51ba9519ed6..81e65fd98d90 100644 --- a/ini/hc32.ini +++ b/ini/hc32.ini @@ -30,18 +30,36 @@ platform = https://github.com/shadow578/platform-hc32f46x.git board = generic_hc32f460 build_flags = - -D TARGET_HC32F46x - -D REDIRECT_PRINTF_TO_SERIAL - -D __DEBUG - -D PLATFORM_M997_SUPPORT + -D TARGET_HC32F46x # marlin target + -D REDIRECT_PRINTF_TO_SERIAL # redirect core-provided printf to host serial + -D __DEBUG # DDL debug mode + -D __CORE_DEBUG # core debug mode + -D ENABLE_MICROS # enable support for micros(), switch systick to 1us (instead of 1ms) + -D DISABLE_SERIAL_GLOBALS # disable global Serial objects, we use our own + -D F_CPU=(SYSTEM_CLOCK_FREQUENCIES.pclk1) # override F_CPU to PCLK1, as marlin freaks out otherwise... + -D PLATFORM_M997_SUPPORT # enable M997 command + # options to reduce debug mode footprint (-16K; messages are less verbose) + -D __DEBUG_SHORT_FILENAMES # use short filenames in DDL debug output + -D __CORE_DEBUG_SHORT_FILENAMES # use short filenames in core debug output + -D __CORE_DEBUG_OMIT_PANIC_MESSAGE # omit panic messages in core debug output + build_src_filter = ${common.default_src_filter} + + # Drivers and Middleware required by the HC32F46x HAL board_build.ddl.ots = true +board_build.ddl.sdioc = true +board_build.ddl.wdt = true board_build.ddl.timer0 = true board_build.ddl.timera = true board_build.mw.sd_card = true +# additional, more aggressive optimization flags +board_build.flags.cpp = + -fno-threadsafe-statics # disable thread-safe statics (only one core anyway) + -fno-exceptions # disable exceptions (not used by marlin) + -fno-rtti # disable RTTI (not used by marlin) + + # # HC32F460xCxx (256K Flash) # @@ -64,3 +82,7 @@ extends = common_HC32F460xCxx_variant # bootloader start address, as logged by the bootloader on boot board_build.ld_args.flash_start = 0xC000 +# print panic messages to Serial2 (host serial) +build_flags = + ${common_HC32F460xCxx_variant.build_flags} # extend common flags + -D PANIC_USART2_TX_PIN=PA9 # write panic messages to PA9 (TX of host serial) using USART2