HAL for HC32F460 (#26414)

This commit is contained in:
Chris 2023-11-27 00:58:56 +01:00 committed by GitHub
parent 8a110b80bf
commit 86338ca835
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
43 changed files with 3061 additions and 4 deletions

View file

@ -137,6 +137,9 @@ jobs:
# STM32G0 # STM32G0
- STM32G0B1RE_btt - STM32G0B1RE_btt
# HC32
- HC32F460C_aquila_101
# LPC176x - Lengthy tests # LPC176x - Lengthy tests
- LPC1768 - LPC1768
- LPC1769 - LPC1769

View file

@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "HAL.h"
#include <core_hooks.h>
#include <drivers/panic/panic.h>
//
// Emergency Parser
//
#if ENABLED(EMERGENCY_PARSER)
extern "C" void core_hook_usart_rx_irq(uint8_t ch, uint8_t usart) {
// Only handle receive on host serial ports
if (false
#ifdef SERIAL_PORT
|| usart != SERIAL_PORT
#endif
#ifdef SERIAL_PORT_2
|| usart != SERIAL_PORT_2
#endif
#ifdef SERIAL_PORT_3
|| usart != SERIAL_PORT_3
#endif
) {
return;
}
// Submit character to emergency parser
if (MYSERIAL1.emergency_parser_enabled())
emergency_parser.update(MYSERIAL1.emergency_state, ch);
}
#endif // EMERGENCY_PARSER
#endif // ARDUINO_ARCH_HC32

154
Marlin/src/HAL/HC32/HAL.h Normal file
View file

@ -0,0 +1,154 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL for HC32F460 based boards
*
* Note: MarlinHAL class is in MarlinHAL.h/cpp
*/
#define CPU_32_BIT
#include "../../inc/MarlinConfig.h"
#include "../../core/macros.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "timers.h"
#include "MarlinSerial.h"
#include <stdint.h>
//
// Serial Ports
//
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
#define NUM_UARTS 4
#if SERIAL_PORT == -1
#error "USB Serial is not supported on HC32F460"
#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS)
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
#define MYSERIAL1 MSERIAL(1) // Dummy port
static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ".")
#endif
#ifdef SERIAL_PORT_2
#if SERIAL_PORT_2 == -1
#error "USB Serial is not supported on HC32F460"
#elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS)
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
#define MYSERIAL2 MSERIAL(1) // Dummy port
static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ".")
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1
#error "USB Serial is not supported on HC32F460"
#elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#define MYSERIAL3 MSERIAL(1) // Dummy port
static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ".")
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if LCD_SERIAL_PORT == -1
#error "USB Serial is not supported on HC32F460"
#elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
#define LCD_SERIAL MSERIAL(1) // Dummy port
static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ".")
#endif
#if HAS_DGUS_LCD
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
#endif
//
// Emergency Parser
//
#if ENABLED(EMERGENCY_PARSER)
extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart);
#endif
//
// Misc. Defines
//
#define square(x) ((x) * (x))
#ifndef strncpy_P
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
#endif
//
// Misc. Functions
//
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#endif
#define CRITICAL_SECTION_START \
uint32_t primask = __get_PRIMASK(); \
(void)__iCliRetVal()
#define CRITICAL_SECTION_END \
if (!primask) \
(void)__iSeiRetVal()
// Disable interrupts
#define cli() noInterrupts()
// Enable interrupts
#define sei() interrupts()
// bss_end alias
#define __bss_end __bss_end__
// Fix bug in pgm_read_ptr
#undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr))
//
// ADC
//
#define HAL_ADC_VREF_MV 3300
#define HAL_ADC_RESOLUTION 10
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
//
// MarlinHAL implementation
//
#include "MarlinHAL.h"

View file

@ -0,0 +1,278 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HAL for HC32F460, based heavily on the legacy implementation and STM32F1
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#include "HAL.h" // Includes MarlinHAL.h
#include <IWatchdog.h>
#include <AsyncAnalogRead.h>
#if TEMP_SENSOR_SOC
#include <OnChipTemperature.h>
#endif
extern "C" char *_sbrk(int incr);
#if ENABLED(POSTMORTEM_DEBUGGING)
// From MinSerial.cpp
extern void install_min_serial();
#endif
#if ENABLED(MARLIN_DEV_MODE)
inline void HAL_clock_frequencies_dump() {
// 1. dump all clock frequencies
update_system_clock_frequencies();
SERIAL_ECHOPGM(
"-- clocks dump -- \nSYS=", SYSTEM_CLOCK_FREQUENCIES.system,
"\nHCLK=", SYSTEM_CLOCK_FREQUENCIES.hclk,
"\nPCLK0=", SYSTEM_CLOCK_FREQUENCIES.pclk0,
"\nPCLK1=", SYSTEM_CLOCK_FREQUENCIES.pclk1,
"\nPCLK2=", SYSTEM_CLOCK_FREQUENCIES.pclk2,
"\nPCLK3=", SYSTEM_CLOCK_FREQUENCIES.pclk3,
"\nPCLK4=", SYSTEM_CLOCK_FREQUENCIES.pclk4,
"\nEXCLK=", SYSTEM_CLOCK_FREQUENCIES.exclk,
"\nF_CPU=", 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 multipliers and dividers
SERIAL_ECHOPGM(
"\nP=", M4_SYSREG->CMU_PLLCFGR_f.MPLLP + 1UL,
"\nQ=", M4_SYSREG->CMU_PLLCFGR_f.MPLLQ + 1UL,
"\nR=", M4_SYSREG->CMU_PLLCFGR_f.MPLLR + 1UL,
"\nN=", M4_SYSREG->CMU_PLLCFGR_f.MPLLN + 1UL,
"\nM=", M4_SYSREG->CMU_PLLCFGR_f.MPLLM + 1UL
);
break;
default: break;
}
// Done
SERIAL_ECHOPGM("\n--\n");
}
#endif // MARLIN_DEV_MODE
//
// MarlinHAL class implementation
//
pin_t MarlinHAL::last_adc_pin;
#if TEMP_SENSOR_SOC
float MarlinHAL::soc_temp = 0;
#endif
MarlinHAL::MarlinHAL() {}
void MarlinHAL::watchdog_init() {
TERN_(USE_WATCHDOG, WDT.begin(5000)); // Reset on 5 second timeout
}
void MarlinHAL::watchdog_refresh() {
TERN_(USE_WATCHDOG, WDT.reload());
}
void MarlinHAL::init() {
NVIC_SetPriorityGrouping(0x3);
// Print clock frequencies to host serial
TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump());
// Register min serial
TERN_(POSTMORTEM_DEBUGGING, install_min_serial());
}
void MarlinHAL::init_board() {}
void MarlinHAL::reboot() {
NVIC_SystemReset();
}
bool MarlinHAL::isr_state() {
return !__get_PRIMASK();
}
void MarlinHAL::isr_on() {
__enable_irq();
}
void MarlinHAL::isr_off() {
__disable_irq();
}
void MarlinHAL::delay_ms(const int ms) {
delay(ms);
}
void MarlinHAL::idletask() {}
uint8_t MarlinHAL::get_reset_source() {
// Query reset cause from RMU
stc_rmu_rstcause_t rstCause;
RMU_GetResetCause(&rstCause);
// Map reset cause code to those expected by Marlin
// - Reset causes are flags, so multiple can be set
TERN_(MARLIN_DEV_MODE, printf("-- Reset Cause -- \n"));
uint8_t cause = 0;
#define MAP_CAUSE(from, to) \
if (rstCause.from == Set) { \
TERN_(MARLIN_DEV_MODE, printf(" - " STRINGIFY(from) "\n")); \
cause |= to; \
}
// Power on
MAP_CAUSE(enPowerOn, RST_POWER_ON) // Power on reset
// 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) // Brown out reset
// Wdt
MAP_CAUSE(enWdt, RST_WATCHDOG) // Watchdog reset
MAP_CAUSE(enSwdt, RST_WATCHDOG) // Special WDT reset
// Software
MAP_CAUSE(enPowerDown, RST_SOFTWARE) // MCU power down (?)
MAP_CAUSE(enSoftware, RST_SOFTWARE) // Software reset (e.g. NVIC_SystemReset())
// 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
#undef MAP_CAUSE
return cause;
}
void MarlinHAL::clear_reset_source() {
RMU_ClrResetFlag();
}
int MarlinHAL::freeMemory() {
volatile char top;
return &top - _sbrk(0);
}
void MarlinHAL::adc_init() {}
void MarlinHAL::adc_enable(const pin_t pin) {
#if TEMP_SENSOR_SOC
if (pin == TEMP_SOC_PIN) {
// Start OTS, min. 1s between reads
ChipTemperature.begin();
ChipTemperature.setMinimumReadDeltaMillis(1000);
return;
}
#endif
// Just set pin mode to analog
pinMode(pin, INPUT_ANALOG);
}
void MarlinHAL::adc_start(const pin_t pin) {
MarlinHAL::last_adc_pin = pin;
#if TEMP_SENSOR_SOC
if (pin == TEMP_SOC_PIN) {
// Read OTS
float temp;
if (ChipTemperature.read(temp))
MarlinHAL::soc_temp = temp;
return;
}
#endif
CORE_ASSERT(IS_GPIO_PIN(pin), "adc_start: invalid pin")
analogReadAsync(pin);
}
bool MarlinHAL::adc_ready() {
#if TEMP_SENSOR_SOC
if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN) return true;
#endif
CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_ready: invalid pin")
return getAnalogReadComplete(MarlinHAL::last_adc_pin);
}
uint16_t MarlinHAL::adc_value() {
#if TEMP_SENSOR_SOC
if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN)
return OTS_FLOAT_TO_ADC_READING(MarlinHAL::soc_temp);
#endif
// 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 value, const uint16_t scale, const bool invert) {
// Invert value if requested
const 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 set_pwm_frequency is not implemented yet
panic("set_pwm_frequency is not implemented yet\n");
}
void flashFirmware(const int16_t) { MarlinHAL::reboot(); }
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,133 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <core_types.h>
#include <stdint.h>
typedef gpio_pin_t pin_t;
#if TEMP_SENSOR_SOC
/**
* Convert ots measurement float to uint16_t for adc_value()
*
* @note returns float as integer in degrees C * 10, if T > 0
*/
#define OTS_FLOAT_TO_ADC_READING(T) ((T) > 0 ? ((uint16_t)((T) * 10.0f)) : 0)
/**
* Convert adc_value() uint16_t to ots measurement float
*
* @note see OTS_FLOAT_TO_ADC_READING for inverse
*
* @note RAW is oversampled by OVERSAMPLENR, so we need to divide first
*/
#define TEMP_SOC_SENSOR(RAW) ((float)(((RAW) / OVERSAMPLENR) / 10))
#endif
/**
* HAL class for Marlin on HC32F460
*/
class MarlinHAL {
public:
// Earliest possible init, before setup()
MarlinHAL();
// Watchdog
static void watchdog_init();
static void watchdog_refresh();
static void init(); // Called early in setup()
static void init_board(); // Called less early in setup()
static void reboot(); // Restart the firmware from 0x0
// Interrupts
static bool isr_state();
static void isr_on();
static void isr_off();
static void delay_ms(const int ms);
// Tasks, called from idle()
static void idletask();
// Reset
static uint8_t get_reset_source();
static void clear_reset_source();
// Free SRAM
static int freeMemory();
//
// ADC Methods
//
// Called by Temperature::init once at startup
static void adc_init();
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t pin);
// Begin ADC sampling on the given pin. Called from Temperature::isr!
static void adc_start(const pin_t pin);
// Is the ADC ready for reading?
static bool adc_ready();
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* Optionally invert the duty cycle [default = false]
* 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 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;
#if TEMP_SENSOR_SOC
/**
* On-chip temperature sensor value
*/
static float soc_temp;
#endif
};
// M997: Trigger a firmware update from SD card (after upload).
// On HC32F460, a reboot is enough to do this.
#ifndef PLATFORM_M997_SUPPORT
#define PLATFORM_M997_SUPPORT
#endif
void flashFirmware(const int16_t);

View file

@ -0,0 +1,142 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#include "MarlinSerial.h"
#include <drivers/usart/Usart.h>
/**
* Not every MarlinSerial instance should handle emergency parsing, as
* it would not make sense to parse GCode from TMC responses
*/
constexpr bool serial_handles_emergency(int port) {
return false
#ifdef SERIAL_PORT
|| (SERIAL_PORT) == port
#endif
#ifdef SERIAL_PORT_2
|| (SERIAL_PORT_2) == port
#endif
#ifdef LCD_SERIAL_PORT
|| (LCD_SERIAL_PORT) == port
#endif
;
}
//
// Define serial ports
//
#define DEFINE_HWSERIAL_MARLIN(name, n) \
MSerialT name(serial_handles_emergency(n), \
&USART##n##_config, \
BOARD_USART##n##_TX_PIN, \
BOARD_USART##n##_RX_PIN);
DEFINE_HWSERIAL_MARLIN(MSerial1, 1);
DEFINE_HWSERIAL_MARLIN(MSerial2, 2);
//
// Serial port assertions
//
// Check the type of each serial port by passing it to a template function.
// HardwareSerial is known to sometimes hang the controller when an error occurs,
// so this case will fail the static assert. All other classes are assumed to be ok.
template <typename T>
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");
#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1");
// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages.
#ifdef MYSERIAL1
CHECK_CFG_SERIAL(MYSERIAL1);
#endif
#ifdef MYSERIAL2
CHECK_CFG_SERIAL(MYSERIAL2);
#endif
#ifdef LCD_SERIAL
CHECK_CFG_SERIAL(LCD_SERIAL);
#endif
#if AXIS_HAS_HW_SERIAL(X)
CHECK_AXIS_SERIAL(X);
#endif
#if AXIS_HAS_HW_SERIAL(X2)
CHECK_AXIS_SERIAL(X2);
#endif
#if AXIS_HAS_HW_SERIAL(Y)
CHECK_AXIS_SERIAL(Y);
#endif
#if AXIS_HAS_HW_SERIAL(Y2)
CHECK_AXIS_SERIAL(Y2);
#endif
#if AXIS_HAS_HW_SERIAL(Z)
CHECK_AXIS_SERIAL(Z);
#endif
#if AXIS_HAS_HW_SERIAL(Z2)
CHECK_AXIS_SERIAL(Z2);
#endif
#if AXIS_HAS_HW_SERIAL(Z3)
CHECK_AXIS_SERIAL(Z3);
#endif
#if AXIS_HAS_HW_SERIAL(Z4)
CHECK_AXIS_SERIAL(Z4);
#endif
#if AXIS_HAS_HW_SERIAL(I)
CHECK_AXIS_SERIAL(I);
#endif
#if AXIS_HAS_HW_SERIAL(J)
CHECK_AXIS_SERIAL(J);
#endif
#if AXIS_HAS_HW_SERIAL(K)
CHECK_AXIS_SERIAL(K);
#endif
#if AXIS_HAS_HW_SERIAL(E0)
CHECK_AXIS_SERIAL(E0);
#endif
#if AXIS_HAS_HW_SERIAL(E1)
CHECK_AXIS_SERIAL(E1);
#endif
#if AXIS_HAS_HW_SERIAL(E2)
CHECK_AXIS_SERIAL(E2);
#endif
#if AXIS_HAS_HW_SERIAL(E3)
CHECK_AXIS_SERIAL(E3);
#endif
#if AXIS_HAS_HW_SERIAL(E4)
CHECK_AXIS_SERIAL(E4);
#endif
#if AXIS_HAS_HW_SERIAL(E5)
CHECK_AXIS_SERIAL(E5);
#endif
#if AXIS_HAS_HW_SERIAL(E6)
CHECK_AXIS_SERIAL(E6);
#endif
#if AXIS_HAS_HW_SERIAL(E7)
CHECK_AXIS_SERIAL(E7);
#endif
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../core/serial_hook.h"
#include <drivers/usart/Usart.h>
// Optionally set uart IRQ priority to reduce overflow errors
// #define UART_IRQ_PRIO 1
struct MarlinSerial : public Usart {
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()->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_t baud) {
Usart::begin(baud);
setPriority();
}
void begin(uint32_t baud, uint8_t config) {
Usart::begin(baud, config);
setPriority();
}
#endif
};
typedef Serial1Class<MarlinSerial> MSerialT;
extern MSerialT MSerial1;
extern MSerialT MSerial2;

View file

@ -0,0 +1,151 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#include <drivers/panic/panic.h>
#if ANY(POSTMORTEM_DEBUGGING, PANIC_ENABLE)
#include <drivers/usart/usart_sync.h>
//
// Shared by both panic and PostMortem debugging
//
static void minserial_begin() {
#if !WITHIN(SERIAL_PORT, 1, 3)
#warning "MinSerial requires a physical UART port for output."
#warning "Disabling MinSerial because the used serial port is not a HW port."
#else
// Prepare usart_sync configuration
const stc_usart_uart_init_t usart_config = {
.enClkMode = UsartIntClkCkNoOutput,
.enClkDiv = UsartClkDiv_1,
.enDataLength = UsartDataBits8,
.enDirection = UsartDataLsbFirst,
.enStopBit = UsartOneStopBit,
.enParity = UsartParityNone,
.enSampleMode = UsartSampleBit8,
.enDetectMode = UsartStartBitFallEdge,
.enHwFlow = UsartRtsEnable,
};
// Initializes usart_sync driver
#define __USART_SYNC_INIT(port_no, baud, config) \
usart_sync_init(M4_USART##port_no, \
BOARD_USART##port_no##_TX_PIN, \
baud, \
config);
#define USART_SYNC_INIT(port_no, baud, config) __USART_SYNC_INIT(port_no, baud, config)
// This will reset the baudrate to what is defined in Configuration.h,
// ignoring any changes made with e.g. M575.
// keeping the dynamic baudrate would require re-calculating the baudrate
// using the register values, which is a pain...
// TODO: retain dynamic baudrate in MinSerial init
// -> see USART_SetBaudrate(), needs to be inverted
USART_SYNC_INIT(SERIAL_PORT, BAUDRATE, &usart_config);
#undef USART_SYNC_INIT
#undef __USART_SYNC_INIT
#endif
}
static void minserial_putc(char c) {
#if WITHIN(SERIAL_PORT, 1, 3)
#define __USART_SYNC_PUTC(port_no, ch) usart_sync_putc(M4_USART##port_no, ch);
#define USART_SYNC_PUTC(port_no, ch) __USART_SYNC_PUTC(port_no, ch)
USART_SYNC_PUTC(SERIAL_PORT, c);
#undef USART_SYNC_PUTC
#undef __USART_SYNC_PUTC
#endif
}
//
// Panic only
//
#ifdef PANIC_ENABLE
void panic_begin() {
minserial_begin();
panic_puts("\n\nPANIC:\n");
}
void panic_puts(const char *str) {
while (*str) minserial_putc(*str++);
}
#endif // PANIC_ENABLE
//
// PostMortem debugging only
//
#if ENABLED(POSTMORTEM_DEBUGGING)
#include "../shared/MinSerial.h"
#include <drivers/panic/fault_handlers.h>
void fault_handlers_init() {
// Enable cpu traps:
// - Divide by zero
// - Unaligned access
SCB->CCR |= SCB_CCR_DIV_0_TRP_Msk; //| SCB_CCR_UNALIGN_TRP_Msk;
}
void install_min_serial() {
HAL_min_serial_init = &minserial_begin;
HAL_min_serial_out = &minserial_putc;
}
extern "C" {
__attribute__((naked)) void JumpHandler_ASM() {
__asm__ __volatile__(
"b CommonHandler_ASM\n");
}
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
}
#endif // POSTMORTEM_DEBUGGING
#endif // POSTMORTEM_DEBUGGING || PANIC_ENABLE
//
// Panic_end is always required to print the '!!' to the host
//
void panic_end() {
// Print '!!' to signal error to host
// Do it 10x so it's not missed
for (uint_fast8_t i = 10; i--;) panic_printf("\n!!\n");
// Then, reset the board
NVIC_SystemReset();
}
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,110 @@
# HC32F460 HAL
This document provides notes on the HAL for the HC32F460 MCU.
## Adding support for a new board
The HC32F460 HAL is designed to be generic enough for any HC32F460-based board. Adding support for a new HC32F460-based board will require the following steps:
1. Follow [the usual instructions](https://marlinfw.org/docs/development/boards.html#adding-a-new-board) to add a new board to Marlin. (i.e., Add a pins file, edit `boards.h` and `pins.h`, etc.)
2. Determine the flash size your board uses:
- Examine the board's main processor. (Refer the naming key in `hc32.ini`.)
- Extend the `HC32F460C_common` base env for 256K, or `HC32F460E_common` for 512K.
3. Determine your board's application start address (see [below](#finding-the-application-start-address))
4. Set `board_build.ld_args.flash_start` to the app start address once you've found it. If your board doesn't use a bootloader, you may be able to use the "ICSP" header or DFU. This document will be updated once we have more information about flashing without a bootloader.
### Finding the application start address
If the board contains a bootloader you'll need to find the application address. This is the address the bootloader jumps to after it's done. You can find this address in a few different ways:
#### 1. Using log messages
If you're lucky, the bootloader may print the app start address on the serial output during boot. To check for this, use your favorite serial monitor to observe the serial output when you power on the board. Look for a message like "Jumping to 0xC000" or "GotoApp->addr=0xC000". This line would be printed before Marlin's "start" message.
Example:
```
[...]
version 1.2
sdio init success!
Disk init
Tips ------ None Firmware file
GotoApp->addr=0xC000
start
[...]
```
#### 2. Using published source code
If the vendor has published Marlin source code that includes the bootloader, you can search the bootloader source code for the address. Begin your search with the following steps:
1. Find the code that sets the vector table offset
The vector table offset is usually set using a line like this:
```c
SCB->VTOR = ((uint32_t) APP_START_ADDRESS & SCB_VTOR_TBLOFF_Msk);
```
Just searching for `SCB->VTOR` should yield some results. From there, you just need to look at the value that's assigned to it. The example uses `APP_START_ADDRESS`.
> [!NOTE]
> Some vendors publish incomplete source code. But they sometimes leave version control related files in the repo, which can contain previous version of files that were removed. Find these by including folders like `.git` or `.svn` in your search.
> [!NOTE]
> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo.
2. Using a linker script
If the repository contains a linker script, look at the memory regions, specifically a region named `FLASH` or similar. The `ORIGIN` of that region will be the application start address.
**Example:**
```ld
MEMORY
{
FLASH (rx): ORIGIN = 0x0000C000, LENGTH = 512K
OTP (rx): ORIGIN = 0x03000C00, LENGTH = 1020
RAM (rwx): ORIGIN = 0x1FFF8000, LENGTH = 188K
RET_RAM (rwx): ORIGIN = 0x200F0000, LENGTH = 4K
}
```
> [!NOTE]
> This example is based on [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/main/hdsc32core/hc32f46x_flash.ld#L55)
## Documentation on the HC32F460
Due to uncertain licensing (w/r/t STMicro), documentation for the HC32F460 is only available upon request. Documentation includes the following:
- Datasheet, user manual, reference manual
- Application notes for the DDL
- DDL source code
- IDE support packages (Keil, IAR, ...) including .svd files
- Programming software
- Emulator / debugger drivers
- Development board documentation and schematics
- Errata documents
- (Limited) sales information
- Full Voxelab firmware source code
- Documents in Chinese or English (machine translated)
Contact me on Discord (@shadow578) if you need it.
## Dependencies
This HAL depends on the following projects:
- [shadow578/platform-hc32f46x](https://github.com/shadow578/platform-hc32f46x) (PlatformIO platform for HC32F46x)
- [shadow578/framework-arduino-hc32f46x](https://github.com/shadow578/framework-arduino-hc32f46x) (Arduino framework for HC32F46x)
- [shadow578/framework-hc32f46x-ddl](https://github.com/shadow578/framework-hc32f46x-ddl) (HC32F46x DDL framework)
## Credits
This HAL wouldn't be possible without the following projects:
- [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2) (original implementation)
- [alexqzd/Marlin-H32](https://github.com/alexqzd/Marlin-H32) (misc. fixes to the original implementation)
- [kgoveas/Arduino-Core-Template](https://github.com/kgoveas/Arduino-Core-Template) (template for Arduino headers)
- [stm32duino/Arduino_Core_STM32](https://github.com/stm32duino/Arduino_Core_STM32) (misc. Arduino functions)

View file

@ -0,0 +1,84 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#if HAS_SERVOS
#include "Servo.h"
static uint8_t servoCount = 0;
static MarlinServo *servos[NUM_SERVOS] = {0};
constexpr uint32_t servoDelays[] = SERVO_DELAY;
static_assert(COUNT(servoDelays) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
//
// MarlinServo impl
//
MarlinServo::MarlinServo() {
this->channel = servoCount++;
servos[this->channel] = this;
}
int8_t MarlinServo::attach(const pin_t apin) {
// 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
const uint8_t rc = this->servo.attach(this->pin);
return rc == INVALID_SERVO ? -1 : rc;
}
void MarlinServo::detach() {
this->servo.detach();
}
bool MarlinServo::attached() {
return this->servo.attached();
}
void MarlinServo::write(servo_angle_t angle) {
this->angle = angle;
this->servo.write(angle);
}
void MarlinServo::move(servo_angle_t angle) {
// Attach with pin=-1 to use last pin attach() was called with
if (attach(-1) < 0) return; // Attach failed
write(angle);
safe_delay(servoDelays[this->channel]);
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
servo_angle_t MarlinServo::read() {
return TERN(OPTIMISTIC_SERVO_READ, this->angle, this->servo.read());
}
#endif // HAS_SERVOS
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,97 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../inc/MarlinConfigPre.h"
#include <Servo.h>
/**
* return last written value in servo.read instead of calculated value
*/
#define OPTIMISTIC_SERVO_READ
/**
* @brief servo lib wrapper for marlin
*/
class MarlinServo {
public:
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:
/**
* @brief internal servo object, provided by arduino core
*/
Servo servo;
/**
* @brief virtual servo channel
*/
uint8_t channel;
/**
* @brief pin the servo attached to last
*/
pin_t pin;
/**
* @brief last known servo angle
*/
servo_angle_t angle;
};
// Alias for marlin HAL
typedef MarlinServo hal_servo_t;

View file

@ -0,0 +1,92 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
#include "../shared/eeprom_api.h"
#include "../shared/eeprom_if.h"
#ifndef MARLIN_EEPROM_SIZE
#error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_start() {
eeprom_init();
return true;
}
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t v = *value;
uint8_t *const p = (uint8_t *const)pos;
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
delay(2);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size,
uint16_t *crc, const bool writing /*=true*/) {
do {
uint8_t *const p = (uint8_t *const)pos;
uint8_t c = eeprom_read_byte(p);
if (writing)
{
*value = c;
}
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // IIC_BL24CXX_EEPROM
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,51 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* Platform-independent Arduino functions for I2C EEPROM.
* Enable USE_SHARED_EEPROM if not supplied by the framework.
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
#include "../../libs/BL24CXX.h"
#include "../shared/eeprom_if.h"
void eeprom_init() {
BL24CXX::init();
}
void eeprom_write_byte(uint8_t *pos, unsigned char value) {
const unsigned eeprom_address = (unsigned)pos;
return BL24CXX::writeOneByte(eeprom_address, value);
}
uint8_t eeprom_read_byte(uint8_t *pos) {
const unsigned eeprom_address = (unsigned)pos;
return BL24CXX::readOneByte(eeprom_address);
}
#endif // IIC_BL24CXX_EEPROM
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,98 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* Implementation of EEPROM settings in SD Card
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDCARD_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
#include "../../sd/cardreader.h"
#define EEPROM_FILENAME "eeprom.dat"
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
size_t PersistentStore::capacity() {
return MARLIN_EEPROM_SIZE;
}
#define _ALIGN(x) __attribute__((aligned(x)))
static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE];
bool PersistentStore::access_start() {
if (!card.isMounted()) return false;
MediaFile file, root = card.getroot();
if (!file.open(&root, EEPROM_FILENAME, O_RDONLY))
return true; // False aborts the save
int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
if (bytes_read < 0) return false;
for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++)
HAL_eeprom_data[bytes_read] = 0xFF;
file.close();
return true;
}
bool PersistentStore::access_finish() {
if (!card.isMounted()) return false;
MediaFile file, root = card.getroot();
int bytes_written = 0;
if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) {
bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE);
file.close();
}
return (bytes_written == MARLIN_EEPROM_SIZE);
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
for (size_t i = 0; i < size; i++) HAL_eeprom_data[pos + i] = value[i];
crc16(crc, value, size);
pos += size;
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing /*=true*/) {
for (size_t i = 0; i < size; i++) {
uint8_t c = HAL_eeprom_data[pos + i];
if (writing) value[i] = c;
crc16(crc, &c, 1);
}
pos += size;
return false;
}
#endif // SDCARD_EEPROM_EMULATION
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,94 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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 <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "../../inc/MarlinConfig.h"
#if USE_WIRED_EEPROM
#warning "SPI / I2C EEPROM has not been tested on HC32F460."
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"
#ifndef MARLIN_EEPROM_SIZE
#error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::access_start() {
eeprom_init();
#if ENABLED(SPI_EEPROM)
#if SPI_CHAN_EEPROM1 == 1
SET_OUTPUT(BOARD_SPI1_SCK_PIN);
SET_OUTPUT(BOARD_SPI1_MOSI_PIN);
SET_INPUT(BOARD_SPI1_MISO_PIN);
SET_OUTPUT(SPI_EEPROM1_CS);
#endif
spiInit(0);
#endif
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t *const p = (uint8_t *const)pos;
uint8_t v = *value;
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing /*=true*/) {
do {
uint8_t c = eeprom_read_byte((uint8_t *)pos);
if (writing && value) {
*value = c;
}
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // USE_WIRED_EEPROM
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,98 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "endstop_interrupts.h"
#include "../../module/endstops.h"
#include <Arduino.h>
#define ENDSTOP_IRQ_PRIORITY DDL_IRQ_PRIORITY_06
//
// IRQ handler
//
void endstopIRQHandler() {
bool flag = false;
// Check all irq flags
#define CHECK(name) TERN_(USE_##name, flag |= checkIRQFlag(name##_PIN, /*clear*/ true))
CHECK(X_MAX);
CHECK(X_MIN);
CHECK(Y_MAX);
CHECK(Y_MIN);
CHECK(Z_MAX);
CHECK(Z_MIN);
CHECK(Z2_MAX);
CHECK(Z2_MIN);
CHECK(Z3_MAX);
CHECK(Z3_MIN);
CHECK(Z_MIN_PROBE);
// Update endstops
if (flag) endstops.update();
#undef CHECK
}
//
// HAL functions
//
void setup_endstop_interrupts() {
#define SETUP(name) TERN_(USE_##name, attachInterrupt(name##_PIN, endstopIRQHandler, CHANGE); setInterruptPriority(name##_PIN, ENDSTOP_IRQ_PRIORITY))
SETUP(X_MAX);
SETUP(X_MIN);
SETUP(Y_MAX);
SETUP(Y_MIN);
SETUP(Z_MAX);
SETUP(Z_MIN);
SETUP(Z2_MAX);
SETUP(Z2_MIN);
SETUP(Z3_MAX);
SETUP(Z3_MIN);
SETUP(Z_MIN_PROBE);
#undef SETUP
}
// Ensure 1 - 10 IRQs are registered
// Disable some endstops if you encounter this error
#define ENDSTOPS_INTERRUPTS_COUNT COUNT_ENABLED(USE_X_MAX, USE_X_MIN, USE_Y_MAX, USE_Y_MIN, USE_Z_MAX, USE_Z_MIN, USE_Z2_MAX, USE_Z2_MIN, USE_Z3_MAX, USE_Z3_MIN, USE_Z_MIN_PROBE)
#if ENDSTOPS_INTERRUPTS_COUNT > 10
#error "Too many endstop interrupts! HC32F460 only supports 10 endstop interrupts."
#elif ENDSTOPS_INTERRUPTS_COUNT == 0
#error "No endstop interrupts are enabled! Comment out this line to continue."
#endif
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,48 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Endstop interrupts for HC32F460 based targets.
*
* On HC32F460, 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).
*/
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the temperature-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
* This feature only works when all used endstop pins can generate an 'external interrupt'.
*
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
void setup_endstop_interrupts();

View file

@ -0,0 +1,69 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for HC32F460
* These use GPIO functions instead of Direct Port Manipulation.
*/
#include <wiring_digital.h>
#include <wiring_analog.h>
#include <drivers/gpio/gpio.h>
#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) getPinMode(IO)
#define _SET_MODE(IO, M) pinMode(IO, M)
#define _SET_OUTPUT(IO) _SET_MODE(IO, OUTPUT)
#define OUT_WRITE(IO, V) \
do { \
_SET_OUTPUT(IO); \
WRITE(IO, V); \
} while (0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT_FLOATING)
#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_PWM || \
_GET_MODE(IO) == OUTPUT_OPEN_DRAIN)
#define PWM_PIN(IO) isAnalogWritePin(IO)
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO, V) digitalWrite(IO, V)
#define NO_COMPILE_TIME_PWM // Can't check for PWM at compile time

View file

@ -0,0 +1,22 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#ifndef TEMP_SOC_PIN
#define TEMP_SOC_PIN 0xFF // Dummy that is not a valid GPIO, HAL checks for this
#endif

View file

@ -0,0 +1,34 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation
#if USE_FALLBACK_EEPROM
#define SDCARD_EEPROM_EMULATION
#elif ANY(I2C_EEPROM, SPI_EEPROM)
#define USE_SHARED_EEPROM 1
#endif
// Allow SD support to be disabled
#if !HAS_MEDIA
#undef ONBOARD_SDIO
#endif

View file

@ -0,0 +1,78 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#ifndef BOARD_XTAL_FREQUENCY
#error "BOARD_XTAL_FREQUENCY is required for HC32F460."
#endif
#if ENABLED(FAST_PWM_FAN)
#error "FAST_PWM_FAN is not yet implemented for this platform."
#endif
#if !defined(HAVE_SW_SERIAL) && HAS_TMC_SW_SERIAL
#error "Missing SoftwareSerial implementation."
#endif
#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA
#undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
#if USE_FALLBACK_EEPROM
#warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
#endif
#error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
#error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
#error "SERIAL_STATS_DROPPED_RX is not supported on this platform."
#endif
#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3)
#error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HC32F460. Comment out this line to proceed at your own risk!"
#endif
// Emergency Parser needs at least one serial with HardwareSerial.
#if ENABLED(EMERGENCY_PARSER) && ((SERIAL_PORT == -1 && !defined(SERIAL_PORT_2)) || (SERIAL_PORT_2 == -1 && !defined(SERIAL_PORT)))
#error "EMERGENCY_PARSER is only supported by HardwareSerial on HC32F460."
#endif
#if TEMP_SENSOR_SOC
#if !defined(TEMP_SOC_PIN)
#error "TEMP_SOC_PIN must be defined to use TEMP_SENSOR_SOC."
#endif
#if defined(TEMP_SOC_PIN) && IS_GPIO_PIN(TEMP_SOC_PIN)
#error "TEMP_SOC_PIN must not be a valid GPIO pin to avoid conflicts."
#endif
#endif
#if ENABLED(POSTMORTEM_DEBUGGING) && !defined(CORE_DISABLE_FAULT_HANDLER)
#error "POSTMORTEM_DEBUGGING requires CORE_DISABLE_FAULT_HANDLER to be set."
#endif
#if defined(PANIC_ENABLE)
#if defined(PANIC_USART1_TX_PIN) || defined(PANIC_USART2_TX_PIN) || defined(PANIC_USART3_TX_PIN) || defined(PANIC_USART3_TX_PIN)
#error "HC32 HAL uses a custom panic handler. Do not define PANIC_USARTx_TX_PIN."
#endif
#endif

View file

@ -0,0 +1,174 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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 <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../inc/MarlinConfig.h"
#include "fastio.h"
#include <drivers/timera/timera_pwm.h>
//
// Translation of routines & variables used by pinsDebug.h
//
#ifndef BOARD_NR_GPIO_PINS
#error "Expected BOARD_NR_GPIO_PINS not found."
#endif
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) IS_GPIO_PIN(pin)
// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included
// after it, it is available in this file as well.
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) \
do { \
sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); \
SERIAL_ECHO(buffer); \
} while (0)
#define PRINT_PIN_ANALOG(p) \
do { \
sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); \
SERIAL_ECHO(buffer); \
} while (0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) \
do { \
sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); \
SERIAL_ECHO(buffer); \
} while (0)
#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin
//
// Pins that will cause a hang / reset / disconnect in M43 Toggle and Watch utils
//
#ifndef M43_NEVER_TOUCH
// Don't 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 == PC14 || Q == PC15)
#define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q))
#endif
static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel);
return pin_t(adc_channel);
}
static bool IS_ANALOG(pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID)
return _GET_MODE(pin) == INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
return false;
}
static bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
}
static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin));
}
/**
* @brief print pin PWM status
* @return true if pin is currently a PWM pin, false otherwise
*/
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 == nullptr) {
// 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
// - PinMode is OUTPUT_PWM
return timera_is_unit_initialized(unit) && timera_is_channel_active(unit, channel) && getPinMode(pin) == OUTPUT_PWM;
}
void pwm_details(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 == nullptr)
return; // No pwm pin or no unit assigned
// Print timer assignment of pin, eg. "TimerA1Ch2 Func4"
SERIAL_ECHOPGM("TimerA", TIMERA_REG_TO_X(unit->peripheral.register_base),
"Ch", TIMERA_CHANNEL_TO_X(channel),
" Func", 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/", clock_divider, " PERAR=", 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=", compare);
}
else {
// Channel inactive
SERIAL_ECHOPGM("N/A");
}
}
void print_port(pin_t pin) {
const char port = 'A' + char(pin >> 4); // Pin div 16
const int16_t gbit = PIN_MAP[pin].bit_pos;
char buffer[8];
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
if (gbit < 10) {
SERIAL_CHAR(' ');
}
SERIAL_ECHO(buffer);
}

View file

@ -0,0 +1,55 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#ifdef REDIRECT_PRINTF_TO_SERIAL
#if !defined(__GNUC__)
#error "only GCC is supported"
#endif
#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
*/
extern "C" int _write(int file, char *ptr, int len) {
//SERIAL_ECHO_START(); // echo:
for (int i = 0; i < len; i++) SERIAL_CHAR(ptr[i]);
return len;
}
/**
* @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) {
return 1;
}
#endif // REDIRECT_PRINTF_TO_SERIAL
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,137 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "sdio.h"
#include <gpio/gpio.h>
#include <sd_card.h>
//
// SDIO configuration
//
#define SDIO_PERIPHERAL M4_SDIOC1
// Use DMA2 channel 0
#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_WRITE_TIMEOUT 100 // ms
//
// HAL functions
//
#define WITH_RETRY(retries, fn) \
for (int retry = 0; retry < (retries); retry++) { \
MarlinHAL::watchdog_refresh(); \
yield(); \
fn \
}
stc_sd_handle_t *handle;
bool SDIO_Init() {
// Configure SDIO pins
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(handle, &cardConf);
if (rc != Ok) printf("SDIO_Init() error (rc=%u)\n", rc);
return rc == Ok;
}
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(handle, block, 1, dst, SDIO_READ_TIMEOUT);
if (rc == Ok) return true;
printf("SDIO_ReadBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode);
})
return false;
}
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(handle, block, 1, (uint8_t *)src, SDIO_WRITE_TIMEOUT);
if (rc == Ok) return true;
printf("SDIO_WriteBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode);
})
return false;
}
bool SDIO_IsReady() {
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
const 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
return _MAX(cardSizeBytes, UINT32_MAX);
}
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,28 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* 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 <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../inc/MarlinConfig.h"
bool SDIO_Init();
bool SDIO_ReadBlock(uint32_t block, uint8_t *dst);
bool SDIO_WriteBlock(uint32_t block, const uint8_t *src);
bool SDIO_IsReady();
uint32_t SDIO_GetCardSize();

View file

@ -0,0 +1,19 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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 <https://www.gnu.org/licenses/>.
*
*/
#pragma once

View file

@ -0,0 +1,124 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* HC32f460 system clock configuration
*/
#ifdef ARDUINO_ARCH_HC32
// Get BOARD_XTAL_FREQUENCY from configuration / pins
#include "../../inc/MarlinConfig.h"
#include <core_hooks.h>
#include <drivers/sysclock/sysclock_util.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 "HC32F460 with 16 MHz XTAL has not been tested."
#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 gracefully if HRC is not 16 MHz
if (1UL != (HRC_FREQ_MON() & 1UL)) {
panic("HRC is not 16 MHz");
}
#ifdef BOARD_XTAL_FREQUENCY
#warning "No valid XTAL frequency defined, falling back to HRC."
#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);
#undef POWER_MODE_SYSTEM_CLOCK
}
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,54 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_HC32
#include "timers.h"
#include <core_debug.h>
/**
* Timer0 Unit 2 Channel A is used for Temperature interrupts
*/
Timer0 temp_timer(&TIMER02A_config, &Temp_Handler);
/**
* 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) {
if (timer_num == TEMP_TIMER_NUM) {
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);
}
else if (timer_num == STEP_TIMER_NUM) {
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);
}
else {
CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_num")
}
}
#endif // ARDUINO_ARCH_HC32

View file

@ -0,0 +1,135 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* 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 <https://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
#include <Timer0.h>
//
// Timer Types
//
typedef Timer0 *timer_channel_t;
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
//
// Timer instances
//
extern Timer0 temp_timer;
extern Timer0 step_timer;
//
// Timer Configurations
//
// TODO: some calculations (step irq min_step_rate) require the timer rate to be known at compile time
// this is not possible with the HC32F460, 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
// TODO: CYCLES_PER_MICROSECOND seems to be used by Marlin to calculate the number of cycles per microsecond in the timer ISRs
// by default, it uses F_CPU, but since that is not known at compile time for HC32, we overwrite it here
#undef CYCLES_PER_MICROSECOND
#define CYCLES_PER_MICROSECOND (HAL_TIMER_RATE / 1000000UL)
// 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: STEPPER_TIMER_RATE seems to work fine like this, but requires further testing...
#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);
// 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) {}
//
// HAL function aliases
//
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM);
//
// HAL ISR callbacks
//
void Step_Handler();
void Temp_Handler();
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() void Step_Handler()
#endif
#ifndef HAL_TEMP_TIMER_ISR
#define HAL_TEMP_TIMER_ISR() void Temp_Handler()
#endif

View file

@ -35,6 +35,8 @@
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY40_41/NAME) #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY40_41/NAME)
#elif defined(TARGET_LPC1768) #elif defined(TARGET_LPC1768)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME) #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME)
#elif defined(ARDUINO_ARCH_HC32)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/HC32/NAME)
#elif defined(__STM32F1__) || defined(TARGET_STM32F1) #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME) #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME)
#elif defined(ARDUINO_ARCH_STM32) #elif defined(ARDUINO_ARCH_STM32)

View file

@ -74,6 +74,8 @@
#include "../TEENSY40_41/Servo.h" #include "../TEENSY40_41/Servo.h"
#elif defined(TARGET_LPC1768) #elif defined(TARGET_LPC1768)
#include "../LPC1768/Servo.h" #include "../LPC1768/Servo.h"
#elif defined(ARDUINO_ARCH_HC32)
#include "../HC32/Servo.h"
#elif defined(__STM32F1__) || defined(TARGET_STM32F1) #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
#include "../STM32F1/Servo.h" #include "../STM32F1/Servo.h"
#elif defined(ARDUINO_ARCH_STM32) #elif defined(ARDUINO_ARCH_STM32)

View file

@ -510,6 +510,11 @@
#define BOARD_MINITRONICS20 7103 // Minitronics v2.0 #define BOARD_MINITRONICS20 7103 // Minitronics v2.0
//
// HC32 ARM Cortex-M4
//
#define BOARD_AQUILA_V101 7200 // Aquila V1.0.1 as found in the Voxelab Aquila X2
// //
// Custom board // Custom board
// //

View file

@ -1256,7 +1256,7 @@
* currently HAL.h must be included ahead of pins.h. * currently HAL.h must be included ahead of pins.h.
*/ */
#if LCD_IS_SERIAL_HOST && !defined(LCD_SERIAL_PORT) #if LCD_IS_SERIAL_HOST && !defined(LCD_SERIAL_PORT)
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1) #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, AQUILA_V101)
#define LCD_SERIAL_PORT 1 #define LCD_SERIAL_PORT 1
#elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO) #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO)
#define LCD_SERIAL_PORT 2 #define LCD_SERIAL_PORT 2

View file

@ -48,7 +48,7 @@
#ifdef __STM32F1__ #ifdef __STM32F1__
#define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0)
#define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) #define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0)
#elif defined(STM32F1) || defined(STM32F4) #elif defined(STM32F1) || defined(STM32F4) || defined(ARDUINO_ARCH_HC32)
#define SDA_IN() SET_INPUT(IIC_EEPROM_SDA) #define SDA_IN() SET_INPUT(IIC_EEPROM_SDA)
#define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA) #define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA)
#endif #endif

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#ifndef ARDUINO_ARCH_HC32
#error "Oops! Select an HC32F460 board in 'Tools > Board.'"
#endif

View file

@ -0,0 +1,212 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
//
// Voxelab Aquila V1.0.1 and V1.0.2 (HC32F460) as found in the Voxelab Aquila X2
//
#include "env_validate.h"
#if HAS_MULTI_HOTEND || E_STEPPERS > 1
#error "Aquila V1.0.1 only supports one hotend and E-stepper"
#endif
#ifndef BOARD_INFO_NAME
#define BOARD_INFO_NAME "Aquila V1.0.1"
#endif
#ifndef DEFAULT_MACHINE_NAME
#define DEFAULT_MACHINE_NAME "Aquila"
#endif
//
// Onboard crystal oscillator
//
#ifndef BOARD_XTAL_FREQUENCY
#define BOARD_XTAL_FREQUENCY 8000000 // 8 MHz XTAL
#endif
//
// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
//
//#define DISABLE_DEBUG
//#define DISABLE_JTAG
//
// EEPROM
//
#if NO_EEPROM_SELECTED
#define IIC_BL24CXX_EEPROM
//#define SDCARD_EEPROM_EMULATION
#undef NO_EEPROM_SELECTED
#endif
#if ENABLED(IIC_BL24CXX_EEPROM)
#define IIC_EEPROM_SDA PA11
#define IIC_EEPROM_SCL PA12
#define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16)
#elif ENABLED(SDCARD_EEPROM_EMULATION)
#define MARLIN_EEPROM_SIZE 0x800 // 2K
#endif
//
// Servos
//
#ifndef SERVO0_PIN
#define SERVO0_PIN PB0 // BLTouch OUT
#endif
//
// Limit Switches
//
#define X_STOP_PIN PA5
#define Y_STOP_PIN PA6
#define Z_STOP_PIN PA7
#ifndef Z_MIN_PROBE_PIN
#define Z_MIN_PROBE_PIN PB1 // BLTouch IN
#endif
//
// Filament Runout Sensor
//
#ifndef FIL_RUNOUT_PIN
#define FIL_RUNOUT_PIN PA4
#endif
//
// Steppers
//
#define X_STEP_PIN PC2
#define X_DIR_PIN PB9
#define X_ENABLE_PIN PC3 // All steppers share enable pins
#define Y_STEP_PIN PB8
#define Y_DIR_PIN PB7
#define Y_ENABLE_PIN X_ENABLE_PIN
#define Z_STEP_PIN PB6
#define Z_DIR_PIN PB5
#define Z_ENABLE_PIN X_ENABLE_PIN
#define E0_STEP_PIN PB4
#define E0_DIR_PIN PB3
#define E0_ENABLE_PIN X_ENABLE_PIN
//
// Temperature Sensors
//
#define TEMP_0_PIN PC5 // HEATER1 ADC1_IN15
#define TEMP_BED_PIN PC4 // HOT BED ADC1_IN14
//
// Heaters / Fans
//
#define HEATER_0_PIN PA1 // HEATER1
#define HEATER_BED_PIN PA2 // HOT BED
#define FAN0_PIN PA0 // FAN0
//
// SD Card
//
#define SD_DETECT_PIN PA10
#define SDCARD_CONNECTION ONBOARD
#define ONBOARD_SDIO
#define NO_SD_HOST_DRIVE // This board's SD card is only seen by the printer
/**
* ------
* PC6 | 1 2 | PB2
* PC0 | 3 4 | PC1
* PB14 5 6 | PB13
* PB12 | 7 8 | PB15
* GND | 9 10 | +5V
* ------
* EXP1
*/
#define EXP1_01_PIN PC6
#define EXP1_02_PIN PB2
#define EXP1_03_PIN PC0
#define EXP1_04_PIN PC1
#define EXP1_05_PIN PB14 // ENC
#define EXP1_06_PIN PB13 // BEEPER
#define EXP1_07_PIN PB12 // EN2
#define EXP1_08_PIN PB15 // EN1
#if ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI)
/**
* Display pinout (display 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
* ------
*/
#ifndef BEEPER_PIN
#define BEEPER_PIN EXP1_06_PIN // BEEP
#endif
#define BTN_ENC EXP1_05_PIN // EN
#define BTN_EN1 EXP1_08_PIN // A
#define BTN_EN2 EXP1_07_PIN // B
#ifndef LCD_SERIAL_PORT
#define LCD_SERIAL_PORT 1
#endif
#endif
//
// SDIO Pins
//
#define BOARD_SDIO_D0 PC8
#define BOARD_SDIO_D1 PC9
#define BOARD_SDIO_D2 PC10
#define BOARD_SDIO_D3 PC11
#define BOARD_SDIO_CLK PC12
#define BOARD_SDIO_CMD PD2
#define BOARD_SDIO_DET PA10
//
// USART Pins
//
// Display
#define BOARD_USART1_TX_PIN PC0
#define BOARD_USART1_RX_PIN PC1
// 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
// Onboard LED (HIGH = off, LOW = on)
#ifndef LED_BUILTIN
#define LED_BUILTIN PA3
#endif

View file

@ -84,7 +84,7 @@
#endif #endif
#ifndef Z2_STOP_PIN #ifndef Z2_STOP_PIN
#define Z2_STOP_PIN 80 // PE7 - Extended mega2560 pin #define Z2_STOP_PIN 80 // PE7 - Extended mega2560 pin
#endif #endif
/** Filament Runout Sensors /** Filament Runout Sensors
* *

View file

@ -885,6 +885,12 @@
#elif MB(MINITRONICS20) #elif MB(MINITRONICS20)
#include "samd/pins_MINITRONICS20.h" // SAMD21 env:SAMD21_minitronics20 #include "samd/pins_MINITRONICS20.h" // SAMD21 env:SAMD21_minitronics20
//
// HC32 ARM Cortex-M4
//
#elif MB(AQUILA_V101)
#include "hc32f4/pins_AQUILA_101.h" // HC32F460 env:HC32F460C_aquila_101
// //
// Custom board (with custom PIO env) // Custom board (with custom PIO env)
// //

View file

@ -210,7 +210,7 @@
#define TFT_CS_PIN FSMC_CS_PIN #define TFT_CS_PIN FSMC_CS_PIN
#define TFT_RS_PIN FSMC_RS_PIN #define TFT_RS_PIN FSMC_RS_PIN
// Buffer for Color UI // Buffer for Color UI
#define TFT_BUFFER_WORDS 3200 #define TFT_BUFFER_WORDS 3200
#endif #endif

View file

@ -0,0 +1,15 @@
#!/usr/bin/env bash
#
# Build tests for HC32F460C_aquila_101
#
# exit on first failure
set -e
restore_configs
opt_set MOTHERBOARD BOARD_AQUILA_V101 SERIAL_PORT 1
opt_enable EEPROM_SETTINGS SDSUPPORT EMERGENCY_PARSER
exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" "$3"
# cleanup
restore_configs

88
ini/hc32.ini Normal file
View file

@ -0,0 +1,88 @@
#
# Marlin Firmware
# PlatformIO Configuration File
#
#################################
#
# HC32F460 Architecture with unified HC32 HAL
#
# Naming Example: HC32F460JEUA
#
# |- Xiaohua Semiconductor
# | |- CPU bit width (32: 32-bit)
# | | |- Product Type (F: Universal MCU)
# | | | |- Core Type (4: Cortex-M4)
# | | | | |- Performance (6: High Performance)
# | | | | | |- Configuration (0: Configuration 1)
# | | | | | | |- Pin Count (J: 48, K: 60/64, P: 100)
# | | | | | | | |- Flash Capacity (C: 256KB, E: 512KB)
# | | | | | | | | |- Package (T: LQFP, U: QFN, H:VFBGA)
# | | | | | | | | | |- Temperature range (A: -40-85°C, B: -40-105°C)
# HC 32 F 4 6 0 J E U A
#
#################################
#
# Base Environment for all HC32F460 variants
#
[HC32F460_base]
platform = https://github.com/shadow578/platform-hc32f46x/archive/main.zip
board = generic_hc32f460
build_src_filter = ${common.default_src_filter} +<src/HAL/HC32> +<src/HAL/shared/backtrace>
build_type = release
build_flags =
-D ARDUINO_ARCH_HC32
-D REDIRECT_PRINTF_TO_SERIAL # Redirect core-provided printf to host serial
-D F_CPU=SYSTEM_CLOCK_FREQUENCIES.pclk1 # Override F_CPU to PCLK1, as marlin freaks out otherwise...
-D PLATFORM_M997_SUPPORT # Enable M997 command
# DDL / Arduino Configuration
-D DISABLE_SERIAL_GLOBALS # Disable global Serial objects, we use our own
-D CORE_DISABLE_FAULT_HANDLER # Disable arduino core fault handler (we use our own)
# DDL / Arduino Debug Options
#-D __DEBUG # DDL debug mode
#-D __CORE_DEBUG # Arduino core debug mode
-D PANIC_ENABLE # enable custom panic handlers (in MinSerial)
# options to reduce debug mode footprint (-16K; messages are less verbose)
-D __DEBUG_SHORT_FILENAMES # Use short filenames in DDL debug output
-D __PANIC_SHORT_FILENAMES # Use short filenames in core panic output
-D __OMIT_PANIC_MESSAGE # Omit panic messages in core panic output
# Drivers and Middleware required by the HC32 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 flags to reduce binary size
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)
#
# Base HC32F460xCxx (256K Flash)
#
[HC32F460C_base]
extends = HC32F460_base
board_build.ld_args.flash_size = 256K
#
# Base HC32F460xExx (512K Flash)
#
[HC32F460E_base]
extends = HC32F460_base
board_build.ld_args.flash_size = 512K
#
# Aquila V1.0.1 Mainboard, as found in the Voxelab Aquila X2
#
[env:HC32F460C_aquila_101]
extends = HC32F460C_base
board_build.ld_args.flash_start = 0xC000 # Bootloader start address, as logged by the bootloader on boot
board_build.ld_args.boot_mode = secondary # Save ~1.4k of flash by compiling as secondary firmware

View file

@ -21,6 +21,7 @@ extra_configs =
ini/due.ini ini/due.ini
ini/esp32.ini ini/esp32.ini
ini/features.ini ini/features.ini
ini/hc32.ini
ini/lpc176x.ini ini/lpc176x.ini
ini/native.ini ini/native.ini
ini/samd21.ini ini/samd21.ini