aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--src/Kconfig3
-rw-r--r--src/hc32f460/Kconfig79
-rw-r--r--src/hc32f460/Makefile37
-rw-r--r--src/hc32f460/adc.c155
-rw-r--r--src/hc32f460/gpio.c153
-rw-r--r--src/hc32f460/gpio.h62
-rw-r--r--src/hc32f460/hard_pwm.c164
-rw-r--r--src/hc32f460/internal.h29
-rw-r--r--src/hc32f460/interrupts.c29
-rw-r--r--src/hc32f460/main.c28
-rw-r--r--src/hc32f460/serial.c189
11 files changed, 928 insertions, 0 deletions
diff --git a/src/Kconfig b/src/Kconfig
index 53b6d166..936e3410 100644
--- a/src/Kconfig
+++ b/src/Kconfig
@@ -20,6 +20,8 @@ choice
bool "LPC176x (Smoothieboard)"
config MACH_STM32
bool "STMicroelectronics STM32"
+ config MACH_HC32F460
+ bool "Huada Semiconductor HC32F460"
config MACH_RP2040
bool "Raspberry Pi RP2040"
config MACH_PRU
@@ -35,6 +37,7 @@ source "src/atsam/Kconfig"
source "src/atsamd/Kconfig"
source "src/lpc176x/Kconfig"
source "src/stm32/Kconfig"
+source "src/hc32f460/Kconfig"
source "src/rp2040/Kconfig"
source "src/pru/Kconfig"
source "src/linux/Kconfig"
diff --git a/src/hc32f460/Kconfig b/src/hc32f460/Kconfig
new file mode 100644
index 00000000..d39bdf82
--- /dev/null
+++ b/src/hc32f460/Kconfig
@@ -0,0 +1,79 @@
+# Kconfig settings for Huada HC32F460 processor
+
+if MACH_HC32F460
+
+config HC32F460_SELECT
+ bool
+ default y
+ select HAVE_GPIO
+ select HAVE_GPIO_ADC
+ select HAVE_GPIO_BITBANGING
+ select HAVE_STRICT_TIMING
+ select HAVE_GPIO_HARD_PWM
+ select HAVE_STEPPER_BOTH_EDGE
+
+config BOARD_DIRECTORY
+ string
+ default "hc32f460"
+
+
+######################################################################
+# Communication interface
+######################################################################
+
+choice
+ prompt "Communication interface"
+ config HC32F460_SERIAL_PA7_PA8
+ bool "Serial (PA7 & PA8) - Creality Ender 2 PRO"
+ select SERIAL
+ config HC32F460_SERIAL_PA3_PA2
+ bool "Serial (PA3 & PA2) - Anycube"
+ select SERIAL
+ config HC32F460_SERIAL_PA15_PA9
+ bool "Serial (PA15 & PA09) - Voxelab"
+ select SERIAL
+ config HC32F460_SERIAL_PC0_PC1
+ bool "Serial (PC0 & PC1) - on LCD connector"
+ select SERIAL
+endchoice
+
+
+######################################################################
+# Bootloader
+# bootloader moves code and then VTOR.RESET points here:
+######################################################################
+config FLASH_SIZE
+ hex
+ default 0x40000
+
+config FLASH_APPLICATION_ADDRESS
+ default 0x8000 # Aquila is 0xC000
+
+config FLASH_BOOT_ADDRESS
+ hex
+ default 0x0
+
+config RAM_SIZE
+ hex
+ default 0x8000
+
+# use the fast RAM in the HC32F460
+config RAM_START
+ hex
+ default 0x1fff8000
+
+config STACK_SIZE
+ int
+ default 1024
+
+
+config CLOCK_FREQ
+ int
+ default 200000000 # Voxelab uses 168000000
+
+
+config MCU
+ string
+ default "HC32F460"
+
+endif
diff --git a/src/hc32f460/Makefile b/src/hc32f460/Makefile
new file mode 100644
index 00000000..c4426736
--- /dev/null
+++ b/src/hc32f460/Makefile
@@ -0,0 +1,37 @@
+# hc32f460 build rules
+
+# Setup the toolchain
+CROSS_PREFIX=arm-none-eabi-
+
+dirs-y += src/hc32f460 src/generic lib/hc32f460/driver/src lib/hc32f460/mcu/common
+
+CFLAGS += -mthumb -mcpu=cortex-m4 -Isrc/hc32f460 -Ilib/hc32f460/driver/inc -Ilib/hc32f460/mcu/common -Ilib/cmsis-core -DHC32F460
+
+CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
+CFLAGS_klipper.elf += -T $(OUT)src/generic/armcm_link.ld
+$(OUT)klipper.elf: $(OUT)src/generic/armcm_link.ld
+
+# Add source files
+src-y += hc32f460/main.c
+src-y += hc32f460/interrupts.c
+src-y += hc32f460/gpio.c
+src-y += ../lib/hc32f460/mcu/common/system_hc32f460.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_clk.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_efm.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_sram.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_utility.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_gpio.c
+src-y += ../lib/hc32f460/driver/src/hc32f460_pwc.c
+src-$(CONFIG_HAVE_GPIO_ADC) += hc32f460/adc.c ../lib/hc32f460/driver/src/hc32f460_adc.c
+src-$(CONFIG_SERIAL) += hc32f460/serial.c generic/serial_irq.c ../lib/hc32f460/driver/src/hc32f460_usart.c
+src-$(CONFIG_HAVE_GPIO_HARD_PWM) += hc32f460/hard_pwm.c ../lib/hc32f460/driver/src/hc32f460_timera.c
+src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_timer.c
+src-y += generic/armcm_reset.c generic/crc16_ccitt.c
+
+
+# Build the additional bin output file
+target-y += $(OUT)klipper.bin
+
+$(OUT)klipper.bin: $(OUT)klipper.elf
+ @echo " Creating bin file $@"
+ $(Q)$(OBJCOPY) -O binary $< $@
diff --git a/src/hc32f460/adc.c b/src/hc32f460/adc.c
new file mode 100644
index 00000000..ef1e58fb
--- /dev/null
+++ b/src/hc32f460/adc.c
@@ -0,0 +1,155 @@
+// ADC functions on Huada HC32F460
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "generic/misc.h" // timer_from_us
+#include "command.h" // shutdown
+#include "board/gpio.h" // gpio_adc_setup
+#include "board/internal.h" // GPIO
+#include "sched.h" // sched_shutdown
+
+// library
+#include "hc32f460_adc.h"
+#include "hc32f460_pwc.h"
+#include "hc32f460_gpio.h"
+
+#define ADC_RESOLUTION_12BIT (12u)
+#define ADC_RESOLUTION_10BIT (10u)
+#define ADC_RESOLUTION_8BIT (8u)
+
+#define ADC1_RESOLUTION (ADC_RESOLUTION_12BIT)
+#define ADC1_PRECISION (1ul << ADC1_RESOLUTION)
+
+#if ADC1_RESOLUTION == ADC_RESOLUTION_12BIT
+#define AdcResolution AdcResolution_12Bit
+#elif ADC1_RESOLUTION == ADC_RESOLUTION_10BIT
+#define AdcResolution AdcResolution_10Bit
+#else
+#define AdcResolution AdcResolution_8Bit
+#endif
+
+
+/* Timeout value definitions. Found in example code */
+#define TIMEOUT_VAL (30u)
+
+DECL_CONSTANT("ADC_MAX", ADC1_PRECISION-1);
+
+// These pins can be used for ADC
+static const uint8_t adc_gpio[] = {
+ GPIO('A', 0), // Chan 0
+ GPIO('A', 1), // Chan 1
+ GPIO('A', 2), // Chan 2
+ GPIO('A', 3), // Chan 3
+ GPIO('A', 4), // Chan 4
+ GPIO('A', 5), // Chan 5
+ GPIO('A', 6), // Chan 6
+ GPIO('A', 7), // Chan 7
+ GPIO('B', 0), // Chan 8
+ GPIO('B', 1), // Chan 9
+ GPIO('C', 0), // Chan 10 // TBed on TriGorilla
+ GPIO('C', 1), // Chan 11 // THead on TriGorilla
+ GPIO('C', 2), // Chan 12
+ GPIO('C', 3), // Chan 13
+ GPIO('C', 4), // Chan 14 // TBed on aquilla
+ GPIO('C', 5), // Chan 15 // THead on aquilla
+};
+
+
+struct gpio_adc
+gpio_adc_setup(uint32_t gpio)
+{
+ // validate pin in adc_pins table
+ int chan;
+ for (chan=0; ; chan++)
+ {
+ if (chan >= ARRAY_SIZE(adc_gpio))
+ {
+ shutdown("Not a valid ADC pin");
+ }
+ if (adc_gpio[chan] == gpio)
+ {
+ break;
+ }
+ }
+
+ // set as analog
+ gpio_peripheral(gpio, Pin_Mode_Ana, 0);
+
+ uint8_t sampleTime[ARRAY_SIZE(adc_gpio)] = { TIMEOUT_VAL }; // all chans
+ stc_adc_ch_cfg_t stcAdcChan;
+ stcAdcChan.u32Channel = 1 << chan;
+ stcAdcChan.u8Sequence = ADC_SEQ_A; // all conversions are in SEQ A
+ stcAdcChan.pu8SampTime = sampleTime;
+ ADC_AddAdcChannel(M4_ADC1, &stcAdcChan);
+
+ return (struct gpio_adc){ .chan = chan };
+}
+
+
+// Try to sample a value. Returns zero if sample ready, otherwise
+// returns the number of clock ticks the caller should wait before
+// retrying this function.
+uint32_t
+gpio_adc_sample(struct gpio_adc g)
+{
+ // true if the sequence is finished
+ if (ADC_GetEocFlag(M4_ADC1, ADC_SEQ_A))
+ {
+ // all conversions are done - clear the flag
+ ADC_ClrEocFlag(M4_ADC1, ADC_SEQ_A);
+ return 0;
+ }
+ else if (M4_ADC1->STR & 1)
+ {
+ // running but not done yet
+ return timer_from_us(TIMEOUT_VAL/2);
+ }
+ else
+ {
+ // not running - so start
+ ADC_StartConvert(M4_ADC1);
+ }
+
+ return timer_from_us(TIMEOUT_VAL);
+}
+
+
+// Read a value; use only after gpio_adc_sample() returns zero
+uint16_t
+gpio_adc_read(struct gpio_adc g)
+{
+ // return the one we want...
+ return ADC_GetValue(M4_ADC1, g.chan);
+}
+
+
+// Cancel a sample that may have been started with gpio_adc_sample()
+void
+gpio_adc_cancel_sample(struct gpio_adc g)
+{
+ ADC_StopConvert(M4_ADC1);
+}
+
+
+// The clocks are already set by the loader.
+// There is ADC1 and ADC2. Sequences do all channels at once.
+void
+adc_init(void)
+{
+ // PCLK2 (ADC clock) is 'divide by 4', Max ADC clock is 60MHz
+ stc_adc_init_t stcAdcInit = {0};
+ stcAdcInit.enResolution = AdcResolution; // see define above
+ stcAdcInit.enDataAlign = AdcDataAlign_Right;
+ stcAdcInit.enAutoClear = AdcClren_Disable;
+ stcAdcInit.enScanMode = AdcMode_SAOnce;
+
+ // power-on ADC
+ PWC_Fcg3PeriphClockCmd(PWC_FCG3_PERIPH_ADC1, Enable);
+
+ // only using ADC1
+ ADC_Init(M4_ADC1, &stcAdcInit);
+}
+
+DECL_INIT(adc_init);
diff --git a/src/hc32f460/gpio.c b/src/hc32f460/gpio.c
new file mode 100644
index 00000000..e3b98df4
--- /dev/null
+++ b/src/hc32f460/gpio.c
@@ -0,0 +1,153 @@
+// GPIO functions on HC32F460
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <string.h> // ffs
+#include "board/irq.h" // irq_save
+#include "command.h" // DECL_ENUMERATION_RANGE
+#include "board/gpio.h" // gpio_out_setup
+#include "internal.h"
+#include "sched.h" // sched_shutdown
+
+#include "hc32f460_gpio.h"
+
+
+// 64pin package
+DECL_ENUMERATION_RANGE("pin", "PA0", GPIO('A', 0), 16);
+DECL_ENUMERATION_RANGE("pin", "PB0", GPIO('B', 0), 16);
+DECL_ENUMERATION_RANGE("pin", "PC0", GPIO('C', 0), 16);
+DECL_ENUMERATION_RANGE("pin", "PD2", GPIO('D', 2), 1);
+DECL_ENUMERATION_RANGE("pin", "PH2", PortH * 16 + 2, 1); // H: special case
+
+
+// HC32F460 ports are in one M4_PORT - offset by 0x10
+// eg toggle: M4_PORT->POTRA + 0x10 => M4_PORT->POTRB
+// 'gpio' is port (0-4) * 16 + pinPosition (0-15)
+#define POTR_OFFSET offsetof(M4_PORT_TypeDef, POTRA) // output flip
+#define PODR_OFFSET offsetof(M4_PORT_TypeDef, PODRA) // output data
+#define PIDR_OFFSET offsetof(M4_PORT_TypeDef, PIDRA) // input data
+#define POSR_OFFSET offsetof(M4_PORT_TypeDef, POSRA) // output set
+#define PORR_OFFSET offsetof(M4_PORT_TypeDef, PORRA) // output reset
+#define PORT_OFFSET offsetof(M4_PORT_TypeDef, PIDRB) // space between PORTS
+
+
+
+void
+gpio_peripheral(uint32_t gpio, int func, int pull_up)
+{
+ stc_port_init_t stcPortInit;
+
+ irqstatus_t flag = irq_save();
+
+ stcPortInit.enPinMode = func;
+ stcPortInit.enLatch = Disable;
+ stcPortInit.enExInt = Disable;
+ stcPortInit.enInvert = Disable;
+ stcPortInit.enPullUp = pull_up ? Enable : Disable;
+ stcPortInit.enPinDrv = Pin_Drv_L;
+ stcPortInit.enPinOType = Pin_OType_Cmos;
+ stcPortInit.enPinSubFunc = Disable;
+
+ // make the port GPIO and disable the sub functionality
+ PORT_SetFunc(GPIO2PORT(gpio), GPIO2BIT(gpio), Func_Gpio, Disable);
+ PORT_Init(GPIO2PORT(gpio), GPIO2BIT(gpio), &stcPortInit);
+
+ irq_restore(flag);
+}
+
+
+struct gpio_out
+gpio_out_setup(uint32_t gpio, uint32_t val)
+{
+ uint32_t port = (uint32_t)M4_PORT + GPIO2PORT(gpio) * PORT_OFFSET;
+ struct gpio_out g =
+ { .gpio = gpio, .portAddress = port, .bitMask = GPIO2BIT(gpio) };
+ gpio_out_reset(g, val);
+
+ return g;
+}
+
+
+void
+gpio_out_reset(struct gpio_out g, uint32_t val)
+{
+ irqstatus_t flag = irq_save();
+ if (val)
+ {
+ uint16_t *POSRx = (uint16_t *)(g.portAddress + POSR_OFFSET);
+ *POSRx = g.bitMask;
+ }
+ else
+ {
+ uint16_t *PORRx = (uint16_t *)(g.portAddress + PORR_OFFSET);
+ *PORRx = g.bitMask;
+ }
+
+ gpio_peripheral(g.gpio, Pin_Mode_Out, 0);
+ irq_restore(flag);
+}
+
+
+void
+gpio_out_toggle_noirq(struct gpio_out g)
+{
+ uint16_t *POTRx = (uint16_t *)(g.portAddress + POTR_OFFSET);
+ *POTRx = g.bitMask;
+}
+
+
+void
+gpio_out_toggle(struct gpio_out g)
+{
+ irqstatus_t flag = irq_save();
+ gpio_out_toggle_noirq(g);
+ irq_restore(flag);
+}
+
+
+void
+gpio_out_write(struct gpio_out g, uint32_t val)
+{
+ if (val)
+ {
+ uint16_t *POSRx = (uint16_t *)(g.portAddress + POSR_OFFSET);
+ *POSRx = g.bitMask;
+ }
+ else
+ {
+ uint16_t *PORRx = (uint16_t *)(g.portAddress + PORR_OFFSET);
+ *PORRx = g.bitMask;
+ }
+}
+
+
+struct gpio_in
+gpio_in_setup(uint32_t gpio, int32_t pull_up)
+{
+ uint32_t port = (uint32_t)M4_PORT + GPIO2PORT(gpio) * PORT_OFFSET;
+
+ struct gpio_in g =
+ { .gpio = gpio, .portAddress = port, .bitMask = GPIO2BIT(gpio) };
+ gpio_in_reset(g, pull_up);
+
+ return g;
+}
+
+
+void
+gpio_in_reset(struct gpio_in g, int32_t pull_up)
+{
+ irqstatus_t flag = irq_save();
+ gpio_peripheral(g.gpio, Pin_Mode_In, pull_up);
+ irq_restore(flag);
+}
+
+
+uint8_t
+gpio_in_read(struct gpio_in g)
+{
+ uint16_t *PIDRx = (uint16_t *)(g.portAddress + PIDR_OFFSET);
+ return !!(*PIDRx & g.bitMask);
+}
diff --git a/src/hc32f460/gpio.h b/src/hc32f460/gpio.h
new file mode 100644
index 00000000..5e88a234
--- /dev/null
+++ b/src/hc32f460/gpio.h
@@ -0,0 +1,62 @@
+#ifndef __HC32F460_GPIO_H
+#define __HC32F460_GPIO_H
+
+#include <stdint.h> // uint32_t
+
+
+struct gpio_out {
+ uint32_t portAddress; // M4_PORT or offset
+ uint16_t gpio; // the mangled pin+port
+ uint16_t bitMask; // the pin shifted to use in register
+};
+struct gpio_out gpio_out_setup(uint32_t gpio, uint32_t val);
+void gpio_out_reset(struct gpio_out g, uint32_t val);
+void gpio_out_toggle_noirq(struct gpio_out g);
+void gpio_out_toggle(struct gpio_out g);
+void gpio_out_write(struct gpio_out g, uint32_t val);
+
+struct gpio_in {
+ uint32_t portAddress;
+ uint16_t gpio;
+ uint16_t bitMask;
+};
+struct gpio_in gpio_in_setup(uint32_t gpio, int32_t pull_up);
+void gpio_in_reset(struct gpio_in g, int32_t pull_up);
+uint8_t gpio_in_read(struct gpio_in g);
+
+struct gpio_pwm {
+ void *timer;
+ uint32_t chan;
+};
+struct gpio_pwm gpio_pwm_setup(uint8_t gpio, uint32_t cycle_time, uint8_t val);
+void gpio_pwm_write(struct gpio_pwm g, uint32_t val);
+
+// all ADC operations will be on ADC1
+struct gpio_adc {
+ uint32_t chan;
+};
+struct gpio_adc gpio_adc_setup(uint32_t gpio);
+uint32_t gpio_adc_sample(struct gpio_adc g);
+uint16_t gpio_adc_read(struct gpio_adc g);
+void gpio_adc_cancel_sample(struct gpio_adc g);
+
+struct spi_config {
+ void *spi;
+ uint32_t spi_cr1;
+};
+struct spi_config spi_setup(uint32_t bus, uint8_t mode, uint32_t rate);
+void spi_prepare(struct spi_config config);
+void spi_transfer(struct spi_config config, uint8_t receive_data
+ , uint8_t len, uint8_t *data);
+
+struct i2c_config {
+ void *i2c;
+ uint8_t addr;
+};
+
+struct i2c_config i2c_setup(uint32_t bus, uint32_t rate, uint8_t addr);
+void i2c_write(struct i2c_config config, uint8_t write_len, uint8_t *write);
+void i2c_read(struct i2c_config config, uint8_t reg_len, uint8_t *reg
+ , uint8_t read_len, uint8_t *read);
+
+#endif // gpio.h
diff --git a/src/hc32f460/hard_pwm.c b/src/hc32f460/hard_pwm.c
new file mode 100644
index 00000000..9d3387e6
--- /dev/null
+++ b/src/hc32f460/hard_pwm.c
@@ -0,0 +1,164 @@
+// Hardware PWM support on HC32F460
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h"
+#include "board/irq.h" // irq_save
+#include "command.h" // shutdown
+#include "board/gpio.h" // gpio_pwm_write
+#include "internal.h" // GPIO
+#include "sched.h" // sched_shutdown
+
+// library
+#include "hc32f460_timera.h"
+#include "hc32f460_pwc.h"
+#include "hc32f460_gpio.h"
+
+
+#define MAX_PWM ((1 << 16) - 1)
+DECL_CONSTANT("PWM_MAX", MAX_PWM);
+
+// timer A (general purpose) has 6 units and each has 8 PWM
+// M4_TMRA_TypeDef* timer;
+
+struct gpio_pwm_info {
+ uint8_t gpio;
+ uint8_t unit; // 6 units in Timer A
+ en_timera_channel_t chan;
+};
+
+// Timer A (general purpose) is only timer used
+// These are for pin function 4 only
+// Some PWM come out on more than 1 pin
+// 64pin package
+static const struct gpio_pwm_info pwm_mapping[] = {
+ {GPIO('A', 0), 2, TimeraCh1},
+ {GPIO('A', 1), 2, TimeraCh2},
+ {GPIO('A', 2), 2, TimeraCh3},
+ {GPIO('A', 3), 2, TimeraCh4},
+ {GPIO('A', 5), 2, TimeraCh1},
+ {GPIO('A', 8), 1, TimeraCh1},
+ {GPIO('A', 9), 1, TimeraCh2},
+ {GPIO('A',10), 1, TimeraCh3},
+ {GPIO('A',11), 1, TimeraCh4},
+ {GPIO('A',13), 2, TimeraCh5},
+ {GPIO('A',14), 2, TimeraCh6},
+ {GPIO('A',15), 2, TimeraCh1},
+ {GPIO('B', 0), 1, TimeraCh6},
+ {GPIO('B', 1), 1, TimeraCh7},
+ {GPIO('B', 2), 1, TimeraCh8},
+ {GPIO('B', 3), 2, TimeraCh2},
+ {GPIO('B', 4), 3, TimeraCh1},
+ {GPIO('B', 5), 3, TimeraCh2},
+ {GPIO('B', 6), 4, TimeraCh1},
+ {GPIO('B', 7), 4, TimeraCh2},
+ {GPIO('B', 8), 4, TimeraCh3},
+ {GPIO('B', 9), 4, TimeraCh4},
+ {GPIO('B',10), 2, TimeraCh3},
+ {GPIO('B',12), 1, TimeraCh8},
+ {GPIO('B',13), 1, TimeraCh5},
+ {GPIO('B',14), 1, TimeraCh6},
+ {GPIO('B',15), 1, TimeraCh7},
+ {GPIO('C', 0), 2, TimeraCh5},
+ {GPIO('C', 1), 2, TimeraCh6},
+ {GPIO('C', 2), 2, TimeraCh7},
+ {GPIO('C', 3), 2, TimeraCh8},
+ {GPIO('C', 6), 3, TimeraCh1},
+ {GPIO('C', 7), 3, TimeraCh2},
+ {GPIO('C', 8), 3, TimeraCh3},
+ {GPIO('C', 9), 3, TimeraCh4},
+ {GPIO('C',10), 2, TimeraCh7},
+ {GPIO('C',11), 2, TimeraCh8},
+ {GPIO('C',13), 4, TimeraCh8},
+ {GPIO('C',14), 4, TimeraCh5},
+ {GPIO('C',15), 4, TimeraCh6},
+ {GPIO('D', 2), 2, TimeraCh4},
+};
+
+
+struct gpio_pwm
+gpio_pwm_setup(uint8_t gpio, uint32_t cycle_time, uint8_t val)
+{
+ // Find gpio pin in pwm_regs table
+ const struct gpio_pwm_info* p = pwm_mapping;
+ for (;; p++) {
+ if (p >= &pwm_mapping[ARRAY_SIZE(pwm_mapping)])
+ shutdown("Not a valid PWM pin");
+ if (p->gpio == gpio)
+ break;
+ }
+
+ // select registers - could make it programmatic
+ // All TimerA power control bits are in PWC_FCG2
+ M4_TMRA_TypeDef *timerA;
+ switch (p->unit)
+ {
+ default:
+ case 1:
+ timerA = M4_TMRA1;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA1, Enable);
+ break;
+ case 2:
+ timerA = M4_TMRA2;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA2, Enable);
+ break;
+ case 3:
+ timerA = M4_TMRA3;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA3, Enable);
+ break;
+ case 4:
+ timerA = M4_TMRA4;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA4, Enable);
+ break;
+ case 5:
+ timerA = M4_TMRA5;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA5, Enable);
+ break;
+ case 6:
+ timerA = M4_TMRA6;
+ PWC_Fcg2PeriphClockCmd(PWC_FCG2_PERIPH_TIMA6, Enable);
+ break;
+ }
+
+ // set the function - only using #4 (Func_Tima0)
+ PORT_SetFunc(GPIO2PORT(gpio), GPIO2PIN(gpio), Func_Tima0, Disable);
+
+ /* Configuration timera unit 1 base structure */
+ stc_timera_base_init_t stcTimeraInit;
+ stcTimeraInit.enClkDiv = TimeraPclkDiv128; // 128 chosen - use below
+ stcTimeraInit.enCntMode = TimeraCountModeTriangularWave;
+ stcTimeraInit.enCntDir = TimeraCountDirUp;
+ stcTimeraInit.enSyncStartupEn = Disable;
+ stcTimeraInit.u16PeriodVal = cycle_time / 2U / 128U / 2;
+ TIMERA_BaseInit(timerA, &stcTimeraInit);
+
+ /* Configuration timera unit 1 compare structure */
+ stc_timera_compare_init_t stcTimerCompareInit;
+ stcTimerCompareInit.u16CompareVal = stcTimeraInit.u16PeriodVal * 4u / 5u;
+ stcTimerCompareInit.enStartCountOutput = TimeraCountStartOutputHigh;
+ stcTimerCompareInit.enStopCountOutput = TimeraCountStopOutputHigh;
+ stcTimerCompareInit.enCompareMatchOutput = TimeraCompareMatchOutputReverse;
+ stcTimerCompareInit.enPeriodMatchOutput = TimeraPeriodMatchOutputKeep;
+ stcTimerCompareInit.enSpecifyOutput = TimeraSpecifyOutputInvalid;
+ stcTimerCompareInit.enCacheEn = Disable;
+ stcTimerCompareInit.enTriangularTroughTransEn = Enable;
+ stcTimerCompareInit.enTriangularCrestTransEn = Disable;
+ stcTimerCompareInit.u16CompareCacheVal = stcTimerCompareInit.u16CompareVal;
+ TIMERA_CompareInit(timerA, p->chan, &stcTimerCompareInit);
+ TIMERA_CompareCmd(timerA, p->chan, Enable);
+
+ // default setup - all disabled
+ stc_timera_hw_startup_config_t stcTimeraHwConfig = { 0 };
+ TIMERA_HwStartupConfig(timerA, &stcTimeraHwConfig);
+
+ return (struct gpio_pwm){.timer = timerA, .chan = p->chan};
+}
+
+
+void
+gpio_pwm_write(struct gpio_pwm g, uint32_t val)
+{
+ TIMERA_SetCompareValue(g.timer, g.chan, (uint16_t)val);
+}
diff --git a/src/hc32f460/internal.h b/src/hc32f460/internal.h
new file mode 100644
index 00000000..dd02f9f3
--- /dev/null
+++ b/src/hc32f460/internal.h
@@ -0,0 +1,29 @@
+#ifndef __HC32F460_INTERNAL_H
+#define __HC32F460_INTERNAL_H
+
+
+// Local definitions for Huada HC32F460
+
+#include "autoconf.h"
+#include "hc32f460.h"
+
+// The HC32F460 library uses a port address and a shifted pin bit
+// eg en_result_t PORT_Toggle(en_port_t enPort, uint16_t u16Pin);
+// see hc32f460_gpio.h
+
+
+// encode and decode gpio ports and pins
+#define GPIO(PORT, NUM) (((PORT)-'A') * 16 + (NUM))
+#define GPIO2PORT(GPIO) ((GPIO) / 16)
+#define GPIO2BIT(GPIO) (1<<((GPIO) % 16))
+#define GPIO2PIN(GPIO) ((GPIO) % 16)
+
+#define GPIO_INPUT 0
+#define GPIO_OUTPUT 1
+
+void gpio_peripheral(uint32_t pin, int func, int pull_up);
+
+// from local interrupts.c - helper
+void IrqRegistration(en_int_src_t irqSrc, IRQn_Type irqType);
+
+#endif // internal.h
diff --git a/src/hc32f460/interrupts.c b/src/hc32f460/interrupts.c
new file mode 100644
index 00000000..fb93648f
--- /dev/null
+++ b/src/hc32f460/interrupts.c
@@ -0,0 +1,29 @@
+// Interrupt support for HC32F460
+// The library interrupt support is huge and redefines systick
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "hc32f460.h"
+
+#define IRQ_PRIORITY_DEFAULT 15u
+
+/* the interrupts on the hc32f460 can be 're-assigned'
+ The author can choose the irqType (IRQ000_Handler, etc...)
+ that the source (irqSrc) triggers
+ */
+
+void IrqRegistration(en_int_src_t irqSrc, IRQn_Type irqType)
+{
+ stc_intc_sel_field_t *stcIntSel = (stc_intc_sel_field_t *)
+ ((uint32_t)(&M4_INTC->SEL0) + (4u * irqType));
+
+ // what is the source of the selected interrupt? (USART, etc...)
+ stcIntSel->INTSEL = irqSrc;
+
+ // set priority and enable
+ NVIC_SetPriority(irqType, IRQ_PRIORITY_DEFAULT);
+ NVIC_ClearPendingIRQ(irqType);
+ NVIC_EnableIRQ(irqType);
+}
diff --git a/src/hc32f460/main.c b/src/hc32f460/main.c
new file mode 100644
index 00000000..a641667f
--- /dev/null
+++ b/src/hc32f460/main.c
@@ -0,0 +1,28 @@
+// Code to setup clocks on Huada HC32F460
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h" // CONFIG_MACH_AVR
+#include "sched.h"
+#include "system_hc32f460.h"
+
+
+/****************************************************************
+ * Startup
+ ****************************************************************/
+
+// Main entry point - called from armcm_boot.c:ResetHandler()
+void __attribute__((noreturn))
+armcm_main(void)
+{
+ // sets the system clock speed variable for library use
+ SystemInit();
+
+ // manage the system
+ sched_main();
+
+ // never get here
+ for (;;) ;
+}
diff --git a/src/hc32f460/serial.c b/src/hc32f460/serial.c
new file mode 100644
index 00000000..45f6b89f
--- /dev/null
+++ b/src/hc32f460/serial.c
@@ -0,0 +1,189 @@
+// HC32F460 serial
+//
+// Copyright (C) 2022 Steven Gotthardt <gotthardt@gmail.com>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h" // CONFIG_SERIAL_BAUD
+
+#include "command.h" // DECL_CONSTANT_STR
+#include "internal.h"
+#include "sched.h" // DECL_INIT
+#include "generic/serial_irq.h"
+#include "generic/armcm_boot.h"
+
+#include "hc32f460_usart.h"
+#include "hc32f460_gpio.h"
+#include "hc32f460_pwc.h"
+
+
+#define USART_BAUDRATE (CONFIG_SERIAL_BAUD)
+
+
+// Aquila 1.0.3 pins for TX, RX to CH304 on PA15 and PA09
+// for the LCD connector: TX, RX on PC00 and PC01
+#if CONFIG_HC32F460_SERIAL_PA15_PA9
+ DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA15,PA9");
+ #define USART_RX_PORT (PortA)
+ #define USART_RX_PIN (Pin15)
+ #define USART_TX_PORT (PortA)
+ #define USART_TX_PIN (Pin09)
+
+#elif CONFIG_HC32F460_SERIAL_PC0_PC1
+ DECL_CONSTANT_STR("RESERVE_PINS_serial", "PC0,PC1");
+ #define USART_RX_PORT (PortC)
+ #define USART_RX_PIN (Pin00)
+ #define USART_TX_PORT (PortC)
+ #define USART_TX_PIN (Pin01)
+
+#elif CONFIG_HC32F460_SERIAL_PA3_PA2
+ DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA3,PA2");
+ #define USART_RX_PORT (PortA)
+ #define USART_RX_PIN (Pin03)
+ #define USART_TX_PORT (PortA)
+ #define USART_TX_PIN (Pin02)
+
+#elif CONFIG_HC32F460_SERIAL_PA7_PA8
+ DECL_CONSTANT_STR("RESERVE_PINS_serial", "PA7,PA8");
+ #define USART_RX_PORT (PortA)
+ #define USART_RX_PIN (Pin07)
+ #define USART_TX_PORT (PortA)
+ #define USART_TX_PIN (Pin08)
+#endif
+
+// use USART 1 for serial connection
+#define USARTx M4_USART1
+#define USART_ENABLE (PWC_FCG1_PERIPH_USART1 | PWC_FCG1_PERIPH_USART2 | \
+ PWC_FCG1_PERIPH_USART3 | PWC_FCG1_PERIPH_USART4)
+
+#define USART_RX_FUNC Func_Usart1_Rx
+#define USART_TX_FUNC Func_Usart1_Tx
+#define USART_RI_NUM INT_USART1_RI
+#define USART_TI_NUM INT_USART1_TI
+#define USART_EI_NUM INT_USART1_EI
+#define USART_TCI_NUM INT_USART1_TCI
+
+
+void
+serialError(void)
+{
+ if (Set == USART_GetStatus(USARTx, UsartFrameErr))
+ {
+ USART_ClearStatus(USARTx, UsartFrameErr);
+
+ // use it anyway
+ serial_rx_byte(USARTx->DR_f.RDR);
+ }
+
+ if (Set == USART_GetStatus(USARTx, UsartOverrunErr))
+ {
+ USART_ClearStatus(USARTx, UsartOverrunErr);
+ }
+}
+DECL_ARMCM_IRQ(serialError, Int001_IRQn);
+
+
+void
+serialTxComplete(void)
+{
+ USART_FuncCmd(USARTx, UsartTx, Disable);
+ USART_FuncCmd(USARTx, UsartTxCmpltInt, Disable);
+}
+DECL_ARMCM_IRQ(serialTxComplete, Int003_IRQn);
+
+
+void
+serialRx(void)
+{
+ uint16_t data = USART_RecData(USARTx);
+
+ // call to klipper generic/serial_irq function
+ serial_rx_byte(data);
+}
+DECL_ARMCM_IRQ(serialRx, Int000_IRQn);
+
+
+void
+serialTxEmpty(void)
+{
+ uint8_t data2send;
+
+ // use helper from generic - zero means byte ready
+ if (!serial_get_tx_byte(&data2send))
+ {
+ //USARTx->DR_f.TDR = data2send;
+ USART_SendData(USARTx, data2send);
+ }
+ else
+ {
+ // no more data - stop the interrupt
+ USART_FuncCmd(USARTx, UsartTxCmpltInt, Enable);
+ USART_FuncCmd(USARTx, UsartTxEmptyInt, Disable);
+ }
+}
+DECL_ARMCM_IRQ(serialTxEmpty, Int002_IRQn);
+
+
+// called by generic framework
+void
+serial_enable_tx_irq(void)
+{
+ /* Enable TX && TX empty interrupt */
+ USART_FuncCmd(USARTx, UsartTxAndTxEmptyInt, Enable);
+}
+
+
+void
+serial_init(void)
+{
+ const stc_usart_uart_init_t stcInitCfg = {
+ UsartIntClkCkNoOutput,
+ UsartClkDiv_1,
+ UsartDataBits8,
+ UsartDataLsbFirst,
+ UsartOneStopBit,
+ UsartParityNone,
+ UsartSampleBit16,
+ UsartStartBitFallEdge,
+ UsartRtsEnable,
+ };
+
+ // Function Clock Control - USART enable (sets bit to a 0)
+ PWC_Fcg1PeriphClockCmd(USART_ENABLE, Enable);
+
+ /* Initialize port pins for USART IO - Disable = NO subfunction */
+ PORT_SetFunc(USART_RX_PORT, USART_RX_PIN, USART_RX_FUNC, Disable);
+ PORT_SetFunc(USART_TX_PORT, USART_TX_PIN, USART_TX_FUNC, Disable);
+
+ /* Initialize UART */
+ USART_UART_Init(USARTx, &stcInitCfg);
+
+ /* Set baudrate */
+ USART_SetBaudrate(USARTx, USART_BAUDRATE);
+
+ /* A word on interrupts in HC32F460
+ In other vendors (STM) the irqs are assigned names in the vector list
+ eg: USART1_IRQn but HC32F460 has numbered IRQs: IRQ000_IRQn IRQ143_IRQn
+ Using INT_USART1_RI from hc32f460.h put in to IRQn->INTSEL
+ if n = 5 then the USART1_RI iterrupt will be at IRQ005_IRQn
+ For the specific case of each USART there are 5 separate irqs to map
+ */
+
+ /* Set USART RX IRQ */
+ IrqRegistration(USART_RI_NUM, Int000_IRQn);
+
+ /* Set USART err */
+ IrqRegistration(USART_EI_NUM, Int001_IRQn);
+
+ /* Set USART TX IRQ */
+ IrqRegistration(USART_TI_NUM, Int002_IRQn);
+
+ /* Set USART TX complete IRQ */
+ IrqRegistration(USART_TCI_NUM, Int003_IRQn);
+
+ /* Enable RX && RX interrupt function */
+ USART_FuncCmd(USARTx, UsartRx, Enable);
+ USART_FuncCmd(USARTx, UsartRxInt, Enable);
+}
+
+DECL_INIT(serial_init);