diff --git a/ch32fun/ch32fun.c b/ch32fun/ch32fun.c index b6280864..a33d7a82 100644 --- a/ch32fun/ch32fun.c +++ b/ch32fun/ch32fun.c @@ -966,6 +966,24 @@ void USBPD_WKUP_IRQHandler( void ) __attribute__((section(".text.vector_handler void TIM2_CC_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); void TIM2_TRG_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); void TIM2_BRK_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +// CH59x +void TMR0_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void GPIOA_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void GPIOB_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void SPI0_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void USB_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void TMR1_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void TMR2_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void UART0_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void UART1_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void ADC_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void I2C_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void PWMX_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void TMR3_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void UART2_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void UART3_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); +void WDOG_BAT_IRQHandler( void ) __attribute__((section(".text.vector_handler"))) __attribute((weak,alias("DefaultIRQHandler"))) __attribute__((used)); + void InterruptVector() __attribute__((naked)) __attribute((section(".init"))) __attribute((weak,alias("InterruptVectorDefault"))) __attribute((naked)); @@ -1060,7 +1078,7 @@ asm volatile( " mret\n" : : [main]"r"(main) ); } -#elif defined(CH32V10x) || defined(CH32V20x) || defined(CH32V30x) +#elif defined(CH32V10x) || defined(CH32V20x) || defined(CH32V30x) || defined(CH59x) void handle_reset( void ) { @@ -1472,7 +1490,7 @@ void DelaySysTick( uint32_t n ) #ifdef CH32V003 uint32_t targend = SysTick->CNT + n; while( ((int32_t)( SysTick->CNT - targend )) < 0 ); -#elif defined(CH32V20x) || defined(CH32V30x) +#elif defined(CH32V20x) || defined(CH32V30x) || defined(CH59x) uint64_t targend = SysTick->CNT + n; while( ((int64_t)( SysTick->CNT - targend )) < 0 ); #elif defined(CH32V10x) || defined(CH32X03x) @@ -1541,7 +1559,36 @@ void SystemInit( void ) #endif #endif -#if defined(FUNCONF_USE_HSI) && FUNCONF_USE_HSI +#if defined(CH59x) // has no HSI + // SYS_SAFE_ACCESS for writing RWA and WA registers + #define SYS_SAFE_ACCESS_ENABLE { R8_SAFE_ACCESS_SIG = SAFE_ACCESS_SIG1; R8_SAFE_ACCESS_SIG = SAFE_ACCESS_SIG2; ADD_N_NOPS(2); } + #define SYS_SAFE_ACCESS_DISABLE { R8_SAFE_ACCESS_SIG = SAFE_ACCESS_SIG0; ADD_N_NOPS(2); } +#ifndef CLK_SOURCE_CH59X + #define CLK_SOURCE_CH59X CLK_SOURCE_PLL_60MHz +#endif + SYS_SAFE_ACCESS_ENABLE + R8_PLL_CONFIG &= ~(1 << 5); + SYS_CLKTypeDef sc = CLK_SOURCE_CH59X; + if(sc & 0x20) // HSE div + { + R32_CLK_SYS_CFG = (0 << 6) | (sc & 0x1f) | RB_TX_32M_PWR_EN | RB_PLL_PWR_EN; + ADD_N_NOPS(4); + R8_FLASH_CFG = 0X51; + } + + else if(sc & 0x40) // PLL div + { + R32_CLK_SYS_CFG = (1 << 6) | (sc & 0x1f) | RB_TX_32M_PWR_EN | RB_PLL_PWR_EN; + ADD_N_NOPS(4); + R8_FLASH_CFG = 0X52; + } + else + { + R32_CLK_SYS_CFG |= RB_CLK_SYS_MOD; + } + R8_PLL_CONFIG |= 1 << 7; + SYS_SAFE_ACCESS_DISABLE +#elif defined(FUNCONF_USE_HSI) && FUNCONF_USE_HSI #if defined(CH32V30x) || defined(CH32V20x) || defined(CH32V10x) EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; #endif @@ -1600,9 +1647,11 @@ void SystemInit( void ) #endif #endif +#if !defined(CH59x) RCC->INTR = 0x009F0000; // Clear PLL, CSSC, HSE, HSI and LSI ready flags. +#endif -#if defined(FUNCONF_USE_PLL) && FUNCONF_USE_PLL +#if defined(FUNCONF_USE_PLL) && FUNCONF_USE_PLL && !defined(CH59x) while((RCC->CTLR & RCC_PLLRDY) == 0); // Wait till PLL is ready uint32_t tmp32 = RCC->CFGR0 & ~(0x03); // clr the SW RCC->CFGR0 = tmp32 | RCC_SW_PLL; // Select PLL as system clock source @@ -1617,6 +1666,7 @@ void SystemInit( void ) #endif } +#if defined(FUNCONF_INIT_ANALOG) && FUNCONF_INIT_ANALOG void funAnalogInit( void ) { //RCC->CFGR0 &= ~(0x1F<<11); // Assume ADCPRE = 0 @@ -1655,6 +1705,7 @@ int funAnalogRead( int nAnalogNumber ) // get result return ADC1->RDATAR; } +#endif // C++ Support diff --git a/ch32fun/ch32fun.h b/ch32fun/ch32fun.h index 3dc94095..c326b51b 100644 --- a/ch32fun/ch32fun.h +++ b/ch32fun/ch32fun.h @@ -128,6 +128,10 @@ #define FUNCONF_DEBUG_HARDFAULT 1 #endif +#if !defined( FUNCONF_INIT_ANALOG ) + #define FUNCONF_INIT_ANALOG 1 +#endif + #if defined( CH32X03x ) && FUNCONF_USE_PLL #error No PLL on the X03x #endif @@ -160,6 +164,8 @@ #endif #elif defined(CH32V30x) #define HSE_VALUE (8000000) + #elif defined(CH59x) + #define HSE_VALUE (32000000) #endif #endif @@ -202,7 +208,12 @@ #endif #ifndef FUNCONF_SYSTEM_CORE_CLOCK - #if defined(FUNCONF_USE_HSI) && FUNCONF_USE_HSI + #if defined(CH59x) // no PLL multiplier, but a divider from the 480 MHz clock + #define FUNCONF_SYSTEM_CORE_CLOCK 60000000 // default in ch32fun.c using CLK_SOURCE_PLL_60MHz + #if defined(CLK_SOURCE_CH59X) + #error Must define FUNCONF_SYSTEM_CORE_CLOCK too if CLK_SOURCE_CH59X is defined + #endif + #elif defined(FUNCONF_USE_HSI) && FUNCONF_USE_HSI #define FUNCONF_SYSTEM_CORE_CLOCK ((HSI_VALUE)*(FUNCONF_PLL_MULTIPLIER)) #elif defined(FUNCONF_USE_HSE) && FUNCONF_USE_HSE #define FUNCONF_SYSTEM_CORE_CLOCK ((HSE_VALUE)*(FUNCONF_PLL_MULTIPLIER)) @@ -348,6 +359,8 @@ typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; #include "ch32v20xhw.h" #elif defined( CH32V30x ) #include "ch32v30xhw.h" +#elif defined( CH59x ) + #include "ch59xhw.h" #endif #if defined(__riscv) || defined(__riscv__) || defined( CH32V003FUN_BASE ) @@ -817,11 +830,49 @@ extern "C" { // and take two cycles, so you typically would use 0, 2, 4, etc. #define ADD_N_NOPS( n ) asm volatile( ".rept " #n "\nc.nop\n.endr" ); +#define FUN_HIGH 0x1 +#define FUN_LOW 0x0 +#if defined(CH59x) +#define OFFSET_FOR_GPIOB(pin) (((pin & PB) >> 31) * (&R32_PB_PIN - &R32_PA_PIN)) // 0 if GPIOA, 0x20 if GPIOB +#define GPIO_ResetBits(pin) (*(&R32_PA_CLR + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB)) +#define GPIO_SetBits(pin) (*(&R32_PA_OUT + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB)) +#define GPIO_InverseBits(pin) (*(&R32_PA_OUT + OFFSET_FOR_GPIOB(pin)) ^= (pin & ~PB)) +#define GPIO_ReadPortPin(pin) (*(&R32_PA_PIN + OFFSET_FOR_GPIOB(pin)) & (pin & ~PB)) +#define funDigitalRead(pin) GPIO_ReadPortPin(pin) +#define funDigitalWrite( pin, value ) { if((value)==FUN_HIGH){GPIO_SetBits(pin);} else if((value)==FUN_LOW){GPIO_ResetBits(pin);} } + +RV_STATIC_INLINE void funPinMode(u32 pin, GPIOModeTypeDef mode) +{ + switch(mode) { + case GPIO_ModeIN_Floating: + *(&R32_PA_PD_DRV + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + *(&R32_PA_PU + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + *(&R32_PA_DIR + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + break; + case GPIO_ModeIN_PU: + *(&R32_PA_PD_DRV + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + *(&R32_PA_PU + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB); + *(&R32_PA_DIR + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + break; + case GPIO_ModeIN_PD: + *(&R32_PA_PD_DRV + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB); + *(&R32_PA_PU + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + *(&R32_PA_DIR + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + break; + case GPIO_ModeOut_PP_5mA: + *(&R32_PA_PD_DRV + OFFSET_FOR_GPIOB(pin)) &= ~(pin & ~PB); + *(&R32_PA_DIR + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB); + break; + case GPIO_ModeOut_PP_20mA: + *(&R32_PA_PD_DRV + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB); + *(&R32_PA_DIR + OFFSET_FOR_GPIOB(pin)) |= (pin & ~PB); + break; + } +} +#else // Arduino-like GPIO Functionality #define GpioOf( pin ) ((GPIO_TypeDef *)(GPIOA_BASE + 0x400 * ((pin)>>4))) -#define FUN_HIGH 0x1 -#define FUN_LOW 0x0 #define FUN_OUTPUT (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP) #define FUN_INPUT (GPIO_CNF_IN_FLOATING) @@ -846,6 +897,7 @@ extern "C" { #define funGpioInitC() { RCC->APB2PCENR |= ( RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOC ); } #define funGpioInitD() { RCC->APB2PCENR |= ( RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOD ); } #define funDigitalRead( pin ) ((int)((GpioOf(pin)->INDR >> ((pin)&0xf)) & 1)) +#endif #define ANALOG_0 0 diff --git a/ch32fun/ch32fun.ld b/ch32fun/ch32fun.ld index 029a018a..7dd34a08 100644 --- a/ch32fun/ch32fun.ld +++ b/ch32fun/ch32fun.ld @@ -65,9 +65,20 @@ MEMORY FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 32K RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 6K #elif TARGET_MCU_LD == 7 - /* CH32V005, CH32V006, CH32V007 */ - FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 62K - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 8K + /* CH32V005, CH32V006, CH32V007 */ + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 62K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 8K +#elif TARGET_MCU_LD == 8 + /* CH591/2 */ + #if MCU_PACKAGE == 1 + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 192K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 24K + #elif MCU_PACKAGE == 2 + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 448K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 24K + #else + #error "Unknown MCU package" +#endif #else #error "Unknown MCU target" #endif diff --git a/ch32fun/ch32fun.mk b/ch32fun/ch32fun.mk index eb76e650..e5b90ccb 100644 --- a/ch32fun/ch32fun.mk +++ b/ch32fun/ch32fun.mk @@ -183,6 +183,27 @@ else endif TARGET_MCU_LD:=3 + else ifeq ($(findstring CH59,$(TARGET_MCU)),CH59) # CH592 1 + TARGET_MCU_PACKAGE?=CH592F + CFLAGS_ARCH+=-march=rv32imac \ + -mabi=ilp32 \ + -DCH59x=1 + + # MCU Flash/RAM split + ifeq ($(findstring 591, $(TARGET_MCU_PACKAGE)), 591) + MCU_PACKAGE:=1 + else ifeq ($(findstring 592, $(TARGET_MCU_PACKAGE)), 592) + MCU_PACKAGE:=2 + endif + + # Package + ifeq ($(findstring D, $(TARGET_MCU_PACKAGE)), D) + CFLAGS+=-DCH59xD + else ifeq ($(findstring F, $(TARGET_MCU_PACKAGE)), F) + CFLAGS+=-DCH59xF + endif + + TARGET_MCU_LD:=8 else ERROR:=$(error Unknown MCU $(TARGET_MCU)) endif diff --git a/ch32fun/ch59xhw.h b/ch32fun/ch59xhw.h new file mode 100644 index 00000000..42ecc7c6 --- /dev/null +++ b/ch32fun/ch59xhw.h @@ -0,0 +1,300 @@ +#ifndef TODO_HARDWARE_H +#define TODO_HARDWARE_H + +#include "ch32fun.h" + +#ifndef __ASSEMBLER__ // Things before this can be used in assembly. + +#ifdef __cplusplus +extern "C" { +#endif + +/* Interrupt Number Definition, according to the selected device */ +typedef enum IRQn +{ + /****** RISC-V Processor Exceptions Numbers *******************************************************/ + NonMaskableInt_IRQn = 2, /* 2 Non Maskable Interrupt */ + EXC_IRQn = 3, /* 3 Exception Interrupt */ + Ecall_M_Mode_IRQn = 5, /* 5 Ecall M Mode Interrupt */ + Ecall_U_Mode_IRQn = 8, /* 8 Ecall U Mode Interrupt */ + Break_Point_IRQn = 9, /* 9 Break Point Interrupt */ + SysTicK_IRQn = 12, /* 12 System timer Interrupt */ + Software_IRQn = 14, /* 14 software Interrupt */ + + /****** RISC-V specific Interrupt Numbers *********************************************************/ + TMR0_IRQn = 16, /* 0: TMR0 */ + GPIOA_IRQn = 17, /* GPIOA */ + GPIOB_IRQn = 18, /* GPIOB */ + SPI0_IRQn = 19, /* SPI0 */ + BB_IRQn = 20, /* BLEB */ + LLE_IRQn = 21, /* BLEL */ + USB_IRQn = 22, /* USB */ + TMR1_IRQn = 24, /* TMR1 */ + TMR2_IRQn = 25, /* TMR2 */ + UART0_IRQn = 26, /* UART0 */ + UART1_IRQn = 27, /* UART1 */ + RTC_IRQn = 28, /* RTC */ + ADC_IRQn = 29, /* ADC */ + I2C_IRQn = 30, /* I2C */ + PWMX_IRQn = 31, /* PWMX */ + TMR3_IRQn = 32, /* TMR3 */ + UART2_IRQn = 33, /* UART2 */ + UART3_IRQn = 34, /* UART3 */ + WDOG_BAT_IRQn = 35, /* WDOG_BAT */ +} IRQn_Type; + +#define BASE_VECTOR "\n\ + .balign 2\n\ + .option push;\n\ + .option norvc;\n\ + j handle_reset\n\ + .word 0\n\ + .word NMI_Handler /* NMI Handler */\n\ + .word HardFault_Handler /* Hard Fault Handler */\n\ + .word 0xF5F9BDA9\n\ + .word Ecall_M_Mode_Handler /* 5 */\n\ + .word 0\n\ + .word 0\n\ + .word Ecall_U_Mode_Handler /* 8 */\n\ + .word Break_Point_Handler /* 9 */\n\ + .word 0\n\ + .word 0\n\ + .word SysTick_Handler /* SysTick Handler */\n\ + .word 0\n\ + .word SW_Handler /* SW Handler */\n\ + .word 0\n\ + /* External Interrupts */\n\ + .word TMR0_IRQHandler /* 0: TMR0 */\n\ + .word GPIOA_IRQHandler /* GPIOA */\n\ + .word GPIOB_IRQHandler /* GPIOB */\n\ + .word SPI0_IRQHandler /* SPI0 */\n\ + .word BB_IRQHandler /* BLEB */\n\ + .word LLE_IRQHandler /* BLEL */\n\ + .word USB_IRQHandler /* USB */\n\ + .word 0\n\ + .word TMR1_IRQHandler /* TMR1 */\n\ + .word TMR2_IRQHandler /* TMR2 */\n\ + .word UART0_IRQHandler /* UART0 */\n\ + .word UART1_IRQHandler /* UART1 */\n\ + .word RTC_IRQHandler /* RTC */\n\ + .word ADC_IRQHandler /* ADC */\n\ + .word I2C_IRQHandler /* I2C */\n\ + .word PWMX_IRQHandler /* PWMX */\n\ + .word TMR3_IRQHandler /* TMR3 */\n\ + .word UART2_IRQHandler /* UART2 */\n\ + .word UART3_IRQHandler /* UART3 */\n\ + .word WDOG_BAT_IRQHandler /* WDOG_BAT */\n" + +#define DEFAULT_INTERRUPT_VECTOR_CONTENTS BASE_VECTOR "\n.option pop;\n" + +/* memory mapped structure for SysTick */ +typedef struct +{ + __IO uint32_t CTLR; + __IO uint32_t SR; + __IO uint64_t CNT; + __IO uint64_t CMP; +} SysTick_Type; + + +/* memory mapped structure for Program Fast Interrupt Controller (PFIC) */ +typedef struct +{ + __I uint32_t ISR[8]; // 0 + __I uint32_t IPR[8]; // 20H + __IO uint32_t ITHRESDR; // 40H + uint8_t RESERVED[4]; // 44H + __O uint32_t CFGR; // 48H + __I uint32_t GISR; // 4CH + __IO uint8_t VTFIDR[4]; // 50H + uint8_t RESERVED0[0x0C]; // 54H + __IO uint32_t VTFADDR[4]; // 60H + uint8_t RESERVED1[0x90]; // 70H + __O uint32_t IENR[8]; // 100H + uint8_t RESERVED2[0x60]; // 120H + __O uint32_t IRER[8]; // 180H + uint8_t RESERVED3[0x60]; // 1A0H + __O uint32_t IPSR[8]; // 200H + uint8_t RESERVED4[0x60]; // 220H + __O uint32_t IPRR[8]; // 280H + uint8_t RESERVED5[0x60]; // 2A0H + __IO uint32_t IACTR[8]; // 300H + uint8_t RESERVED6[0xE0]; // 320H + __IO uint8_t IPRIOR[256]; // 400H + uint8_t RESERVED7[0x810]; // 500H + __IO uint32_t SCTLR; // D10H +} PFIC_Type; +#endif /* __ASSEMBLER__*/ + +#ifdef __ASSEMBLER__ +#define CORE_PERIPH_BASE (0xE0000000) /* System peripherals base address in the alias region */ +#else +#define CORE_PERIPH_BASE ((uint32_t)(0xE0000000)) +#endif /* __ASSEMBLER__*/ + +#define PFIC_BASE (CORE_PERIPH_BASE + 0xE000) +#define SysTick_BASE (CORE_PERIPH_BASE + 0xF000) + +#define PFIC ((PFIC_Type *) PFIC_BASE) +#define NVIC PFIC +#define NVIC_KEY1 ((uint32_t)0xFA050000) +#define NVIC_KEY2 ((uint32_t)0xBCAF0000) +#define NVIC_KEY3 ((uint32_t)0xBEEF0000) + +#define SysTick ((SysTick_Type *) SysTick_BASE) +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFFFFFFFFFFF) +#define SysTick_CTLR_SWIE (1 << 31) +#define SysTick_CTLR_INIT (1 << 5) +#define SysTick_CTLR_MODE (1 << 4) +#define SysTick_CTLR_STRE (1 << 3) +#define SysTick_CTLR_STCLK (1 << 2) +#define SysTick_CTLR_STIE (1 << 1) +#define SysTick_CTLR_STE (1 << 0) +#define SysTick_SR_CNTIF (1 << 0) + +typedef enum +{ + CLK_SOURCE_LSI = 0x00, + CLK_SOURCE_LSE, + + CLK_SOURCE_HSE_16MHz = (0x20 | 2), + CLK_SOURCE_HSE_8MHz = (0x20 | 4), + CLK_SOURCE_HSE_6_4MHz = (0x20 | 5), + CLK_SOURCE_HSE_4MHz = (0x20 | 8), + + CLK_SOURCE_PLL_60MHz = (0x40 | 8), + CLK_SOURCE_PLL_48MHz = (0x40 | 10), + CLK_SOURCE_PLL_32MHz = (0x40 | 15), + CLK_SOURCE_PLL_24MHz = (0x40 | 20), +} SYS_CLKTypeDef; + +// For debug writing to the debug interface. +#define DMDATA0 ((vu32*)0xe0000380) +#define DMDATA1 ((vu32*)0xe0000384) +#define DMSTATUS_SENTINEL ((vu32*)0xe0000388)// Reads as 0x00000000 if debugger is attached. + +/* System: clock configuration register */ +#define R32_CLK_SYS_CFG (*((vu32*)0x40001008)) // RWA, system clock configuration, SAM +#define RB_CLK_PLL_DIV 0x1F // RWA, output clock divider from PLL or CK32M +#define RB_CLK_SYS_MOD 0xC0 // RWA, system clock source mode: 00=divided from 32MHz, 01=divided from PLL-480MHz, 10=directly from 32MHz, 11=directly from 32KHz +#define RB_TX_32M_PWR_EN 0x40000 // RWA, extern 32MHz HSE power contorl +#define RB_XT_FORCE_EN 0x80000 // RWA, system clock control in Halt mode +#define RB_PLL_PWR_EN 0x100000 // RWA, PLL power control + +/* System: safe accessing register */ +#define R32_SAFE_ACCESS (*((vu32*)0x40001040)) // RW, safe accessing +#define R8_SAFE_ACCESS_SIG (*((vu8*)0x40001040)) // WO, safe accessing sign register, must write SAFE_ACCESS_SIG1 then SAFE_ACCESS_SIG2 to enter safe accessing mode +#define RB_SAFE_ACC_MODE 0x03 // RO, current safe accessing mode: 11=safe/unlocked (SAM), other=locked (00..01..10..11) +#define RB_SAFE_ACC_ACT 0x08 // RO, indicate safe accessing status now: 0=locked, read only, 1=safe/unlocked (SAM), write enabled +#define RB_SAFE_ACC_TIMER 0x70 // RO, safe accessing timer bit mask (16*clock number) +#define SAFE_ACCESS_SIG1 0x57 // WO: safe accessing sign value step 1 +#define SAFE_ACCESS_SIG2 0xA8 // WO: safe accessing sign value step 2 +#define SAFE_ACCESS_SIG0 0x00 // WO: safe accessing sign value for disable +#define R8_CHIP_ID (*((vu8*)0x40001041)) // RF, chip ID register, always is ID_CH59* + +/*System: Miscellaneous Control register */ +#define R32_MISC_CTRL (*((vu32*)0x40001048)) // RWA, miscellaneous control register +#define R8_PLL_CONFIG (*((vu8*)0x4000104B)) // RWA, PLL configuration control, SAM +#define RB_PLL_CFG_DAT 0x7F // RWA, PLL configuration control, SAM + +/* System: Flash ROM control register */ +#define R32_FLASH_DATA (*((vu32*)0x40001800)) // RO/WO, flash ROM data +#define R32_FLASH_CONTROL (*((vu32*)0x40001804)) // RW, flash ROM control +#define R8_FLASH_DATA (*((vu8*)0x40001804)) // RO/WO, flash ROM data buffer +#define R8_FLASH_CTRL (*((vu8*)0x40001806)) // RW, flash ROM access control +#define R8_FLASH_CFG (*((vu8*)0x40001807)) // RW, flash ROM access config, SAM + + +/* GPIO PA register */ +#define R32_PA_DIR (*((vu32*)0x400010A0)) // RW, GPIO PA I/O direction: 0=in, 1=out +#define R32_PA_PIN (*((vu32*)0x400010A4)) // RO, GPIO PA input +#define R32_PA_OUT (*((vu32*)0x400010A8)) // RW, GPIO PA output +#define R32_PA_CLR (*((vu32*)0x400010AC)) // WZ, GPIO PA clear output: 0=keep, 1=clear +#define R32_PA_PU (*((vu32*)0x400010B0)) // RW, GPIO PA pullup resistance enable +#define R32_PA_PD_DRV (*((vu32*)0x400010B4)) // RW, PA pulldown for input or PA driving capability for output + +/* GPIO PB register */ +#define R32_PB_DIR (*((vu32*)0x400010C0)) // RW, GPIO PB I/O direction: 0=in, 1=out +#define R32_PB_PIN (*((vu32*)0x400010C4)) // RO, GPIO PB input +#define R32_PB_OUT (*((vu32*)0x400010C8)) // RW, GPIO PB output +#define R32_PB_CLR (*((vu32*)0x400010CC)) // WZ, GPIO PB clear output: 0=keep, 1=clear +#define R32_PB_PU (*((vu32*)0x400010D0)) // RW, GPIO PB pullup resistance enable +#define R32_PB_PD_DRV (*((vu32*)0x400010D4)) // RW, PB pulldown for input or PB driving capability for output + +#define PA0 (0x00000001) /*!< Pin 0 selected */ +#define PA1 (0x00000002) /*!< Pin 1 selected */ +#define PA2 (0x00000004) /*!< Pin 2 selected */ +#define PA3 (0x00000008) /*!< Pin 3 selected */ +#define PA4 (0x00000010) /*!< Pin 4 selected */ +#define PA5 (0x00000020) /*!< Pin 5 selected */ +#define PA6 (0x00000040) /*!< Pin 6 selected */ +#define PA7 (0x00000080) /*!< Pin 7 selected */ +#define PA8 (0x00000100) /*!< Pin 8 selected */ +#define PA9 (0x00000200) /*!< Pin 9 selected */ +#define PA10 (0x00000400) /*!< Pin 10 selected */ +#define PA11 (0x00000800) /*!< Pin 11 selected */ +#define PA12 (0x00001000) /*!< Pin 12 selected */ +#define PA13 (0x00002000) /*!< Pin 13 selected */ +#define PA14 (0x00004000) /*!< Pin 14 selected */ +#define PA15 (0x00008000) /*!< Pin 15 selected */ + +#define PB (0x80000000) /* Bit mask to indicate bank B */ +#define PB0 (0x80000001) /*!< Pin 0 selected */ +#define PB1 (0x80000002) /*!< Pin 1 selected */ +#define PB2 (0x80000004) /*!< Pin 2 selected */ +#define PB3 (0x80000008) /*!< Pin 3 selected */ +#define PB4 (0x80000010) /*!< Pin 4 selected */ +#define PB5 (0x80000020) /*!< Pin 5 selected */ +#define PB6 (0x80000040) /*!< Pin 6 selected */ +#define PB7 (0x80000080) /*!< Pin 7 selected */ +#define PB8 (0x80000100) /*!< Pin 8 selected */ +#define PB9 (0x80000200) /*!< Pin 9 selected */ +#define PB10 (0x80000400) /*!< Pin 10 selected */ +#define PB11 (0x80000800) /*!< Pin 11 selected */ +#define PB12 (0x80001000) /*!< Pin 12 selected */ +#define PB13 (0x80002000) /*!< Pin 13 selected */ +#define PB14 (0x80004000) /*!< Pin 14 selected */ +#define PB15 (0x80008000) /*!< Pin 15 selected */ +#define PB16 (0x80010000) /*!< Pin 16 selected */ +#define PB17 (0x80020000) /*!< Pin 17 selected */ +#define PB18 (0x80040000) /*!< Pin 18 selected */ +#define PB19 (0x80080000) /*!< Pin 19 selected */ +#define PB20 (0x80100000) /*!< Pin 20 selected */ +#define PB21 (0x80200000) /*!< Pin 21 selected */ +#define PB22 (0x80400000) /*!< Pin 22 selected */ +#define PB23 (0x80800000) /*!< Pin 23 selected */ +#define P_All (0xFFFFFFFF) /*!< All pins selected */ + +typedef enum +{ + GPIO_ModeIN_Floating, + GPIO_ModeIN_PU, + GPIO_ModeIN_PD, + GPIO_ModeOut_PP_5mA, + GPIO_ModeOut_PP_20mA, +} GPIOModeTypeDef; + +/* General Purpose I/O */ +typedef enum +{ + GPIO_CFGLR_IN_FLOAT = GPIO_ModeIN_Floating, + GPIO_CFGLR_IN_PUPD = GPIO_ModeIN_PU, // is most common + GPIO_CFGLR_IN_PU = GPIO_ModeIN_PU, + GPIO_CFGLR_IN_PD = GPIO_ModeIN_PD, // to suppress the -Wswitch warning + GPIO_CFGLR_OUT_10Mhz_PP = GPIO_ModeOut_PP_20mA, + GPIO_CFGLR_OUT_2Mhz_PP = GPIO_ModeOut_PP_5mA, + GPIO_CFGLR_OUT_50Mhz_PP = GPIO_ModeOut_PP_20mA, +} GPIO_CFGLR_PIN_MODE_Typedef; + +#define HardFault_IRQn EXC_IRQn + +/* Standard Peripheral Library old definitions (maintained for legacy purpose) */ +#define HSI_Value HSI_VALUE +#define HSE_Value HSE_VALUE +#define HSEStartUp_TimeOut HSE_STARTUP_TIMEOUT + +#ifdef __cplusplus +} +#endif + +#endif // Header guard diff --git a/examples_ch59x/blink/Makefile b/examples_ch59x/blink/Makefile new file mode 100644 index 00000000..f91e0ef0 --- /dev/null +++ b/examples_ch59x/blink/Makefile @@ -0,0 +1,10 @@ +all : flash + +TARGET:=blink +TARGET_MCU:=CH592 +TARGET_MCU_PACKAGE:=CH592F + +include ../../ch32fun/ch32fun.mk + +flash : cv_flash +clean : cv_clean diff --git a/examples_ch59x/blink/blink.c b/examples_ch59x/blink/blink.c new file mode 100644 index 00000000..75b1ea87 --- /dev/null +++ b/examples_ch59x/blink/blink.c @@ -0,0 +1,17 @@ +#include "ch32fun.h" +#include + +int main() +{ + SystemInit(); + + funPinMode( PA8, GPIO_CFGLR_OUT_2Mhz_PP ); + + while(1) + { + funDigitalWrite( PA8, FUN_LOW ); // Turn on LED + Delay_Ms( 33 ); + funDigitalWrite( PA8, FUN_HIGH ); // Turn off LED + Delay_Ms( 300 ); + } +} diff --git a/examples_ch59x/blink/funconfig.h b/examples_ch59x/blink/funconfig.h new file mode 100644 index 00000000..31dec37c --- /dev/null +++ b/examples_ch59x/blink/funconfig.h @@ -0,0 +1,14 @@ +#ifndef _FUNCONFIG_H +#define _FUNCONFIG_H + +#define FUNCONF_USE_HSI 0 // CH592 does not have HSI +#define FUNCONF_USE_HSE 1 +#define CLK_SOURCE_CH59X CLK_SOURCE_PLL_60MHz // default so not really needed +#define FUNCONF_SYSTEM_CORE_CLOCK 60 * 1000 * 1000 // keep in line with CLK_SOURCE_CH59X + +#define FUNCONF_DEBUG_HARDFAULT 0 +#define FUNCONF_USE_CLK_SEC 0 +#define FUNCONF_USE_DEBUGPRINTF 0 // saves 16 bytes, enable / remove if you want printf over swio +#define FUNCONF_INIT_ANALOG 0 // ADC is not implemented yet + +#endif diff --git a/examples_ch59x/debugprintfdemo/Makefile b/examples_ch59x/debugprintfdemo/Makefile new file mode 100644 index 00000000..04239d39 --- /dev/null +++ b/examples_ch59x/debugprintfdemo/Makefile @@ -0,0 +1,10 @@ +all : flash + +TARGET:=debugprintfdemo +TARGET_MCU:=CH592 +TARGET_MCU_PACKAGE:=CH592F + +include ../../ch32fun/ch32fun.mk + +flash : cv_flash +clean : cv_clean diff --git a/examples_ch59x/debugprintfdemo/debugprintfdemo.c b/examples_ch59x/debugprintfdemo/debugprintfdemo.c new file mode 100644 index 00000000..9ae474f1 --- /dev/null +++ b/examples_ch59x/debugprintfdemo/debugprintfdemo.c @@ -0,0 +1,34 @@ +/* Small example showing how to use the SWIO programming pin to + do printf through the debug interface */ + +#include "ch32fun.h" +#include + +uint32_t count; + +int last = 0; +void handle_debug_input( int numbytes, uint8_t * data ) +{ + last = data[0]; + count += numbytes; +} + +int main() +{ + SystemInit(); + + funPinMode( PA8, GPIO_CFGLR_OUT_10Mhz_PP ); + + while(1) + { + funDigitalWrite( PA8, FUN_LOW ); // Turn on LED + printf( "+%lu\n", count++ ); + Delay_Ms(100); + int i; + for( i = 0; i < 10000; i++ ) + poll_input(); + funDigitalWrite( PA8, FUN_HIGH ); // Turn off LED + printf( "-%lu[%c]\n", count++, last ); + Delay_Ms(100); + } +} diff --git a/examples_ch59x/debugprintfdemo/funconfig.h b/examples_ch59x/debugprintfdemo/funconfig.h new file mode 100644 index 00000000..3ee74d61 --- /dev/null +++ b/examples_ch59x/debugprintfdemo/funconfig.h @@ -0,0 +1,13 @@ +#ifndef _FUNCONFIG_H +#define _FUNCONFIG_H + +#define FUNCONF_USE_HSI 0 // CH592 does not have HSI +#define FUNCONF_USE_HSE 1 +#define CLK_SOURCE_CH59X CLK_SOURCE_PLL_60MHz // default so not really needed +#define FUNCONF_SYSTEM_CORE_CLOCK 60 * 1000 * 1000 // keep in line with CLK_SOURCE_CH59X + +#define FUNCONF_DEBUG_HARDFAULT 0 +#define FUNCONF_USE_CLK_SEC 0 +#define FUNCONF_INIT_ANALOG 0 // ADC is not implemented yet + +#endif