未验证 提交 c802fcdc 编写于 作者: E emuzit 提交者: GitHub

WCH CH569W-R0-1v0 evt board bsp port, first version (#6167)

WCH CH569W-R0-1v0 evt board bsp port, first version

dev/test under Ubuntu 20.04
toolchain from MounRiver_Studio_Community_Linux_x64_V120

tested drivers : SysTick, gpio, gpio interrupt, uart1 (RX interrupt, TX polling)

libcpu/risc-v/SConscript :
group includes rtconfig.CPU only if folder exists

libcpu/risc-v/common/cpuport.c/rt_hw_context_switch_interrupt() :
make it RT_WEAK for customization
上级 226b3e19
......@@ -5,4 +5,11 @@ config SOC_RISCV_SERIES_CH32V103
bool
select ARCH_RISCV
select SOC_RISCV_FAMILY_CH32
\ No newline at end of file
config SOC_FAMILY_CH56X
bool
select ARCH_RISCV
config SOC_SERIES_CH569
bool
select SOC_FAMILY_CH56X
from building import *
cwd = GetCurrentDir()
src = Split("""
ch56x_sys.c
swi_gcc.S
""")
if GetDepend('SOC_SERIES_CH569'):
src += ['ch56x_pfic.c']
if GetDepend('RT_USING_WDT'):
src += ['ch56x_wdt.c']
if GetDepend('RT_USING_HWTIMER'):
src += ['ch56x_timer.c']
if GetDepend('RT_USING_PIN'):
src += ['ch56x_gpio.c']
if GetDepend(['RT_USING_SERIAL', 'BSP_USING_UART']):
src += ['ch56x_uart.c']
path = [cwd]
group = DefineGroup('Drivers', src, depend=[''], CPPPATH=path)
Return('group')
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include <drivers/pin.h>
#include "ch56x_gpio.h"
#include "isr_sp.h"
struct port_info
{
uint32_t pin_mark;
struct gpio_px_regs *regbase;
};
static const struct port_info pin_ports[GPIO_PORTS] =
{
{GPIO_PA_PIN_MARK, (struct gpio_px_regs *)GPIO_REG_BASE_PA},
{GPIO_PB_PIN_MARK, (struct gpio_px_regs *)GPIO_REG_BASE_PB},
};
static struct rt_pin_irq_hdr pin_irq_hdr_table[8] =
{
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
{-1, 0, RT_NULL, RT_NULL},
};
#if defined(SOC_SERIES_CH569)
static int _gpio_pin_to_ibit(rt_base_t pin)
{
/* gpio ext interrupt 7-0 : {PB15,PB12,PB11,PB4,PB3,PA4,PA3,PA2}
* not time critical, use linear search
*/
switch (pin)
{
case GET_PIN(A, 2): return 0;
case GET_PIN(A, 3): return 1;
case GET_PIN(A, 4): return 2;
case GET_PIN(B, 3): return 3;
case GET_PIN(B, 4): return 4;
case GET_PIN(B, 11): return 5;
case GET_PIN(B, 12): return 6;
case GET_PIN(B, 15): return 7;
}
return -1;
}
#else
static int _gpio_pin_to_ibit(rt_base_t pin)
{
/* gpio ext interrupt 7-0 : {PB10,PB4,PA12,PA11,PA10,PA6,PA4,PA3}
* not time critical, use linear search
*/
switch (pin)
{
case GET_PIN(A, 3): return 0;
case GET_PIN(A, 4): return 1;
case GET_PIN(A, 6): return 2;
case GET_PIN(A, 10): return 3;
case GET_PIN(A, 11): return 4;
case GET_PIN(A, 12): return 5;
case GET_PIN(B, 4): return 6;
case GET_PIN(B, 10): return 7;
}
return -1;
}
#endif
static struct gpio_px_regs *_gpio_px_regbase(rt_base_t pin)
{
/* fixed linear mapping : 32 pins per port, for ports A,B,C,D...
*/
uint32_t port = (uint32_t)pin >> 5;
uint32_t bitpos = 1 << (pin & 0x1f);
if (port < GPIO_PORTS && (pin_ports[port].pin_mark & bitpos))
return pin_ports[port].regbase;
else
return RT_NULL;
}
static void gpio_pin_mode(struct rt_device *device, rt_base_t pin, rt_base_t mode)
{
volatile struct gpio_px_regs *px;
uint32_t port = (uint32_t)pin >> 5;
uint32_t bitpos = 1 << (pin & 0x1f);
if (port < GPIO_PORTS && (pin_ports[port].pin_mark & bitpos))
px = pin_ports[port].regbase;
else
return;
switch (mode)
{
case PIN_MODE_OUTPUT:
BITS_CLR(px->PD, bitpos);
BITS_SET(px->DIR, bitpos);
break;
case PIN_MODE_INPUT:
BITS_CLR(px->PU, bitpos);
BITS_CLR(px->PD, bitpos);
BITS_CLR(px->DIR, bitpos);
break;
case PIN_MODE_INPUT_PULLUP:
BITS_SET(px->PU, bitpos);
BITS_CLR(px->PD, bitpos);
BITS_CLR(px->DIR, bitpos);
break;
case PIN_MODE_INPUT_PULLDOWN:
BITS_CLR(px->PU, bitpos);
BITS_SET(px->PD, bitpos);
BITS_CLR(px->DIR, bitpos);
break;
case PIN_MODE_OUTPUT_OD:
BITS_SET(px->PD, bitpos);
BITS_SET(px->OUT, bitpos);
}
}
static void gpio_pin_write(struct rt_device *device, rt_base_t pin, rt_base_t value)
{
volatile struct gpio_px_regs *px;
uint32_t port = (uint32_t)pin >> 5;
uint32_t bitpos = 1 << (pin & 0x1f);
if (port < GPIO_PORTS && (pin_ports[port].pin_mark & bitpos))
px = pin_ports[port].regbase;
else
return;
if (value == 0)
BITS_CLR(px->OUT, bitpos);
else
BITS_SET(px->OUT, bitpos);
}
static int gpio_pin_read(struct rt_device *device, rt_base_t pin)
{
volatile struct gpio_px_regs *px;
uint32_t port = (uint32_t)pin >> 5;
uint32_t bitpos = 1 << (pin & 0x1f);
if (port < GPIO_PORTS && (pin_ports[port].pin_mark & bitpos))
px = pin_ports[port].regbase;
else
return PIN_LOW;
return (px->PIN & bitpos) ? PIN_HIGH : PIN_LOW;
}
static rt_base_t gpio_pin_get(const char *name)
{
int port, pin, sz, n;
/* pin name is in the form "PX.nn" (X: A,B,C,D...; nn: 0~31)
* fixed linear mapping : 32 pins per port, for ports A,B,C,D...
*/
sz = rt_strlen(name);
if ((sz == 4 || sz == 5) && name[0] == 'P' && name[2] == '.')
{
port = name[1] - 'A';
pin = name[3] - '0';
if (0 <= port && port < GPIO_PORTS && 0 <= pin && pin <= 9)
{
if (sz == 5)
{
n = name[4] - '0';
pin = (0 <= n && n <= 9) ? (pin * 10 + n) : 32;
}
if (pin < 32 && (pin_ports[port].pin_mark & (1 << pin)))
{
return port * 32 + pin;
}
}
}
return -1;
}
static rt_err_t gpio_pin_attach_irq(struct rt_device *device, rt_int32_t pin,
rt_uint32_t mode, void (*hdr)(void *args), void *args)
{
rt_base_t level;
int ibit;
switch (mode)
{
case PIN_IRQ_MODE_RISING:
case PIN_IRQ_MODE_FALLING:
case PIN_IRQ_MODE_HIGH_LEVEL:
case PIN_IRQ_MODE_LOW_LEVEL:
break;
case PIN_IRQ_MODE_RISING_FALLING:
/* hardware not supported */
default:
return -RT_EINVAL;
}
ibit = _gpio_pin_to_ibit(pin);
if (ibit < 0)
return -RT_EINVAL;
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_table[ibit].pin == pin &&
pin_irq_hdr_table[ibit].mode == mode &&
pin_irq_hdr_table[ibit].hdr == hdr &&
pin_irq_hdr_table[ibit].args == args)
{
rt_hw_interrupt_enable(level);
return RT_EOK;
}
if (pin_irq_hdr_table[ibit].pin >= 0)
{
rt_hw_interrupt_enable(level);
return -RT_EFULL;
}
pin_irq_hdr_table[ibit].pin = pin;
pin_irq_hdr_table[ibit].mode = mode;
pin_irq_hdr_table[ibit].hdr = hdr;
pin_irq_hdr_table[ibit].args = args;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
static rt_err_t gpio_pin_detach_irq(struct rt_device *device, rt_int32_t pin)
{
rt_base_t level;
int ibit;
ibit = _gpio_pin_to_ibit(pin);
if (ibit < 0)
return -RT_EINVAL;
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_table[ibit].pin < 0)
{
rt_hw_interrupt_enable(level);
return RT_EOK;
}
pin_irq_hdr_table[ibit].pin = -1;
pin_irq_hdr_table[ibit].mode = 0;
pin_irq_hdr_table[ibit].hdr = RT_NULL;
pin_irq_hdr_table[ibit].args = RT_NULL;
rt_hw_interrupt_enable(level);
return RT_EOK;
}
static rt_err_t gpio_pin_irq_enable(struct rt_device *device, rt_base_t pin,
rt_uint32_t enabled)
{
volatile struct gpio_registers *gpio;
rt_base_t level, int_enable;
int ibit, bitpos;
ibit = _gpio_pin_to_ibit(pin);
if (ibit < 0)
return -RT_EINVAL;
bitpos = (1 << ibit);
gpio = (struct gpio_registers *)GPIO_REG_BASE;
if (enabled == PIN_IRQ_ENABLE)
{
level = rt_hw_interrupt_disable();
if (pin_irq_hdr_table[ibit].pin != pin)
{
rt_hw_interrupt_enable(level);
return -RT_EINVAL;
}
switch (pin_irq_hdr_table[ibit].mode)
{
case PIN_IRQ_MODE_RISING:
BITS_SET(gpio->INT_MODE.reg, bitpos);
BITS_SET(gpio->INT_POLAR.reg, bitpos);
break;
case PIN_IRQ_MODE_FALLING:
BITS_SET(gpio->INT_MODE.reg, bitpos);
BITS_CLR(gpio->INT_POLAR.reg, bitpos);
break;
case PIN_IRQ_MODE_HIGH_LEVEL:
BITS_CLR(gpio->INT_MODE.reg, bitpos);
BITS_SET(gpio->INT_POLAR.reg, bitpos);
break;
case PIN_IRQ_MODE_LOW_LEVEL:
BITS_CLR(gpio->INT_MODE.reg, bitpos);
BITS_CLR(gpio->INT_POLAR.reg, bitpos);
break;
case PIN_IRQ_MODE_RISING_FALLING:
default:
rt_hw_interrupt_enable(level);
return -RT_EINVAL;
}
/* clear possible pending intr, then enable pin intr */
int_enable = gpio->INT_ENABLE.reg;
gpio->INT_FLAG.reg = bitpos;
gpio->INT_ENABLE.reg = int_enable | bitpos;
/* enable GPIO_IRQn if this is the first enabled EXTIx */
if (int_enable == 0)
{
rt_hw_interrupt_umask(GPIO_IRQn);
}
rt_hw_interrupt_enable(level);
}
else if (enabled == PIN_IRQ_DISABLE)
{
level = rt_hw_interrupt_disable();
int_enable = gpio->INT_ENABLE.reg;
BITS_CLR(int_enable, bitpos);
gpio->INT_ENABLE.reg = int_enable;
/* disable GPIO_IRQn if no EXTIx enabled */
if (int_enable == 0)
{
rt_hw_interrupt_mask(GPIO_IRQn);
}
rt_hw_interrupt_enable(level);
}
else
{
return -RT_EINVAL;
}
return RT_EOK;
}
static const struct rt_pin_ops pin_ops =
{
.pin_mode = gpio_pin_mode,
.pin_write = gpio_pin_write,
.pin_read = gpio_pin_read,
.pin_attach_irq = gpio_pin_attach_irq,
.pin_detach_irq = gpio_pin_detach_irq,
.pin_irq_enable = gpio_pin_irq_enable,
.pin_get = gpio_pin_get,
};
static int rt_hw_pin_init(void)
{
return rt_device_pin_register("pin", &pin_ops, RT_NULL);
}
INIT_BOARD_EXPORT(rt_hw_pin_init);
void gpio_irq_handler(void) __attribute__((interrupt()));
void gpio_irq_handler(void)
{
volatile struct gpio_registers *gpio;
uint8_t iflags;
int ibit, bitpos;
isr_sp_enter();
rt_interrupt_enter();
gpio = (struct gpio_registers *)GPIO_REG_BASE;
iflags = gpio->INT_FLAG.reg;
/* prioritized as pb15 -> pa2 (CH569), or pb10 -> pa3 */
for (ibit = 7; ibit >= 0; ibit--)
{
bitpos = (1 << ibit);
if (iflags & bitpos)
{
if (pin_irq_hdr_table[ibit].hdr)
{
pin_irq_hdr_table[ibit].hdr(pin_irq_hdr_table[ibit].args);
}
/* clear interrupt */
gpio->INT_FLAG.reg = bitpos;
}
}
rt_interrupt_leave();
isr_sp_leave();
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __CH56X_GPIO_H__
#define __CH56X_GPIO_H__
#include "soc.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Fixed linear mapping : 32 pins per port, for ports A,B,C,D...
*/
#define GET_PIN(port,pin) (GPIO_P##port##_PIN_START + pin)
#ifdef SOC_SERIES_CH569
#define GPIO_INT_PINS { \
GET_PIN(A,2), GET_PIN(A,3), GET_PIN(A,4), GET_PIN(B,3), \
GET_PIN(B,4), GET_PIN(B,11), GET_PIN(B,12), GET_PIN(B,15) \
}
#else
#define GPIO_INT_PINS { \
GET_PIN(A,3), GET_PIN(A,4), GET_PIN(A,6), GET_PIN(A,10), \
GET_PIN(A,11), GET_PIN(A,12), GET_PIN(B,4), GET_PIN(B,10), \
}
#endif
/*
* R8_GPIO_INT_FLAG / R8_GPIO_INT_STATUS (CH567,CH568):
* write 1 to specific bit to clear int flag
*
* R8_GPIO_INT_ENABLE:
* To use EXTIx function, pin should be set as input.
* For wakeup function, also set RB_SLP_GPIO_WAKE.
*
* R8_GPIO_INT_MODE:
* R8_GPIO_INT_POLAR:
*/
#if defined(SOC_SERIES_CH569)
union _gpio_interrupt
{
uint8_t reg;
struct
{
uint8_t pa2 : 1;
uint8_t pa3 : 1;
uint8_t pa4 : 1;
uint8_t pb3 : 1;
uint8_t pb4 : 1;
uint8_t pb11 : 1;
uint8_t pb12 : 1;
uint8_t pb15 : 1;
};
};
#else
union _gpio_interrupt
{
uint8_t reg;
struct
{
uint8_t pa3 : 1;
uint8_t pa4 : 1;
uint8_t pa6 : 1;
uint8_t pa10 : 1;
uint8_t pa11 : 1;
uint8_t pa12 : 1;
uint8_t pb4 : 1;
uint8_t pb10 : 1;
};
};
#endif
#define GPIO_IE_DISABLE 0
#define GPIO_IE_ENABLE 1
#define GPIO_IM_LEVEL 0
#define GPIO_IM_EDGE 1
#define GPIO_IP_LOW_FALLING 0
#define GPIO_IP_HIGH_RISING 1
/*
* R8_PIN_ALTERNATE (CH569) : reset value is 0x01
* R8_PORT_PIN (CH567/CH568) : reset value is 0x00
*/
union _gpio_pin_alternate
{
uint8_t reg;
struct
{
uint8_t pin_mii : 1; // RW, ETH uses RMII/RGMII (CH565W/CH569W)
uint8_t pin_tmr1 : 1; // RW, TMR1/PWM5/CAP1 remapping
uint8_t pin_tmr2 : 1; // RW, TMR2/PWM6/CAP2 remapping
uint8_t resv_3 : 1;
uint8_t pin_uart0 : 1; // RW, RXD0/TXD0 remapping
uint8_t pin_uart1 : 1; // RW, CH567 only
uint8_t resv_6 : 2;
};
};
#define RB_PIN_MII 0x01
#define RB_PIN_TMR1 0x02
#define RB_PIN_TMR2 0x04
#define RB_PIN_UART0 0x10
#define RB_PIN_UART1 0x20
#ifdef SOC_SERIES_CH569
#define GPIO_ALT_RMII 0
#define GPIO_ALT_RGMII 1
#define GPIO_ALT_TMR1_PB15 0
#define GPIO_ALT_TMR1_PB0 1
#define GPIO_ALT_TMR2_PA4 0
#define GPIO_ALT_TMR2_PB3 1
#define GPIO_ALT_UART0_PB5_6 0
#define GPIO_ALT_UART0_PA5_6 1
#else
#define GPIO_ALT_TMR1_PA10 0
#define GPIO_ALT_TMR1_PB2 1
#define GPIO_ALT_TMR2_PA11 0
#define GPIO_ALT_TMR2_PB11 1
#define GPIO_ALT_UART0_PB4_7 0
#define GPIO_ALT_UART0_PA15_14 1
#define GPIO_ALT_UART1_PA8_9 0
#define GPIO_ALT_UART1_PB8_9 1
#endif
struct gpio_px_regs
{
uint32_t DIR; // reset value for pins is 0, input pins
uint32_t PIN; // RO
uint32_t OUT; // reset value is 0
uint32_t CLR; // reset value is 0
uint32_t PU; // reset value is 0
uint32_t PD; // reset value is 0
uint32_t DRV; // reset value for pins is 0, 8mA
uint32_t SMT; // reset value for pins is 1, enable schmitt trigger
} __packed;
CHECK_STRUCT_SIZE(struct gpio_px_regs, 0x20);
#define GPIO_PX_DIR_IN 0
#define GPIO_PX_DIR_OUT 1
#define GPIO_PX_PU_DISABLE 0
#define GPIO_PX_PU_ENABLE 1
#define GPIO_PX_PD_DISABLE 0 // for DIR_IN
#define GPIO_PX_PD_ENABLE 1 // for DIR_IN
#define GPIO_PX_PD_PUSH_PULL 0 // for DIR_OUT
#define GPIO_PX_PD_OPEN_DRAIN 1 // for DIR_OUT
#define GPIO_PX_DRV_8mA 0
#define GPIO_PX_DRV_16mA 1
#define GPIO_PX_SMT_DISABLE 0
#define GPIO_PX_SMT_SLOW 1 // for DIR_OUT
#define GPIO_PX_SMT_ENABLE 1 // for DIR_IN
/*
* 0x12 R8_PIN_ALTERNATE: GPIO multi-use remapping register
* 0x1c R8_GPIO_INT_FLAG: GPIO interrupt flag register
* 0x1d R8_GPIO_INT_ENABLE: GPIO interrupt enable register
* 0x1e R8_GPIO_INT_MODE: GPIO interrupt mode register
* 0x1f R8_GPIO_INT_POLAR: GPIO interrupt polarity register
*
* 0x40 R32_PA_DIR: PA pin direction control
* 0x44 R32_PA_PIN: PA pin input status
* 0x48 R32_PA_OUT: PA pin output register
* 0x4c R32_PA_CLR: PA pin output clear
* 0x50 R32_PA_PU: PA pin pull-up resistor enable register
* 0x54 R32_PA_PD: PA pin open drain output / input pull-down control
* 0x58 R32_PA_DRV: PA pin output driving capability register
* 0x5c R32_PA_SMT: PA pin slow output / schmitt trigger input control
*
* 0x60 R32_PB_DIR:
* 0x64 R32_PB_PIN:
* 0x68 R32_PB_OUT:
* 0x6c R32_PB_CLR:
* 0x70 R32_PB_PU:
* 0x74 R32_PB_PD:
* 0x78 R32_PB_DRV:
* 0x7c R32_PB_SMT:
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read.
*/
struct gpio_registers
{
uint32_t resv_00[4];
uint8_t resv_10[2];
union _gpio_pin_alternate PIN_ALTERNATE;
uint8_t resv_13;
uint32_t resv_14[2];
union _gpio_interrupt INT_FLAG;
union _gpio_interrupt INT_ENABLE;
union _gpio_interrupt INT_MODE;
union _gpio_interrupt INT_POLAR;
uint32_t resv_20[8];
struct gpio_px_regs PA;
struct gpio_px_regs PB;
} __packed;
CHECK_STRUCT_SIZE(struct gpio_registers, 0x80);
#ifdef __cplusplus
}
#endif
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include "ch56x_pfic.h"
#include "ch56x_sys.h"
#include "isr_sp.h"
void rt_hw_interrupt_mask(int vector)
{
pfic_interrupt_mask(vector);
}
void rt_hw_interrupt_umask(int vector)
{
pfic_interrupt_umask(vector);
}
/**
* @brief Trigger software interrupt.
*/
void pfic_swi_pendset(void)
{
volatile struct pfic_registers *pfic = (void *)PFIC_REG_BASE;
_pfic_ireg_bit_set(pfic, IPSR, SWI_IRQn);
}
/**
* @brief Clear software interrupt.
*/
void pfic_swi_pendreset(void)
{
volatile struct pfic_registers *pfic = (void *)PFIC_REG_BASE;
_pfic_ireg_bit_set(pfic, IPRR, SWI_IRQn);
}
/**
* @brief Write PFIC interrupt configuration register.
*
* @param key_bit is (PFIC_CFGR_KEYx + bit_position), one of the following :
* PFIC_CFGR_NMISET / PFIC_CFGR_NMIRESET
* PFIC_CFGR_EXCSET / PFIC_CFGR_EXCRESET
* PFIC_CFGR_PFICRESET
* PFIC_CFGR_SYSRESET
* All others are treated as NEST/HWSTK (B.1/B.0) write.
*/
void pfic_cfgr_set(uint32_t key_bit)
{
volatile struct pfic_registers *pfic = (void *)PFIC_REG_BASE;
uint32_t u32v;
switch (key_bit)
{
case PFIC_CFGR_NMISET:
case PFIC_CFGR_NMIRESET:
case PFIC_CFGR_EXCSET:
case PFIC_CFGR_EXCRESET:
case PFIC_CFGR_PFICRESET:
case PFIC_CFGR_SYSRESET:
pfic->CFGR = key_bit;
default:
/* B.1/B.0 hold NEST/HWSTK, key ignored */
u32v = key_bit & (CFGR_NESTCTRL_MASK | CFGR_HWSTKCTRL_MASK);
pfic->CFGR = cfgr_nest_hwstk(u32v);
}
}
/**
* @brief Make SysTick ready, systick/swi irq are enabled.
*
* @param count is (HCLK/8) clocks count to generate systick irq.
* if 0 => calculate with current HCLK and RT_TICK_PER_SECOND
*/
void systick_init(uint32_t count)
{
volatile struct systick_registers *systick = (void *)SysTick_REG_BASE;
volatile struct pfic_registers *pfic = (void *)PFIC_REG_BASE;
if (count == 0)
count = sys_hclk_get() / 8 / RT_TICK_PER_SECOND;
_pfic_irqn_disable(pfic, SysTick_IRQn);
pfic->IPRIOR[SysTick_IRQn] = 0xe0;
pfic->IPRIOR[SWI_IRQn] = 0xf0;
systick->CTLR.reg = 0;
systick->CNTL = 0;
systick->CNTH = 0;
systick->CMPLR = count - 1;
systick->CMPHR = 0;
systick->CNTFG.cntif = 0;
/* enable & reload SysTick, with HCLK/8 */
systick->CTLR.reg = RB_STKCTL_STRELOAD | RB_STKCTL_STIE | RB_STKCTL_STE;
_pfic_irqn_enable(pfic, SysTick_IRQn);
_pfic_irqn_enable(pfic, SWI_IRQn);
}
void systick_handler(void) __attribute__((interrupt()));
void systick_handler(void)
{
volatile struct systick_registers *systick;
isr_sp_enter();
rt_interrupt_enter();
rt_tick_increase();
systick = (struct systick_registers *)SysTick_REG_BASE;
/* clear count-to-zero flag */
systick->CNTFG.cntif = 0;
rt_interrupt_leave();
isr_sp_leave();
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __CH56X_PFIC_H__
#define __CH56X_PFIC_H__
#include "soc.h"
#ifdef __cplusplus
extern "C" {
#endif
/* IREG: IENR/IRER/IRSR/IPRR, make sure irqn be 12~59
*/
#define PFIC_IREG1_MASK 0xfffff000
#define PFIC_IREG2_MASK 0x0fffffff
#define PFIC_MAX_IREG_BITS 60
#define _pfic_ireg_bit_get(pfic, IREG, irqn) \
((pfic->IREG[(irqn) >> 5] >> ((irqn) & 0x1f)) & 1)
#define _pfic_ireg_bit_set(pfic, IREG, irqn) \
do pfic->IREG[(irqn) >> 5] = 1 << ((irqn) & 0x1f); while(0)
#define _pfic_irqn_enable(pfic, irqn) _pfic_ireg_bit_set(pfic, IENR, irqn)
#define _pfic_irqn_disable(pfic, irqn) _pfic_ireg_bit_set(pfic, IRER, irqn)
/* Note: `union _pfic_cfgr` is not used directly in the reg structure */
union _pfic_cfgr
{
uint32_t reg;
struct
{
uint32_t hwstkctrl : 1; // RW, hw stack push/pop control (0:enable)
uint32_t nestctrl : 1; // RW, nested intr enable control (0:enable)
uint32_t nmiset : 1; // WO, write 1 to set NMI pending
uint32_t nmireset : 1; // WO, write 1 to reset NMI pending
uint32_t excset : 1; // WO, write 1 to set exception pending
uint32_t excreset : 1; // WO, write 1 to reset exception pending
uint32_t pficreset : 1; // WO, write 1 to reset PFIC module, auto clear
uint32_t sysreset : 1; // WO, write 1 for a system reset, auto clear
uint32_t resv_8 : 8;
uint32_t keycode : 16; // WO, write protection keycode
};
};
#define PFIC_CFGR_KEY1 0xfa05 // for hwstkctrl & nestctrl
#define PFIC_CFGR_KEY2 0xbcaf // for nmi & exc set/reset
#define PFIC_CFGR_KEY3 0xbeef // for sysreset
#define PFIC_CFGR_NMISET (PFIC_CFGR_KEY2 << 16 | 1 << 2)
#define PFIC_CFGR_NMIRESET (PFIC_CFGR_KEY2 << 16 | 1 << 3)
#define PFIC_CFGR_EXCSET (PFIC_CFGR_KEY2 << 16 | 1 << 4)
#define PFIC_CFGR_EXCRESET (PFIC_CFGR_KEY2 << 16 | 1 << 5)
#define PFIC_CFGR_PFICRESET (1 << 6)
#define PFIC_CFGR_SYSRESET (PFIC_CFGR_KEY3 << 16 | 1 << 7)
#define CFGR_HWSTKCTRL_ENABLE (0 << 0)
#define CFGR_HWSTKCTRL_DISABLE (1 << 0)
#define CFGR_HWSTKCTRL_MASK (1 << 0)
#define CFGR_NESTCTRL_ENABLE (0 << 1)
#define CFGR_NESTCTRL_DISABLE (1 << 1)
#define CFGR_NESTCTRL_MASK (1 << 1)
#define cfgr_nest_hwstk(v) (PFIC_CFGR_KEY1 << 16 | (v))
union _pfic_gisr
{
uint32_t reg;
struct
{
uint32_t neststa : 8; // RO, nested interrupt state (0/1/2)
uint32_t gactsta : 1; // RO, global interrupt active status
uint32_t gpendsta : 1; // RO, global interrupt pending status
uint32_t resv_10 : 22;
};
};
#define PFIC_NESTSTA_NONE 0
#define PFIC_NESTSTA_L1 1
#define PFIC_NESTSTA_L2 2
union _pfic_fiofaddrr
{
uint32_t reg;
struct
{
uint32_t offaddr : 24; // RW
uint32_t irqid : 8; // RW
};
};
union _pfic_sctlr
{
uint32_t reg;
struct
{
uint32_t resv_0 : 1;
uint32_t sleeponexit : 1; // enter (deep) sleep mode on isr exiting
uint32_t sleepdeep : 1; // RW, 0/1 for sleep/deep-sleep mode
uint32_t wfitowfe : 1; // RW, treat WFI as WFE
uint32_t sevonpend : 1; // RW
uint32_t setevent : 1; // WO, set event for WFE
uint32_t resv_6 : 26;
};
};
/*
* 0x000 R32_PFIC_ISR1: PFIC interrupt enable status (# 12-31)
* 0x004 R32_PFIC_ISR2: PFIC interrupt enable status (# 32-59)
* 0x020 R32_PFIC_IPR1: PFIC interrupt pending status (# 12-31)
* 0x024 R32_PFIC_IPR2: PFIC interrupt pending status (# 32-59)
* 0x040 R32_PFIC_ITHRESDR: PFIC interrupt priority threshold (B.7-4)
* 0x044 R32_PFIC_FIBADDRR: PFIC fast intr base address (B.31-28)
* 0x048 R32_PFIC_CFGR: PFIC interrupt configuration register
* 0x04c R32_PFIC_GISR: PFIC global interrupt status register
* 0x060 R32_PFIC_FIOFADDRR0: PFIC fast intr 0 offset address (B.23-0)
* 0x064 R32_PFIC_FIOFADDRR1: PFIC fast intr 1 offset address (B.23-0)
* 0x068 R32_PFIC_FIOFADDRR2: PFIC fast intr 2 offset address (B.23-0)
* 0x06c R32_PFIC_FIOFADDRR3: PFIC fast intr 3 offset address (B.23-0)
* 0x100 R32_PFIC_IENR1: PFIC interrupt enable register (# 12-31)
* 0x104 R32_PFIC_IENR2: PFIC interrupt enable register (# 32-59)
* 0x180 R32_PFIC_IRER1: PFIC interrupt reset register (# 12-31)
* 0x184 R32_PFIC_IRER2: PFIC interrupt reset register (# 32-59)
* 0x200 R32_PFIC_IPSR1: PFIC interrupt pending set register (# 12-31)
* 0x204 R32_PFIC_IPSR2: PFIC interrupt pending set register (# 32-59)
* 0x280 R32_PFIC_IPRR1: PFIC interrupt pending reset register (# 12-31)
* 0x284 R32_PFIC_IPRR2: PFIC interrupt pending reset register (# 32-59)
* 0x300 R32_PFIC_IACTR1: PFIC interrupt active status register (# 12-31)
* 0x304 R32_PFIC_IACTR2: PFIC interrupt active status register (# 32-59)
* 0x400 R32_PFIC_IPRIORx: PFIC interrupt priority registers
* 0xd10 R32_PFIC_SCTLR: PFIC system control register
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read.
*/
struct pfic_registers
{
uint32_t ISR[2];
uint32_t resv_08[6];
uint32_t IPR[2];
uint32_t resv_28[6];
uint32_t ITHRESDR;
uint32_t FIBADDRR;
uint32_t CFGR;
union _pfic_gisr GISR;
uint32_t resv_50[4];
union _pfic_fiofaddrr FIOFADDRR[4];
uint32_t resv_70[36];
uint32_t IENR[2];
uint32_t resv_108[30];
uint32_t IRER[2];
uint32_t resv_188[30];
uint32_t IPSR[2];
uint32_t resv_208[30];
uint32_t IPRR[2];
uint32_t resv_288[30];
uint32_t IACTR[2];
uint32_t resv_308[62];
uint8_t IPRIOR[256];
uint32_t resv_500[516];
union _pfic_sctlr SCTLR;
} __packed;
CHECK_STRUCT_SIZE(struct pfic_registers, 0xd14);
union _systick_ctlr
{
uint32_t reg;
struct
{
uint32_t ste : 1; // RW, systick enable
uint32_t stie : 1; // RW, systick interrupt enable
uint32_t stclk : 1; // RW, systick clock source select
uint32_t resv_3 : 5;
uint32_t streload : 1; // W1, write 1 to reload systick
uint32_t resv_9 : 23;
};
};
#define RB_STKCTL_STE 0x001
#define RB_STKCTL_STIE 0x002
#define RB_STKCTL_STCLK 0x004
#define RB_STKCTL_STRELOAD 0x100
#define SYSTICK_SRC_HCLK_8 0
#define SYSTICK_SRC_HCLK 1
union _systick_cntfg
{
uint32_t reg;
struct
{
uint32_t swie : 1; // RW, software interrupt enable
uint32_t cntif : 1; // RW0, counter dec to 0 (write 0 to clear)
uint32_t resv_2 : 30;
};
};
#define RB_CNTFG_SWIE 0X01
#define RB_CNTFG_CNTIF 0X02
/*
* 0x00 R32_STK_CTLR: SysTick control register
* 0x04 R32_STK_CNTL: SysTick counter, Lo.32
* 0x08 R32_STK_CNTH: SysTick counter, Hi.32
* 0x0c R32_STK_CMPLR: SysTick compare-reload register, Lo.32
* 0x10 R32_STK_CMPHR: SysTick compare-reload register, Hi.32
* 0x14 R32_STK_CNTFG: SysTick counter flags
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read.
*/
struct systick_registers
{
union _systick_ctlr CTLR;
uint32_t CNTL;
uint32_t CNTH;
uint32_t CMPLR;
uint32_t CMPHR;
union _systick_cntfg CNTFG;
} __packed;
CHECK_STRUCT_SIZE(struct systick_registers, 0x18);
rt_inline void pfic_interrupt_umask(uint8_t irqn)
{
volatile struct pfic_registers *pfic;
if (irqn < PFIC_MAX_IREG_BITS)
{
pfic = (void *)PFIC_REG_BASE;
_pfic_ireg_bit_set(pfic, IENR, irqn);
}
}
rt_inline void pfic_interrupt_mask(uint8_t irqn)
{
volatile struct pfic_registers *pfic;
if (irqn < PFIC_MAX_IREG_BITS)
{
pfic = (void *)PFIC_REG_BASE;
_pfic_ireg_bit_set(pfic, IRER, irqn);
}
}
void pfic_swi_pendset(void);
void pfic_swi_pendreset(void);
void pfic_cfgr_set(uint32_t key_bit);
void systick_init(uint32_t count);
#ifdef __cplusplus
}
#endif
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include "ch56x_sys.h"
rt_inline uint8_t _slp_clk_off0_irqn_bit(uint8_t irqn)
{
uint8_t bitpos;
switch (irqn)
{
case TMR0_IRQn: bitpos = RB_SLP_CLK_TMR0; break;
case TMR1_IRQn: bitpos = RB_SLP_CLK_TMR1; break;
case TMR2_IRQn: bitpos = RB_SLP_CLK_TMR2; break;
/* special case to control PWMX clock in irqn way */
case PWMX_OFFn: bitpos = RB_SLP_CLK_PWMX; break;
case UART0_IRQn: bitpos = RB_SLP_CLK_UART0; break;
case UART1_IRQn: bitpos = RB_SLP_CLK_UART1; break;
case UART2_IRQn: bitpos = RB_SLP_CLK_UART2; break;
case UART3_IRQn: bitpos = RB_SLP_CLK_UART3; break;
default:
bitpos = 0;
}
return bitpos;
}
rt_inline uint8_t _slp_clk_off1_irqn_bit(uint8_t irqn)
{
uint8_t bitpos;
switch (irqn)
{
case SPI0_IRQn: bitpos = RB_SLP_CLK_SPI0; break;
case SPI1_IRQn: bitpos = RB_SLP_CLK_SPI1; break;
#if defined(SOC_CH567)
case SDC_IRQn: bitpos = RB_SLP_CLK_SDC; break;
case LED_IRQn: bitpos = RB_SLP_CLK_LED; break;
case USB0_IRQn: bitpos = RB_SLP_CLK_USB0; break;
case USB1_IRQn: bitpos = RB_SLP_CLK_USB1; break;
case ECDC_IRQn: bitpos = RB_SLP_CLK_ECDC; break;
#elif defined(SOC_CH568)
case SDC_IRQn: bitpos = RB_SLP_CLK_SDC; break;
case LED_IRQn: bitpos = RB_SLP_CLK_LED; break;
case USB1_IRQn: bitpos = RB_SLP_CLK_USB1; break;
case USB0_IRQn: bitpos = RB_SLP_CLK_SATA; break;
case ECDC_IRQn: bitpos = RB_SLP_CLK_ECDC; break;
#else
case EMMC_IRQn: bitpos = RB_SLP_CLK_EMMC; break;
case HSPI_IRQn: bitpos = RB_SLP_CLK_HSPI; break;
case USBHS_IRQn: bitpos = RB_SLP_CLK_USBHS; break;
case USBSS_IRQn: bitpos = RB_SLP_CLK_USBSS; break;
case SerDes_IRQn: bitpos = RB_SLP_CLK_SERD; break;
case DVP_IRQn: bitpos = RB_SLP_CLK_DVP; break;
#endif
default:
bitpos = 0;
}
return bitpos;
}
#if defined(SOC_SERIES_CH569)
rt_inline uint8_t _wake_clk_off_irqn_bit(uint8_t irqn)
{
uint8_t bitpos;
switch (irqn)
{
case ETH_IRQn: bitpos = RB_SLP_CLK_ETH; break;
case ECDC_IRQn: bitpos = RB_SLP_CLK_ECDC; break;
default:
bitpos = 0;
}
return bitpos;
}
#endif
/**
* @brief Turn on/off device clock for group clk_off0.
*
* @param bits is a bit mask to select corresponding devices.
*
* @param off is to turn off the clock (1) or trun on (0).
*/
void sys_slp_clk_off0(uint8_t bits, int off)
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
rt_base_t level;
uint8_t u8v;
u8v = sys->SLP_CLK_OFF0.reg;
u8v = off ? (u8v | bits) : (u8v & ~bits);
level = rt_hw_interrupt_disable();
sys_safe_access_enter(sys);
sys->SLP_CLK_OFF0.reg = u8v;
sys_safe_access_leave(sys);
rt_hw_interrupt_enable(level);
}
/**
* @brief Turn on/off device clock for group clk_off1.
*
* @param bits is a bit mask to select corresponding devices.
*
* @param off is to turn off the clock (1) or trun on (0).
*/
void sys_slp_clk_off1(uint8_t bits, int off)
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
rt_base_t level;
uint8_t u8v;
u8v = sys->SLP_CLK_OFF1.reg;
u8v = off ? (u8v | bits) : (u8v & ~bits);
level = rt_hw_interrupt_disable();
sys_safe_access_enter(sys);
sys->SLP_CLK_OFF1.reg = u8v;
sys_safe_access_leave(sys);
rt_hw_interrupt_enable(level);
}
/**
* @brief Turn on/off device clock, specified by its irq number.
*
* @param irqn is the irq number of the target device.
* PWMX does not have irqn, use special PWMX_OFFn number.
*
* @param off is to turn off the clock (1) or trun on (0).
*
* @return Returns if irqn-device has corresponding clk off bit :
* 0 if device not found; otherwise bit position of off0/off1.
*/
int sys_clk_off_by_irqn(uint8_t irqn, int off)
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
uint8_t u8v;
size_t offset;
uint8_t bitpos = 0;
if (irqn < END_OF_IRQn)
{
if ((bitpos = _slp_clk_off0_irqn_bit(irqn)) != 0)
{
offset = offsetof(struct sys_registers, SLP_CLK_OFF0);
}
else if ((bitpos = _slp_clk_off1_irqn_bit(irqn)) != 0)
{
offset = offsetof(struct sys_registers, SLP_CLK_OFF1);
}
#if defined(SOC_SERIES_CH569)
else if ((bitpos = _wake_clk_off_irqn_bit(irqn)) != 0)
{
offset = offsetof(struct sys_registers, SLP_WAKE_CTRL);
}
#endif
if (bitpos)
{
volatile uint8_t *cxreg = (void *)sys;
rt_base_t level;
u8v = cxreg[offset];
u8v = off ? (u8v | bitpos) : (u8v & ~bitpos);
level = rt_hw_interrupt_disable();
sys_safe_access_enter(sys);
cxreg[offset] = u8v;
sys_safe_access_leave(sys);
rt_hw_interrupt_enable(level);
}
}
return bitpos;
}
/**
* @brief Setup HCLK frequency.
*
* @param freq is the desired hclk frequency.
* supported : 120/96/80/60/48/40/32/30/15/10/6/3/2 MHz
*
* @return Returns 0 if hclk is successfully set.
*/
int sys_hclk_set(uint32_t freq)
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
uint8_t plldiv;
int clksel = -1;
if (freq >= 30000000)
{
if (freq <= 120000000)
{
/* supported : 120/96/80/60/48/40/32/30 MHz */
plldiv = 480000000 / freq; // 30M => 16 & 0xf => 0
clksel = RB_CLK_SEL_PLL;
}
}
else if (freq >= 2000000)
{
/* supported : 15/10/6/3/2 MHz */
plldiv = 30000000 / freq;
clksel = 0;
}
if (clksel >= 0)
{
rt_base_t level = rt_hw_interrupt_disable();
sys_safe_access_enter(sys);
sys->CLK_PLL_DIV.reg = clk_pll_div_wdat(plldiv);
sys->CLK_CFG_CTRL.reg = clk_cfg_ctrl_wdat(clksel);
sys_safe_access_leave(sys);
rt_hw_interrupt_enable(level);
clksel = 0;
}
return clksel;
}
/**
* @brief Get current HCLK frequency.
*
* @return Returns current HCLK frequency (Hz).
*/
uint32_t sys_hclk_get(void)
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
uint8_t plldiv = sys->CLK_PLL_DIV.pll_div;
if (sys->CLK_CFG_CTRL.sel_pll == CLK_SEL_PLL_USB_480M)
{
return plldiv ? 480000000 / plldiv : 30000000;
}
else
{
return plldiv ? 30000000 / plldiv : 2000000;
}
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __CH56X_SYS_H__
#define __CH56X_SYS_H__
#include "soc.h"
#ifdef __cplusplus
extern "C" {
#endif
#define sys_safe_access_enter(sys) \
do { \
sys->SAFE_ACCESS_SIG.reg = SAFE_ACCESS_SIG_1; \
sys->SAFE_ACCESS_SIG.reg = SAFE_ACCESS_SIG_2; \
} while(0)
#define sys_safe_access_leave(sys) \
do sys->SAFE_ACCESS_SIG.reg = 0; while(0)
union _sys_safe_access_sig
{
uint8_t reg;
struct
{
uint8_t safe_acc_mode : 2; // RO, current safe access, 11b => RWA ok
uint8_t resv_2 : 2;
uint8_t safe_acc_timer : 3; // RO, current safe access time count
uint8_t resv_7 : 1;
};
};
#define RB_SAFE_ACC_MODE 0x03
#define RB_SAFE_ACC_TIMER 0x70
#define SAFE_ACCESS_SIG_1 0x57
#define SAFE_ACCESS_SIG_2 0xa8
union _sys_glob_rom_cfg
{
uint8_t reg;
struct
{
uint8_t rom_ext_re : 1; // RO, allow programmer to read FlashROM
uint8_t code_ram_we : 1; // RWA, code SRAM writaboe
uint8_t rom_data_we : 1; // RWA, FlashROM data erasable/writable
uint8_t rom_code_we : 1; // RWA, FlashROM code erasable/writable
uint8_t rom_code_ofs : 1; // RWA, FlashROM offset for user code
uint8_t resv_5 : 3;
};
};
#define RB_ROM_EXT_RE 0x01
#define RB_CODE_RAM_WE 0x02
#define RB_ROM_DATA_WE 0x04
#define RB_ROM_CODE_WE 0x08
#define RB_ROM_CODE_OFS 0x10
#define ROM_CODE_OFS_0x00000 0
#define ROM_CODE_OFS_0x04000 1
union _sys_rst_boot_stat
{
uint8_t reg;
struct
{
uint8_t reset_flag : 2; // RO, last reset cause
uint8_t cfg_reset_en : 1; // RO, external reset pin (#RST) status
uint8_t cfg_boot_en : 1; // RO, reset as 1
uint8_t cfg_debug_en : 1; // RO
uint8_t boot_loader : 1; // RO
uint8_t resv_6 : 2;
};
};
#define RB_RESET_FLAG 0x03
#define RB_CFG_RESET_EN 0x04
#define RB_CFG_BOOT_EN 0x08
#define RB_CFG_DEBUG_EN 0x10
#define RB_BOOT_LOADER 0x20
#define RESET_FLAG_IS_SOFT 0
#define RESET_FLAG_IS_POR 1
#define RESET_FLAG_IS_WDOG 2
#define RESET_FLAG_IS_RSTPIN 3
union _sys_rst_wdog_ctrl
{
uint8_t reg;
struct
{
uint8_t software_reset : 1; // WA/WZ, system software reset, auto clear
#if defined(SOC_SERIES_CH569)
uint8_t wdog_rst_en : 1; // RWA, enable watchdog overflow to reset
uint8_t wdog_int_en : 1; // RWA, enable watchdog overflow interrupt
uint8_t wdog_int_flag : 1; // RW1, watchdog counter overflow
#else
uint8_t resv_2 : 3;
#endif
uint8_t resv_4 : 4; // RO, B.7-6 must write 01b
};
};
#define RB_SOFTWARE_RESET 0x01
#ifdef SOC_SERIES_CH569
#define RB_WDOG_RST_EN 0x02
#define RB_WDOG_INT_EN 0x04
#define RB_WDOG_INT_FLAG 0x08
#endif
#define wdog_ctrl_wdat(v) (0x40 | (v))
union _sys_clk_pll_div
{
uint8_t reg;
struct
{
uint8_t pll_div : 4; // RWA, min 2
uint8_t resv_4 : 4; // RWA, B.7-6 must write 01b
};
};
#define clk_pll_div_wdat(div) (0x40 | (div))
union _sys_clk_cfg_ctrl
{
uint8_t reg;
struct
{
uint8_t pll_sleep : 1; // RWA, PLL sleep control
uint8_t sel_pll : 1; // RWA, clock source select
uint8_t resv_6 : 6; // RWA, must write 10b
};
};
#define RB_CLK_PLL_SLEEP 0x01
#define RB_CLK_SEL_PLL 0x02
#define CLK_PLL_SLEEP_DISABLE 0
#define CLK_PLL_SLEEP_ENABLE 1
#define CLK_SEL_PLL_HSE_30M 0
#define CLK_SEL_PLL_USB_480M 1
#define clk_cfg_ctrl_wdat(v) (0x80 | (v))
union _sys_clk_mod_aux
{
uint8_t reg;
struct
{
uint8_t int_125m_en : 1; // RWA, USB PHY 125MHz to ETH
uint8_t ext_125m_en : 1; // RWA, external 125MHz to ETH
uint8_t mco_sel_msk : 2; // RWA, MCO output select
uint8_t mco_en : 1; // RWA, MCO output enable
uint8_t resv_5 : 3;
};
};
#define RB_INT_125M_EN 0x01
#define RB_EXT_125M_EN 0x02
#define RB_MCO_SEL_MSK 0x0c
#define RB_MCO_EN 0x10
#define MCO_SEL_MSK_125M 0
#define MCO_SEL_MSK_25M 1
#define MCO_SEL_MSK_2_5M 2
/* All bits are RWA (need safe_access_sig), 0/1 : clock on/off
*/
union _sys_slp_clk_off0
{
uint8_t reg;
struct
{
uint8_t tmr0 : 1;
uint8_t tmr1 : 1;
uint8_t tmr2 : 1;
uint8_t pwmx : 1;
uint8_t uart0 : 1;
uint8_t uart1 : 1;
uint8_t uart2 : 1;
uint8_t uart3 : 1;
};
};
#define RB_SLP_CLK_TMR0 0x01
#define RB_SLP_CLK_TMR1 0x02
#define RB_SLP_CLK_TMR2 0x04
#define RB_SLP_CLK_PWMX 0x08
#define RB_SLP_CLK_UART0 0x10
#define RB_SLP_CLK_UART1 0x20
#define RB_SLP_CLK_UART2 0x40
#define RB_SLP_CLK_UART3 0x80
#define SYS_SLP_CLK_ON 0
#define SYS_SLP_CLK_OFF 1
/* All writable bits are RWA (need safe_access_sig), 0/1 : clock on/off
*/
union _sys_slp_clk_off1
{
uint8_t reg;
struct
{
uint8_t spi0 : 1;
uint8_t spi1 : 1;
#if defined(SOC_CH567)
uint8_t sdc : 1;
uint8_t led : 1;
uint8_t usb0 : 1;
uint8_t usb1 : 1;
uint8_t resv_6 : 1;
#elif defined(SOC_CH568)
uint8_t sdc : 1;
uint8_t led : 1;
uint8_t resv_4 : 1;
uint8_t usb1 : 1;
uint8_t sata : 1;
uint8_t ecdc : 1;
#else
uint8_t emmc : 1;
uint8_t hspi : 1;
uint8_t usbhs : 1;
uint8_t usbss : 1;
uint8_t serd : 1;
uint8_t dvp : 1;
#endif
};
};
#define RB_SLP_CLK_SPI0 0x01
#define RB_SLP_CLK_SPI1 0x02
#if defined(SOC_WCH_CH567)
#define RB_SLP_CLK_SDC 0x04
#define RB_SLP_CLK_LED 0x08
#define RB_SLP_CLK_USB0 0x10
#define RB_SLP_CLK_USB1 0x20
#define RB_SLP_CLK_ECDC 0x80
#elif defined(SOC_WCH_CH568)
#define RB_SLP_CLK_SDC 0x04
#define RB_SLP_CLK_LED 0x08
#define RB_SLP_CLK_USB1 0x20
#define RB_SLP_CLK_SATA 0x40
#define RB_SLP_CLK_ECDC 0x80
#else
#define RB_SLP_CLK_EMMC 0x04
#define RB_SLP_CLK_HSPI 0x08
#define RB_SLP_CLK_USBHS 0x10
#define RB_SLP_CLK_USBSS 0x20
#define RB_SLP_CLK_SERD 0x40
#define RB_SLP_CLK_DVP 0x80
#endif
/* All writable bits are RWA (need safe_access_sig)
*/
union _sys_slp_wake_ctrl
{
uint8_t reg;
struct
{
#if defined(SOC_WCH_CH567)
uint8_t usb0_wake : 1;
uint8_t usb1_wake : 1;
uint8_t resv_2 : 2;
uint8_t gpio_wake : 1;
uint8_t resv_5 : 3;
#elif defined(SOC_WCH_CH568)
uint8_t resv_0 : 1;
uint8_t usb1_wake : 1;
uint8_t sata_wake : 1;
uint8_t resv_3 : 1;
uint8_t gpio_wake : 1;
uint8_t resv_5 : 3;
#else
uint8_t usbhs_wake : 1;
uint8_t usbss_wake : 1;
uint8_t clk_eth : 1;
uint8_t clk_ecdc : 1;
uint8_t gpio_wake : 1;
uint8_t eth_wake : 1;
uint8_t resv_6 : 2;
#endif
};
};
#if defined(SOC_WCH_CH567)
#define RB_SLP_USB0_WAKE 0x01
#define RB_SLP_USB1_WAKE 0x02
#define RB_SLP_GPIO_WAKE 0x10
#elif defined(SOC_WCH_CH568)
#define RB_SLP_USB1_WAKE 0x02
#define RB_SLP_SATA_WAKE 0x04
#define RB_SLP_GPIO_WAKE 0x10
#else
#define RB_SLP_USBHS_WAKE 0x01
#define RB_SLP_USBSS_WAKE 0x02
#define RB_SLP_CLK_ETH 0x04
#define RB_SLP_CLK_ECDC 0x08
#define RB_SLP_GPIO_WAKE 0x10
#define RB_SLP_ETH_WAKE 0x20
#endif
union _sys_slp_power_ctrl
{
uint8_t reg;
struct
{
uint8_t usbhs_pwrdn : 1; // RWA, USBHS power down (0:PWRUP)
uint8_t resv_2 : 7;
};
};
#define RB_SLP_USBHS_PWRDN 0x01
union _sys_serd_ana_cfg1
{
uint16_t reg;
struct
{
uint8_t serd_pll_cfg; // RWA, reset as 0x5a
uint8_t serd_30m_sel : 1; // RWA
uint8_t serd_dn_tst : 1; // RWA
uint8_t resv_10 : 6;
};
};
#define RB_SERD_PLL_CFG 0x0ff
#define RB_SERD_30M_SEL 0x100
#define RB_SERD_DN_TST 0x200
union _sys_serd_ana_cfg2
{
uint32_t reg;
struct
{
uint32_t serd_trx_cfg : 25; // RWA, reset as 423015h
uint32_t resv_25 : 7;
};
};
#define RB_SERD_TRX_CFG 0x1000000
/*
* 0x00 R8_SAFE_ACCESS_SIG: safe access signature register
* 0x01 R8_CHIP_ID: RF, chip ID register
* 0x02 R8_SAFE_ACCESS_ID: RF, read as 02h
* 0x03 R8_WDOG_COUNT RW, watchdog counter
* 0x04 R8_GLOB_ROM_CFG: ROM config register
* 0x05 R8_RST_BOOT_STAT: RO, boot state register
* 0x06 R8_RST_WDOG_CTRL: software reset & watchdog control register
* 0x07 R8_GLOB_RESET_KEEP: RW, only power-on-reset can clear this register
* 0x08 R8_CLK_PLL_DIV: RWA, PLL output divisor register
* 0x0a R8_CLK_CFG_CTRL: RWA, clock config register
* 0x0b R8_CLK_MOD_AUX: RWA, clock auxiliary register
* 0x0c R8_SLP_CLK_OFF0: RWA, sleep control register 0
* 0x0d R8_SLP_CLK_OFF1: RWA, sleep control register 1
* 0x0e R8_SLP_WAKE_CTRL: RWA, wakeup control register
* 0x0f R8_SLP_POWER_CTRL: RWA, low power management register
* 0x20 R16_SERD_ANA_CFG1: RWA, SerDes PHY analog param config register 1
* 0x24 R32_SERD_ANA_CFG2: RWA, SerDes PHY analog param config register 2
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read.
*/
struct sys_registers
{
union _sys_safe_access_sig SAFE_ACCESS_SIG;
uint8_t CHIP_ID;
uint8_t SAFE_ACCESS_ID;
uint8_t WDOG_COUNT;
union _sys_glob_rom_cfg GLOB_ROM_CFG;
union _sys_rst_boot_stat RST_BOOT_STAT;
union _sys_rst_wdog_ctrl RST_WDOG_CTRL;
uint8_t GLOB_RESET_KEEP;
union _sys_clk_pll_div CLK_PLL_DIV;
uint8_t resv_9;
union _sys_clk_cfg_ctrl CLK_CFG_CTRL;
union _sys_clk_mod_aux CLK_MOD_AUX;
union _sys_slp_clk_off0 SLP_CLK_OFF0;
union _sys_slp_clk_off1 SLP_CLK_OFF1;
union _sys_slp_wake_ctrl SLP_WAKE_CTRL;
union _sys_slp_power_ctrl SLP_POWER_CTRL;
#if defined(SOC_SERIES_CH569)
uint32_t resv_10[4];
union _sys_serd_ana_cfg1 SERD_ANA_CFG1;
uint16_t resv_22;
union _sys_serd_ana_cfg2 SERD_ANA_CFG2;
#endif
} __packed;
CHECK_STRUCT_SIZE(struct sys_registers, 0x28);
uint32_t sys_hclk_get(void);
int sys_hclk_set(uint32_t freq);
int sys_clk_off_by_irqn(uint8_t irqn, int off);
void sys_slp_clk_off0(uint8_t bits, int off);
void sys_slp_clk_off1(uint8_t bits, int off);
#ifdef __cplusplus
}
#endif
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include <drivers/hwtimer.h>
#include "ch56x_sys.h"
#include "ch56x_timer.h"
#include "isr_sp.h"
struct hwtimer_device
{
struct rt_hwtimer_device parent;
struct rt_hwtimer_info hwtimer_info;
volatile struct timer_registers *reg_base;
rt_hwtimer_mode_t tmode;
irq_number_t irqn;
char *name;
};
#ifdef BSP_USING_TMR0
static struct hwtimer_device hwtimer_device_0 =
{
.hwtimer_info =
{
.maxfreq = 80000000,
.minfreq = 80000000,
.maxcnt = 0x3ffffff,
.cntmode = HWTIMER_CNTMODE_UP,
},
.reg_base = (struct timer_registers *)TMR0_REG_BASE,
.tmode = HWTIMER_MODE_PERIOD,
.irqn = TMR0_IRQn,
.name = "timer0",
};
#endif
#ifdef BSP_USING_TMR1
static struct hwtimer_device hwtimer_device_1 =
{
.hwtimer_info =
{
.maxfreq = 80000000,
.minfreq = 80000000,
.maxcnt = 0x3ffffff,
.cntmode = HWTIMER_CNTMODE_UP,
},
.reg_base = (struct timer_registers *)TMR1_REG_BASE,
.tmode = HWTIMER_MODE_PERIOD,
.irqn = TMR1_IRQn,
.name = "timer1",
};
#endif
#ifdef BSP_USING_TMR2
static struct hwtimer_device hwtimer_device_2 =
{
.hwtimer_info =
{
.maxfreq = 80000000,
.minfreq = 80000000,
.maxcnt = 0x3ffffff,
.cntmode = HWTIMER_CNTMODE_UP,
},
.reg_base = (struct timer_registers *)TMR2_REG_BASE,
.tmode = HWTIMER_MODE_PERIOD,
.irqn = TMR2_IRQn,
.name = "timer2",
};
#endif
static void hwtimer_stop(struct rt_hwtimer_device *timer);
static void hwtimer_init(struct rt_hwtimer_device *timer, uint32_t state)
{
struct hwtimer_device *hwtimer_device = (void *)timer;
RT_ASSERT(hwtimer_device != RT_NULL);
/* no resource processing, `state` ignored */
hwtimer_stop(timer);
if (hwtimer_device->irqn != TMR0_IRQn)
{
hwtimer_device->reg_base->CTRL_DMA.reg = 0;
}
}
static rt_err_t hwtimer_start(struct rt_hwtimer_device *timer, uint32_t cnt, rt_hwtimer_mode_t mode)
{
struct hwtimer_device *hwtimer_device = (void *)timer;
volatile struct timer_registers *txreg;
RT_ASSERT(hwtimer_device != RT_NULL);
/* hwtimer_device->tmode may be different from timer->mode.
* For multi-cycle ONESHOT, tmode is set to PERIOD at hwtimer_start.
*/
hwtimer_device->tmode = mode;
sys_clk_off_by_irqn(hwtimer_device->irqn, SYS_SLP_CLK_ON);
txreg = hwtimer_device->reg_base;
txreg->CNT_END = cnt;
txreg->CTRL_MOD.reg = RB_TMR_ALL_CLEAR;
txreg->CTRL_MOD.reg = RB_TMR_COUNT_EN;
txreg->INTER_EN.cyc_end = 1;
rt_hw_interrupt_umask(hwtimer_device->irqn);
return RT_EOK;
}
static void hwtimer_stop(struct rt_hwtimer_device *timer)
{
struct hwtimer_device *hwtimer_device = (void *)timer;
volatile struct timer_registers *txreg;
RT_ASSERT(hwtimer_device != RT_NULL);
rt_hw_interrupt_mask(hwtimer_device->irqn);
/* note: RB_TMR_COUNT_EN cleared */
txreg = hwtimer_device->reg_base;
txreg->CTRL_MOD.reg = RB_TMR_ALL_CLEAR;
txreg->INTER_EN.reg = 0;
sys_clk_off_by_irqn(hwtimer_device->irqn, SYS_SLP_CLK_OFF);
}
static uint32_t hwtimer_count_get(struct rt_hwtimer_device *timer)
{
struct hwtimer_device *hwtimer_device = (void *)timer;
RT_ASSERT(hwtimer_device != RT_NULL);
return hwtimer_device->reg_base->COUNT;
}
static rt_err_t hwtimer_control(
struct rt_hwtimer_device *timer, uint32_t cmd, void *args)
{
struct hwtimer_device *hwtimer_device = (void *)timer;
rt_err_t result = RT_EOK;
RT_ASSERT(hwtimer_device != RT_NULL);
switch (cmd)
{
case HWTIMER_CTRL_FREQ_SET:
/* clocking for ch56x timers are fixed to Fsys */
if (args == RT_NULL || *(uint32_t *)args != timer->info->minfreq)
{
result = -RT_EINVAL;
}
break;
case HWTIMER_CTRL_STOP:
case HWTIMER_CTRL_INFO_GET:
case HWTIMER_CTRL_MODE_SET:
default:
result = -RT_ENOSYS;
}
return result;
}
static const struct rt_hwtimer_ops hwtimer_ops =
{
.init = hwtimer_init,
.start = hwtimer_start,
.stop = hwtimer_stop,
.count_get = hwtimer_count_get,
.control = hwtimer_control,
};
static int rt_hw_hwtimer_init(void)
{
struct hwtimer_device *devices[3];
uint32_t Fsys = sys_hclk_get();
int n = 0;
#ifdef BSP_USING_TMR2
devices[n++] = &hwtimer_device_2;
#endif
#ifdef BSP_USING_TMR1
devices[n++] = &hwtimer_device_1;
#endif
#ifdef BSP_USING_TMR0
devices[n++] = &hwtimer_device_0;
#endif
while (--n >= 0)
{
struct hwtimer_device *hwtimer_device = devices[n];
/* counting frequency is fixed to Fsys */
hwtimer_device->hwtimer_info.maxfreq = Fsys;
hwtimer_device->hwtimer_info.minfreq = Fsys;
hwtimer_device->parent.info = &hwtimer_device->hwtimer_info;
hwtimer_device->parent.ops = &hwtimer_ops;
rt_device_hwtimer_register(
&hwtimer_device->parent, hwtimer_device->name, RT_NULL);
}
return RT_EOK;
}
INIT_DEVICE_EXPORT(rt_hw_hwtimer_init);
static void _hwtimer_isr_common(struct hwtimer_device *hwtimer_device)
{
volatile struct timer_registers *txreg = hwtimer_device->reg_base;
if (txreg->INT_FLAG.cyc_end)
{
if (hwtimer_device->tmode == HWTIMER_MODE_ONESHOT)
{
/* disable timer to emulate oneshot */
txreg->CTRL_MOD.reg = 0;
}
rt_device_hwtimer_isr(&hwtimer_device->parent);
txreg->INT_FLAG.cyc_end = 1;
}
}
#ifdef BSP_USING_TMR0
void tmr0_irq_handler(void) __attribute__((interrupt()));
void tmr0_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_hwtimer_isr_common(&hwtimer_device_0);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
#ifdef BSP_USING_TMR1
void tmr1_irq_handler(void) __attribute__((interrupt()));
void tmr1_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_hwtimer_isr_common(&hwtimer_device_1);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
#ifdef BSP_USING_TMR2
void tmr2_irq_handler(void) __attribute__((interrupt()));
void tmr2_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_hwtimer_isr_common(&hwtimer_device_2);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __CH56X_TIMER_H__
#define __CH56X_TIMER_H__
#include "soc.h"
#ifdef __cplusplus
extern "C" {
#endif
union _timer_ctrl_mod
{
uint8_t reg;
struct
{
uint8_t mode_in : 1; // B.0 : RW, timer mode setting
uint8_t all_clear : 1; // B.1 : RW, clear FIFO/count/int-flag
uint8_t count_en : 1; // B.2 : RW, enable timer module
uint8_t out_en : 1; // B.3 : RW, timer output enable
uint8_t out_polar : 1; // B.4 : RW, output polarity for PWM mode
uint8_t resv_5 : 1;
uint8_t pwm_repeat : 2; // B.7-6 : RW, PWM repeat count, 1/4/8/16
};
struct
{
uint8_t stuff_0 : 6;
uint8_t cap_edge : 2; // B.7-6 : RW, capture edge mode
};
};
#define RB_TMR_MODE_IN 0x01
#define RB_TMR_ALL_CLEAR 0x02
#define RB_TMR_COUNT_EN 0x04
#define RB_TMR_OUT_EN 0x08
#define RB_TMR_OUT_POLAR 0x10
#define RB_TMR_CAP_COUNT 0x10
#define RB_TMR_PWM_REPEAT 0xc0
#define RB_TMR_CAP_EDGE 0xc0
#define TMR_MODE_TIMER_PWM 0
#define TMR_MODE_CAP_COUNT 1
#define TMR_PWM_REPEAT_1 0
#define TMR_PWM_REPEAT_4 1
#define TMR_PWM_REPEAT_8 2
#define TMR_PWM_REPEAT_16 3
#define TMR_CAP_EDGE_NONE 0
#define TMR_CAP_EDGE_BOTH 1
#define TMR_CAP_EDGE_F2F 2
#define TMR_CAP_EDGE_R2R 3
union _timer_ctrl_dma
{
uint8_t reg;
struct
{
uint8_t dma_enable : 1; // B.0 : RW, enable DMA
uint8_t resv_1 : 1;
uint8_t dma_loop : 1; // B.2 : RW, enable DMA address looping
uint8_t resv_3 : 5;
};
};
#define RB_TMR_DMA_ENABLE 0x01
#define RB_TMR_DMA_LOOP 0x04
union _timer_interrupt
{
uint8_t reg;
struct
{
uint8_t cyc_end : 1; // B.0
uint8_t data_act : 1; // B.1
uint8_t fifo_hf : 1; // B.2
uint8_t dma_end : 1; // B.3
uint8_t fifo_ov : 1; // B.4
uint8_t resv_5 : 3;
};
};
#define RB_TMR_IX_MASK 0x1f
#define RB_TMR_IE_CYC_END 0x01 // RW, enable interrupt for timer capture count timeout or PWM cycle end
#define RB_TMR_IE_DATA_ACT 0x02 // RW, enable interrupt for timer capture input action or PWM trigger
#define RB_TMR_IE_FIFO_HF 0x04 // RW, enable interrupt for timer FIFO half (capture fifo >=4 or PWM fifo <=3)
#define RB_TMR_IE_DMA_END 0x08 // RW, enable interrupt for timer1/2 DMA completion
#define RB_TMR_IE_FIFO_OV 0x10 // RW, enable interrupt for timer FIFO overflow
#define RB_TMR_IF_CYC_END 0x01 // RW1, interrupt flag for timer capture count timeout or PWM cycle end
#define RB_TMR_IF_DATA_ACT 0x02 // RW1, interrupt flag for timer capture input action or PWM trigger
#define RB_TMR_IF_FIFO_HF 0x04 // RW1, interrupt flag for timer FIFO half (capture fifo >=4 or PWM fifo <=3)
#define RB_TMR_IF_DMA_END 0x08 // RW1, interrupt flag for timer1/2 DMA completion
#define RB_TMR_IF_FIFO_OV 0x10 // RW1, interrupt flag for timer FIFO overflow
/*
* 0x00 R8_TMRx_CTRL_MOD: mode setting register
* 0x01 R8_TMRx_CTRL_DMA: DMA control register
* 0x02 R8_TMRx_INTER_EN: interrupt enable register
* 0x06 R8_TMRx_INT_FLAG: interrupt flag register
* 0x07 R8_TMRx_FIFO_COUNT: RO, FIFO count register
* 0x08 R32_TMRx_COUNT: RO, timer current count register
* 0x0c R32_TMRx_CNT_END: RW, timer count end register
* 0x10 R32_TMRx_FIFO: RO/WO, FIFO data register, LSB 26 bits
* 0x14 R32_TMRx_DMA_NOW: RW, DMA buffer current address, LSB 18 bits
* 0x18 R32_TMRx_DMA_BEG: RW, DMA buffer begin address, LSB 18 bits
* 0x1c R32_TMRx_DMA_END: RW, DMA buffer end address (exclusive), LSB 18 bits
*
* Note: DMA related registers (0x10,0x14,0x18,0x1c) are TMR1/2 only
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read.
*/
struct timer_registers
{
union _timer_ctrl_mod CTRL_MOD;
union _timer_ctrl_dma CTRL_DMA;
union _timer_interrupt INTER_EN;
uint8_t resv_3[3];
union _timer_interrupt INT_FLAG;
uint8_t FIFO_COUNT;
uint32_t COUNT;
uint32_t CNT_END;
uint32_t FIFO;
uint32_t DMA_NOW;
uint32_t DMA_BEG;
uint32_t DMA_END;
} __packed;
CHECK_STRUCT_SIZE(struct timer_registers, 0x20);
#ifdef __cplusplus
}
#endif
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include <ipc/completion.h>
#include <ipc/dataqueue.h>
#ifdef RT_USING_SERIAL_V2
#include <drivers/serial_v2.h>
#else
#include <drivers/serial.h>
#endif
#include "ch56x_sys.h"
#include "ch56x_uart.h"
#include "isr_sp.h"
#if !defined(BSP_USING_UART0) && !defined(BSP_USING_UART1) && \
!defined(BSP_USING_UART2) && !defined(BSP_USING_UART3)
#error "Please define at least one UARTx"
#endif
struct serial_device
{
struct rt_serial_device parent;
volatile struct uart_registers *reg_base;
irq_number_t irqn;
char *name;
};
#ifdef BSP_USING_UART0
static struct serial_device serial_device_0 =
{
.reg_base = (struct uart_registers *)UART0_REG_BASE,
.irqn = UART0_IRQn,
.name = "uart0",
};
#endif
#ifdef BSP_USING_UART1
static struct serial_device serial_device_1 =
{
.reg_base = (struct uart_registers *)UART1_REG_BASE,
.irqn = UART1_IRQn,
.name = "uart1",
};
#endif
#ifdef BSP_USING_UART2
static struct serial_device serial_device_2 =
{
.reg_base = (struct uart_registers *)UART2_REG_BASE,
.irqn = UART2_IRQn,
.name = "uart2",
};
#endif
#ifdef BSP_USING_UART3
static struct serial_device serial_device_3 =
{
.reg_base = (struct uart_registers *)UART3_REG_BASE,
.irqn = UART3_IRQn,
.name = "uart3",
};
#endif
static rt_err_t uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
struct serial_device *serial_device = (struct serial_device *)serial;
volatile struct uart_registers *uxreg = serial_device->reg_base;
union _uart_fcr fcr;
union _uart_lcr lcr;
uint32_t x;
x = 10 * sys_hclk_get() / 8 / cfg->baud_rate;
x = (x + 5) / 10;
uxreg->DL = x;
uxreg->DIV = 1;
lcr.reg = 0;
switch (cfg->data_bits)
{
case DATA_BITS_5:
lcr.word_sz = LCR_DATA_BITS_5;
break;
case DATA_BITS_6:
lcr.word_sz = LCR_DATA_BITS_6;
break;
case DATA_BITS_7:
lcr.word_sz = LCR_DATA_BITS_7;
break;
case DATA_BITS_8:
default:
lcr.word_sz = LCR_DATA_BITS_8;
break;
}
switch (cfg->stop_bits)
{
case STOP_BITS_2:
lcr.stop_bit = LCR_STOP_BITS_2;
break;
case STOP_BITS_1:
default:
lcr.stop_bit = LCR_STOP_BITS_1;
break;
}
switch (cfg->parity)
{
case PARITY_ODD:
lcr.par_mod = LCR_PARITY_ODD;
lcr.par_en = 1;
break;
case PARITY_EVEN:
lcr.par_mod = LCR_PARITY_EVEN;
lcr.par_en = 1;
break;
case PARITY_NONE:
default:
lcr.par_en = 0;
break;
}
uxreg->LCR.reg = lcr.reg;
fcr.reg = RB_FCR_FIFO_EN | RB_FCR_RX_FIFO_CLR | RB_FCR_TX_FIFO_CLR;
fcr.fifo_trig = UART_1BYTE_TRIG;
uxreg->FCR.reg = fcr.reg;
/* TXD pin output enable */
uxreg->IER.txd_en = 1;
return RT_EOK;
}
static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *args)
{
struct serial_device *serial_device = (struct serial_device *)serial;
volatile struct uart_registers *uxreg = serial_device->reg_base;
switch (cmd)
{
case RT_DEVICE_CTRL_CLR_INT:
uxreg->IER.recv_rdy = 0;
uxreg->IER.line_stat = 0;
uxreg->IER.thr_empty = 0;
rt_hw_interrupt_mask(serial_device->irqn);
break;
case RT_DEVICE_CTRL_SET_INT:
uxreg->FCR.fifo_trig = UART_1BYTE_TRIG;
uxreg->MCR.int_oe = 1;
uxreg->IER.recv_rdy = 1;
uxreg->IER.line_stat = 1;
if (serial->parent.open_flag & RT_DEVICE_FLAG_INT_TX)
{
uxreg->IER.thr_empty = 1;
}
rt_hw_interrupt_umask(serial_device->irqn);
break;
default:
break;
}
return RT_EOK;
}
static int uart_putc(struct rt_serial_device *serial, char ch)
{
struct serial_device *serial_device = (struct serial_device *)serial;
volatile struct uart_registers *uxreg = serial_device->reg_base;
if (serial->parent.open_flag & RT_DEVICE_FLAG_INT_TX)
{
if (uxreg->TFC >= UART_FIFO_SIZE)
return -1;
}
else
{
while (uxreg->TFC >= UART_FIFO_SIZE)
{
if (rt_thread_self() && rt_interrupt_get_nest() == 0)
rt_thread_yield();
}
}
uxreg->THR = ch;
return 1;
}
static int uart_getc(struct rt_serial_device *serial)
{
struct serial_device *serial_device = (struct serial_device *)serial;
volatile struct uart_registers *uxreg = serial_device->reg_base;
/* UART_II_RECV_RDY is cleared by reading RBR */
return (uxreg->RFC > 0) ? uxreg->RBR : -1;
}
static const struct rt_uart_ops uart_ops =
{
.configure = uart_configure,
.control = uart_control,
.putc = uart_putc,
.getc = uart_getc,
.dma_transmit = RT_NULL,
};
int rt_hw_uart_init(void)
{
struct serial_device *devices[4];
/* Note: HCLK should be at least 8MHz for default 115200 baud to work */
struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
int n = 0;
#ifdef BSP_USING_UART3
devices[n++] = &serial_device_3;
#endif
#ifdef BSP_USING_UART2
devices[n++] = &serial_device_2;
#endif
#ifdef BSP_USING_UART1
devices[n++] = &serial_device_1;
#endif
#ifdef BSP_USING_UART0
devices[n++] = &serial_device_0;
#endif
/* IMPORTANT: pin mode should be set properly @ board init */
while (--n >= 0)
{
uint32_t flag;
struct serial_device *serial = devices[n];
serial->parent.ops = &uart_ops;
serial->parent.config = config;
sys_clk_off_by_irqn(serial->irqn, SYS_SLP_CLK_ON);
flag = RT_DEVICE_FLAG_RDWR |
RT_DEVICE_FLAG_STREAM | // for converting '\n'
RT_DEVICE_FLAG_INT_TX |
RT_DEVICE_FLAG_INT_RX ;
rt_hw_serial_register(&serial->parent, serial->name, flag, RT_NULL);
/* rt_serial_open => uart_control with RT_DEVICE_CTRL_SET_INT */
}
return 0;
}
static void _uart_isr_common(struct serial_device *serial_device)
{
struct rt_serial_device *serial = &serial_device->parent;
volatile struct uart_registers *uxreg = serial_device->reg_base;
switch (uxreg->IIR.int_mask)
{
case UART_II_RECV_TOUT:
/* FIXME: It's a bad idea to read RBR to clear UART_II_RECV_TOUT.
* Race condition may happen that actual rx data is dropped.
*/
if (uxreg->RFC == 0)
{
uxreg->RBR;
//rt_hw_serial_isr(serial, RT_SERIAL_EVENT_RX_TIMEOUT);
break;
}
/* pass through as if UART_II_RECV_RDY */
case UART_II_RECV_RDY:
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_RX_IND);
break;
case UART_II_THR_EMPTY:
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_TX_DONE);
break;
case UART_II_LINE_STAT:
uxreg->LSR;
break;
case UART_II_MODEM_CHG:
uxreg->MSR;
break;
case UART_II_SLV_ADDR:
uxreg->IIR;
break;
default:
break;
}
}
#ifdef BSP_USING_UART0
void uart0_irq_handler(void) __attribute__((interrupt()));
void uart0_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_uart_isr_common(&serial_device_0);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
#ifdef BSP_USING_UART1
void uart1_irq_handler(void) __attribute__((interrupt()));
void uart1_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_uart_isr_common(&serial_device_1);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
#ifdef BSP_USING_UART2
void uart2_irq_handler(void) __attribute__((interrupt()));
void uart2_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_uart_isr_common(&serial_device_2);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
#ifdef BSP_USING_UART3
void uart3_irq_handler(void) __attribute__((interrupt()));
void uart3_irq_handler(void)
{
isr_sp_enter();
rt_interrupt_enter();
_uart_isr_common(&serial_device_3);
rt_interrupt_leave();
isr_sp_leave();
}
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __CH56X_UART_H__
#define __CH56X_UART_H__
#include "soc.h"
#ifdef __cplusplus
extern "C" {
#endif
#ifndef UART_FIFO_SIZE
#define UART_FIFO_SIZE 8
#endif
#ifndef UART_RECV_RDY_SZ
#define UART_RECV_RDY_SZ 7 // FIFO trigger level for rx data available
#endif
union _uart_mcr
{
uint8_t reg;
struct
{
uint8_t dtr : 1; // B.0 : RW, DTR output (UART0 only)
uint8_t rts : 1; // B.1 : RW, RTS output (UART0 only)
uint8_t out1 : 1; // B.2 : RW, user defined modem control (UART0 only)
uint8_t int_oe : 1; // B.3 : RW, interrupt output enable / OUT2
uint8_t loop : 1; // B.4 : RW, enable internal loop test (UART0 only)
uint8_t au_flow_en : 1; // B.5 : RW, enable CTS/RTS autoflow control
uint8_t tnow : 1; // B.6 : RW, enable DTR TNOW output (UART0 only)
uint8_t half : 1; // B.7 : RW, enable half-duplex mode (UART0 only)
};
};
#define RB_MCR_DTR 0x01
#define RB_MCR_RTS 0x02
#define RB_MCR_OUT1 0x04
#define RB_MCR_OUT2 0x08
#define RB_MCR_INT_OE 0x08
#define RB_MCR_LOOP 0x10
#define RB_MCR_AU_FLOW_EN 0x20
#define RB_MCR_TNOW 0x40
#define RB_MCR_HALF 0x80
union _uart_ier
{
uint8_t reg;
struct
{
uint8_t recv_rdy : 1; // B.0 : RW, enable rx data ready intr
uint8_t thr_empty : 1; // B.1 : RW, enable THR empty intr
uint8_t line_stat : 1; // B.2 : RW, enable rx line status intr
uint8_t modem_chg : 1; // B.3 : RW, enable modem status change intr (UART0 only)
uint8_t dtr_en : 1; // B.4 : RW, DTR/TNOW output pin enable (UART0 only)
uint8_t rts_en : 1; // B.5 : RW, RTS output pin enable (UART0 only)
uint8_t txd_en : 1; // B.6 : RW, TXD pin enable
uint8_t reset : 1; // B.7 : WZ, software reset control, active high, auto clear
};
};
#define RB_IER_RECV_RDY 0x01
#define RB_IER_THR_EMPTY 0x02
#define RB_IER_LINE_STAT 0x04
#define RB_IER_MODEM_CHG 0x08
#define RB_IER_DTR_EN 0x10
#define RB_IER_RTS_EN 0x20
#define RB_IER_TXD_EN 0x40
#define RB_IER_RESET 0x80
union _uart_fcr
{
uint8_t reg;
struct
{
uint8_t fifo_en : 1; // B.0 : RW, FIFO enable
uint8_t rx_fifo_clr : 1; // B.1 : WZ, write 1 to clear rx FIFO, auto clear
uint8_t tx_fifo_clr : 1; // B.2 : WZ, write 1 to clear tx FIFO, auto clear
uint8_t resv_3 : 3;
uint8_t fifo_trig : 2; // B.7-6 : RW, rx FIFO trigger level, 1/2/4/7 bytes
};
};
#define RB_FCR_FIFO_EN 0x01
#define RB_FCR_RX_FIFO_CLR 0x02
#define RB_FCR_TX_FIFO_CLR 0x04
#define RB_FCR_FIFO_TRIG 0xc0
#define UART_1BYTE_TRIG 0
#define UART_2BYTE_TRIG 1
#define UART_4BYTE_TRIG 2
#define UART_7BYTE_TRIG 3
union _uart_lcr
{
uint8_t reg;
struct
{
uint8_t word_sz : 2; // B.1-0 : RW, word bit length, 5/6/7/8 bits
uint8_t stop_bit : 1; // B.2 : RW, stop bit length, 1/2 bits
uint8_t par_en : 1; // B.3 : RW, parity enable
uint8_t par_mod : 2; // B.5-4 : RW, parity mode, odd/even/mark/space
uint8_t break_en : 1; // B.6 : RW, force BREAK line condition
uint8_t dlab : 1; // B.7 : RW, user defined general purpose bit
};
};
#define RB_LCR_WORD_SZ 0x03
#define RB_LCR_STOP_BIT 0x04
#define RB_LCR_PAR_EN 0x08
#define RB_LCR_PAR_MOD 0x30
#define RB_LCR_BREAK_EN 0x40
#define RB_LCR_DLAB 0x80
#define RB_LCR_GP_BIT 0x80
#define LCR_DATA_BITS_5 0
#define LCR_DATA_BITS_6 1
#define LCR_DATA_BITS_7 2
#define LCR_DATA_BITS_8 3
#define LCR_STOP_BITS_1 0
#define LCR_STOP_BITS_2 1
#define LCR_PARITY_ODD 0
#define LCR_PARITY_EVEN 1
#define LCR_PARITY_MARK 2
#define LCR_PARITY_SPACE 3
union _uart_iir
{
uint8_t reg;
struct
{
uint8_t int_mask : 4; // B.3-0 : RO, interrupt mask (intr if B.0 is 0)
uint8_t resv_4 : 2;
uint8_t fifo_id : 2; // B.7-6 : RO, FIFO enabled flag
};
};
#define RB_IIR_NO_INT 0x01
#define RB_IIR_INT_MASK 0x0f
#define RB_IIR_FIFO_ID 0xc0
/* RB_IIR_INT_MASK (IIR bits 3:0) definition
*/
#define UART_II_SLV_ADDR 0x0e // UART0 slave address match interrupt
#define UART_II_LINE_STAT 0x06 // rx line status interrupt
#define UART_II_RECV_RDY 0x04 // rx data available interrupt
#define UART_II_RECV_TOUT 0x0c // rx fifo timeout interrupt
#define UART_II_THR_EMPTY 0x02 // THR empty interrupt
#define UART_II_MODEM_CHG 0x00 // UART0 modem status change interrupt
#define UART_II_NO_INTER 0x01 // no interrupt pending
union _uart_lsr
{
uint8_t reg;
struct
{
uint8_t data_rdy : 1; // B.0 : RO, rx FIFO data ready
uint8_t over_err : 1; // B.1 : RZ, rx FIFO data overrun
uint8_t par_err : 1; // B.2 : RZ, rx parity error
uint8_t frame_err : 1; // B.3 : RZ, rx frame error
uint8_t break_err : 1; // B.4 : RZ, rx BREAK detected
uint8_t tx_fifo_emp : 1; // B.5 : RO, tx FIFO empty
uint8_t tx_all_emp : 1; // B.6 : RO, THR/TSR all empty
uint8_t err_rx_fifo : 1; // B.7 : RO, PAR/FRAME/BREAK ERR in rx FIFO
};
};
#define RB_LSR_DATA_RDY 0x01
#define RB_LSR_OVER_ERR 0x02
#define RB_LSR_PAR_ERR 0x04
#define RB_LSR_FRAME_ERR 0x08
#define RB_LSR_BREAK_ERR 0x10
#define RB_LSR_TX_FIFO_EMP 0x20
#define RB_LSR_TX_ALL_EMP 0x40
#define RB_LSR_ERR_RX_FIFO 0x80
union _uart_msr
{
uint8_t reg;
struct
{
uint8_t cts_chg : 1; // B.0 : RZ, CTS input changed
uint8_t dsr_chg : 1; // B.1 : RZ, DSR input changed
uint8_t ri_chg : 1; // B.2 : RZ, RI input changed
uint8_t dcd_chg : 1; // B.3 : RZ, DCD input changed
uint8_t cts : 1; // B.4 : RO, CTS action status
uint8_t dsr : 1; // B.5 : RO, DSR action status
uint8_t ri : 1; // B.6 : RO, RI action status
uint8_t dcd : 1; // B.7 : RO, DCD action status
};
};
#define RB_MSR_CTS_CHG 0x01
#define RB_MSR_DSR_CHG 0x02
#define RB_MSR_RI_CHG 0x04
#define RB_MSR_DCD_CHG 0x08
#define RB_MSR_CTS 0x10
#define RB_MSR_DSR 0x20
#define RB_MSR_RI 0x40
#define RB_MSR_DCD 0x80
/*
* 0x00 R8_UARTx_MCR: Modem Control Register
* 0x01 R8_UARTx_IER: Interrupt Enable Register
* 0x02 R8_UARTx_FCR: FIFO Control Register
* 0x03 R8_UARTx_LCR: Line Control Register
* 0x04 R8_UARTx_IIR: Interrupt Identification Register
* 0x05 R8_UARTx_LSR: Line Status Register
* 0x06 R8_UARTx_MSR: Modem Status Register (UART0 only)
* 0x08 R8_UARTx_RBR: Rx Buffer Register
* 0x08 R8_UARTx_THR: Tx Hold Register
* 0x0a R8_UARTx_RFC: Rx FIFO count register
* 0x0b R8_UARTx_TFC: Tx FIFO count register
* 0x0c R16_UARTx_DL: Divisor Latch
* 0x0e R8_UARTx_DIV: frequency pre divider
* 0x0f R8_UARTx_ADR: Address Register (UART0 only)
*
* CAVEAT: gcc (as of 8.2.0) tends to read 32-bit word for bit field test.
* Be careful for those with side effect for read (e.g. RBR, IIR).
*/
struct uart_registers
{
union _uart_mcr MCR;
union _uart_ier IER;
union _uart_fcr FCR;
union _uart_lcr LCR;
union _uart_iir IIR;
union _uart_lsr LSR;
union _uart_lsr MSR;
uint8_t resv_7;
union
{
uint8_t RBR;
uint8_t THR;
};
uint8_t resv_9;
uint8_t RFC;
uint8_t TFC;
uint16_t DL;
uint8_t DIV;
uint8_t ADR;
} __packed;
CHECK_STRUCT_SIZE(struct uart_registers, 0x10);
int rt_hw_uart_init(void);
#ifdef __cplusplus
}
#endif
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-20 Emuzit first version
*/
#include <rthw.h>
#include <rtdebug.h>
#include <drivers/watchdog.h>
#include "ch56x_sys.h"
#define WDOG_HICOUNT_MAX 0xfff // enough to hold (4095 * 120M/524288) >> 8
struct watchdog_device
{
rt_watchdog_t parent;
volatile uint32_t hicount;
uint32_t timeout;
uint32_t reload;
uint8_t is_start;
};
static struct watchdog_device watchdog_device;
static void wdt_reload_counter(rt_watchdog_t *wdt, int cmd)
{
struct watchdog_device *wdt_dev = (void *)wdt;
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
rt_base_t level;
level = rt_hw_interrupt_disable();
/* reload WDOG_COUNT also clears RB_WDOG_INT_FLAG*/
sys->WDOG_COUNT = (uint8_t)wdt_dev->reload;
wdt_dev->hicount = wdt_dev->reload >> 8;
if (cmd != RT_DEVICE_CTRL_WDT_KEEPALIVE && wdt_dev->is_start)
{
sys_safe_access_enter(sys);
if ((wdt_dev->reload >> 8) == WDOG_HICOUNT_MAX)
{
/* WDOG_COUNT can work on its own, no wdog_irq needed */
sys->RST_WDOG_CTRL.reg = wdog_ctrl_wdat(RB_WDOG_RST_EN);
rt_hw_interrupt_mask(WDOG_IRQn);
}
else
{
/* Extend wdt with wdt_dev->hicount through wdog_irq.
* CAVEAT: wdt not effective if global interrupt disabled !!
*/
sys->RST_WDOG_CTRL.reg = wdog_ctrl_wdat(RB_WDOG_INT_EN);
rt_hw_interrupt_umask(WDOG_IRQn);
}
sys_safe_access_leave(sys);
}
rt_hw_interrupt_enable(level);
}
static uint32_t wdt_get_timeleft(rt_watchdog_t *wdt)
{
struct watchdog_device *wdt_dev = (void *)wdt;
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
uint32_t countleft;
uint64_t count64;
if ((wdt_dev->reload >> 8) == WDOG_HICOUNT_MAX)
{
/* WDOG_COUNT can work on its own, without hicount */
countleft = 0xff - sys->WDOG_COUNT;
}
else
{
uint32_t c1 = sys->WDOG_COUNT;
uint32_t hc = wdt_dev->hicount;
uint32_t c2 = sys->WDOG_COUNT;
/* check if WDOG_COUNT overflows between c1/c2 reads */
if (c2 < c1)
{
rt_base_t level = rt_hw_interrupt_disable();
hc = wdt_dev->hicount;
if (sys->RST_WDOG_CTRL.wdog_int_flag && sys->RST_WDOG_CTRL.wdog_int_en)
{
hc++;
}
rt_hw_interrupt_enable(level);
}
countleft = ((WDOG_HICOUNT_MAX << 8) + 0xff) - ((hc << 8) + c2);
}
/* convert wdt count to seconds : count / (Fsys/524288) */
count64 = countleft;
return (uint32_t)((count64 << 19) / sys_hclk_get());
}
static uint32_t _convert_timeout_to_reload(uint32_t seconds)
{
uint32_t N, R, Fsys, reload = -1;
/* timeout is limited to 4095, not to overflow 32-bit (T * 2^19) */
if (seconds < 4096)
{
/* watchdog timer is clocked at Fsys/524288, arround 3~228Hz */
Fsys = sys_hclk_get();
/* T * (Fsys/2^19) => (T * N) + T * (R/2^19) */
N = Fsys >> 19;
R = Fsys & 0x7ffff;
reload = (WDOG_HICOUNT_MAX << 8) + 0xff;
reload -= seconds * N + ((seconds * R) >> 19) + 1;
}
return reload;
}
static void _stop_wdog_operation()
{
volatile struct sys_registers *sys = (void *)SYS_REG_BASE;
rt_base_t level = rt_hw_interrupt_disable();
sys_safe_access_enter(sys);
sys->RST_WDOG_CTRL.reg = wdog_ctrl_wdat(RB_WDOG_INT_FLAG);
sys_safe_access_leave(sys);
rt_hw_interrupt_enable(level);
rt_hw_interrupt_mask(WDOG_IRQn);
}
static rt_err_t wdt_init(rt_watchdog_t *wdt)
{
struct watchdog_device *wdt_dev = (void *)wdt;
_stop_wdog_operation();
wdt_dev->is_start = 0;
wdt_dev->timeout = -1;
wdt_dev->reload = -1;
return RT_EOK;
}
static rt_err_t wdt_control(rt_watchdog_t *wdt, int cmd, void *arg)
{
struct watchdog_device *wdt_dev = (void *)wdt;
uint32_t reload, timeout;
switch (cmd)
{
case RT_DEVICE_CTRL_WDT_KEEPALIVE:
wdt_reload_counter(wdt, cmd);
break;
case RT_DEVICE_CTRL_WDT_GET_TIMELEFT:
*((uint32_t *)arg) = wdt_get_timeleft(wdt);
break;
case RT_DEVICE_CTRL_WDT_GET_TIMEOUT:
*((uint32_t *)arg) = wdt_dev->timeout;
break;
case RT_DEVICE_CTRL_WDT_SET_TIMEOUT:
/* CAVEAT: Setting timeout larger than an 8-bit WDOG_COUNT can
* hold turns the wdog into interrupt mode, which makes wdog
* usless if cause of death is lost global interrupt enable.
*/
timeout = *((uint32_t *)arg);
reload = _convert_timeout_to_reload(timeout);
if ((reload >> 8) > WDOG_HICOUNT_MAX)
{
return -RT_EINVAL;
}
wdt_dev->timeout = timeout;
wdt_dev->reload = reload;
/* FIXME: code example implies wdt started by SET_TIMEOUT ? */
case RT_DEVICE_CTRL_WDT_START:
if ((wdt_dev->reload >> 8) > WDOG_HICOUNT_MAX)
{
return -RT_EINVAL;
}
wdt_dev->is_start = 1;
wdt_reload_counter(wdt, cmd);
break;
case RT_DEVICE_CTRL_WDT_STOP:
_stop_wdog_operation();
wdt_dev->is_start = 0;
break;
default:
return -RT_ERROR;
}
return RT_EOK;
}
static struct rt_watchdog_ops watchdog_ops =
{
.init = wdt_init,
.control = wdt_control,
};
int rt_hw_wdt_init(void)
{
rt_uint32_t flag;
watchdog_device.parent.ops = &watchdog_ops;
flag = RT_DEVICE_FLAG_DEACTIVATE;
return rt_hw_watchdog_register(&watchdog_device.parent, "wdt", flag, RT_NULL);
}
INIT_BOARD_EXPORT(rt_hw_wdt_init);
void wdog_irq_handler(void) __attribute__((interrupt()));
void wdog_irq_handler(void)
{
volatile struct pfic_registers *pfic;
volatile struct sys_registers *sys;
rt_interrupt_enter();
sys = (struct sys_registers *)SYS_REG_BASE;
/* FIXME: RB_WDOG_INT_FLAG seems completely not functioning at all !!
* It's not set at WDOG_COUNT overflow, writing 1 to it does not clear
* wdt interrupt. Bit 16 of pfic->IPR[0] is not effective thereof.
*/
if (watchdog_device.hicount < WDOG_HICOUNT_MAX)
{
watchdog_device.hicount++;
/* clear interrupt flag */
//sys->RST_WDOG_CTRL.reg |= RB_WDOG_INT_FLAG;
sys->WDOG_COUNT = sys->WDOG_COUNT;
}
else
{
/* reset system if watchdog timeout */
uint8_t u8v = RB_SOFTWARE_RESET | RB_WDOG_INT_FLAG;
sys_safe_access_enter(sys);
sys->RST_WDOG_CTRL.reg = wdog_ctrl_wdat(u8v);
sys_safe_access_leave(sys);
}
rt_interrupt_leave();
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-27 Emuzit first version
*/
#ifndef __ISR_SP_H__
#define __ISR_SP_H__
/* usrstack is no more in use right after rt_system_scheduler_start().
* It is also the time global interrupt is enabled.
*/
#define isr_sp_enter() \
asm("la t0, rt_interrupt_nest"); \
asm("bnez t0, 1f"); \
asm("la t0, _eusrstack"); \
asm("sw sp, -4(t0)"); \
asm("addi sp, t0, -4"); \
asm("1:")
#define isr_sp_leave() \
asm("la t0, rt_interrupt_nest"); \
asm("bnez t0, 1f"); \
asm("la t0, _eusrstack"); \
asm("lw sp, -4(t0)"); \
asm("1:")
#endif
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __SOC_H__
#define __SOC_H__
#include <stdint.h>
#include <stddef.h>
#include <assert.h>
#if !defined(SOC_CH567) && \
!defined(SOC_CH568) && \
!defined(SOC_SERIES_CH569)
#define SOC_SERIES_CH569
#endif
#define CHECK_STRUCT_SIZE(s, size) \
static_assert(sizeof(s) == size, #s " has wrong size")
#define BITS_SET(x, bits) do x |= bits; while(0)
#define BITS_CLR(x, bits) do x &= ~bits; while(0)
#define FLASH_BASE_ADDRESS 0x00000000
#define RAMS_BASE_ADDRESS 0x20000000
#define RAMX_BASE_ADDRESS 0x20020000
#define BUS8_BASE_ADDRESS 0x80000000
#ifdef SOC_SERIES_CH569
#define RAMS_SIZE 16
#else
#define RAMS_SIZE 32
#endif
#define RAMS_END (RAMS_BASE_ADDRESS + RAMS_SIZE * 1024)
#define SYS_REG_BASE 0x40001000
#define GPIO_REG_BASE 0x40001000
#define GPIO_REG_BASE_PA 0x40001040
#define GPIO_REG_BASE_PB 0x40001060
#define GPIO_PORTS 2 // 2 ports : PA & PB
#define GPIO_PA_PIN_START 0 // PA : pin number 0~31
#define GPIO_PB_PIN_START 32 // PB : pin number 32~63
#ifdef SOC_SERIES_CH569
#define GPIO_PA_PIN_MARK 0x00ffffff // PA : bits 0~23
#define GPIO_PB_PIN_MARK 0x01ffffff // PB : bits 0~24
#else
#define GPIO_PA_PIN_MARK 0x0000ffff // PA : bits 0~15
#define GPIO_PB_PIN_MARK 0x00003fff // PB : bits 0~13
#endif
#define TMR0_REG_BASE 0x40002000
#define TMR1_REG_BASE 0x40002400
#define TMR2_REG_BASE 0x40002800
#define UART0_REG_BASE 0x40003000
#define UART1_REG_BASE 0x40003400
#define UART2_REG_BASE 0x40003800
#define UART3_REG_BASE 0x40003c00
#define SPI0_REG_BASE 0x40004000
#define SPI1_REG_BASE 0x40004400
#define PWMX_REG_BASE 0x40005000
#define PFIC_REG_BASE 0xe000e000
#define SysTick_REG_BASE 0xe000f000
#ifdef SOC_SERIES_CH569
#define HSPI_REG_BASE 0x40006000 // CH569W
#define ECDC_REG_BASE 0x40007000
#define USBSS_REG_BASE 0x40008000
#define USBHS_REG_BASE 0x40009000
#define EMMC_REG_BASE 0x4000a000
#define SERDES_REG_BASE 0x4000b000
#define ETH_REG_BASE 0x4000c000 // CH565W/CH569W
#define DVP_REG_BASE 0x4000e000 // CH565W/CH565M
#else
#define LED_REG_BASE 0x40006000
#define USB0_REG_BASE 0x40008000 // CH567
#define USB1_REG_BASE 0x40009000 // CH567
#define USB_REG_BASE 0x40009000 // CH568
#define SDC_REG_BASE 0x4000a000
#define SATA_REG_BASE 0x4000b000 // CH568
#define ECDC_REG_BASE 0x4000c400
#endif
#if defined(SOC_SERIES_CH569)
typedef enum
{
PWMX_OFFn = 0,
NMI_IRQn = 2,
EXC_IRQn = 3,
SysTick_IRQn = 12,
SWI_IRQn = 14,
WDOG_IRQn = 16,
TMR0_IRQn = 17,
GPIO_IRQn = 18,
SPI0_IRQn = 19,
USBSS_IRQn = 20,
LINK_IRQn = 21,
TMR1_IRQn = 22,
TMR2_IRQn = 23,
UART0_IRQn = 24,
USBHS_IRQn = 25,
EMMC_IRQn = 26,
DVP_IRQn = 27,
HSPI_IRQn = 28,
SPI1_IRQn = 29,
UART1_IRQn = 30,
UART2_IRQn = 31,
UART3_IRQn = 32,
SerDes_IRQn = 33,
ETH_IRQn = 34,
PMT_IRQn = 35,
ECDC_IRQn = 36,
END_OF_IRQn
} irq_number_t;
#else
typedef enum
{
PWMX_OFFn = 0,
SOFT_IRQn = 0,
TMR0_IRQn = 1,
GPIO_IRQn = 2,
SPI0_IRQn = 3,
USB0_IRQn = 4, // CH567
SATA_IRQn = 4, // CH568
TMR1_IRQn = 5,
TMR2_IRQn = 6,
UART0_IRQn = 7,
USB1_IRQn = 8,
SDC_IRQn = 9,
ECDC_IRQn = 10,
LED_IRQn = 11,
SPI1_IRQn = 12,
UART1_IRQn = 13,
UART2_IRQn = 14,
UART3_IRQn = 15,
END_OF_IRQn
} irq_number_t;
#endif
#endif
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-09-09 WCH the first version
* 2022-07-15 Emuzit adapt to ch569w-evt
*/
#include "cpuport.h"
.global swi_handler
.align 2
swi_handler:
/* save all from thread context */
#ifdef ARCH_RISCV_FPU
addi sp, sp, -32 * FREGBYTES
FSTORE f0, 0 * FREGBYTES(sp)
FSTORE f1, 1 * FREGBYTES(sp)
FSTORE f2, 2 * FREGBYTES(sp)
FSTORE f3, 3 * FREGBYTES(sp)
FSTORE f4, 4 * FREGBYTES(sp)
FSTORE f5, 5 * FREGBYTES(sp)
FSTORE f6, 6 * FREGBYTES(sp)
FSTORE f7, 7 * FREGBYTES(sp)
FSTORE f8, 8 * FREGBYTES(sp)
FSTORE f9, 9 * FREGBYTES(sp)
FSTORE f10, 10 * FREGBYTES(sp)
FSTORE f11, 11 * FREGBYTES(sp)
FSTORE f12, 12 * FREGBYTES(sp)
FSTORE f13, 13 * FREGBYTES(sp)
FSTORE f14, 14 * FREGBYTES(sp)
FSTORE f15, 15 * FREGBYTES(sp)
FSTORE f16, 16 * FREGBYTES(sp)
FSTORE f17, 17 * FREGBYTES(sp)
FSTORE f18, 18 * FREGBYTES(sp)
FSTORE f19, 19 * FREGBYTES(sp)
FSTORE f20, 20 * FREGBYTES(sp)
FSTORE f21, 21 * FREGBYTES(sp)
FSTORE f22, 22 * FREGBYTES(sp)
FSTORE f23, 23 * FREGBYTES(sp)
FSTORE f24, 24 * FREGBYTES(sp)
FSTORE f25, 25 * FREGBYTES(sp)
FSTORE f26, 26 * FREGBYTES(sp)
FSTORE f27, 27 * FREGBYTES(sp)
FSTORE f28, 28 * FREGBYTES(sp)
FSTORE f29, 29 * FREGBYTES(sp)
FSTORE f30, 30 * FREGBYTES(sp)
FSTORE f31, 31 * FREGBYTES(sp)
#endif
addi sp, sp, -32 * REGBYTES
STORE x1, 1 * REGBYTES(sp)
/* saved MPIE */
li x1, 0x80
STORE x1, 2 * REGBYTES(sp)
STORE x4, 4 * REGBYTES(sp)
STORE x5, 5 * REGBYTES(sp)
STORE x6, 6 * REGBYTES(sp)
STORE x7, 7 * REGBYTES(sp)
STORE x8, 8 * REGBYTES(sp)
STORE x9, 9 * REGBYTES(sp)
STORE x10, 10 * REGBYTES(sp)
STORE x11, 11 * REGBYTES(sp)
STORE x12, 12 * REGBYTES(sp)
STORE x13, 13 * REGBYTES(sp)
STORE x14, 14 * REGBYTES(sp)
STORE x15, 15 * REGBYTES(sp)
STORE x16, 16 * REGBYTES(sp)
STORE x17, 17 * REGBYTES(sp)
STORE x18, 18 * REGBYTES(sp)
STORE x19, 19 * REGBYTES(sp)
STORE x20, 20 * REGBYTES(sp)
STORE x21, 21 * REGBYTES(sp)
STORE x22, 22 * REGBYTES(sp)
STORE x23, 23 * REGBYTES(sp)
STORE x24, 24 * REGBYTES(sp)
STORE x25, 25 * REGBYTES(sp)
STORE x26, 26 * REGBYTES(sp)
STORE x27, 27 * REGBYTES(sp)
STORE x28, 28 * REGBYTES(sp)
STORE x29, 29 * REGBYTES(sp)
STORE x30, 30 * REGBYTES(sp)
STORE x31, 31 * REGBYTES(sp)
/* rt_thread_switch_interrupt_flag not 0 => clear & switch thread */
la t0, rt_thread_switch_interrupt_flag
lw t1, 0(t0)
beqz t1, .L_restore
sw zero, 0(t0)
/* prepare to switch to rt_interrupt_to_thread */
csrr t1, mepc
STORE t1, 0 * REGBYTES(sp)
la t0, rt_interrupt_from_thread
LOAD t1, 0(t0)
STORE sp, 0(t1)
la t0, rt_interrupt_to_thread
LOAD t1, 0(t0)
LOAD sp, 0(t1)
LOAD t1, 0 * REGBYTES(sp)
csrw mepc, t1
.L_restore:
/* clear software interrupt */
jal pfic_swi_pendreset
LOAD x1, 1 * REGBYTES(sp)
li t0, 0x1800
csrs mstatus, t0
LOAD t0, 2 * REGBYTES(sp)
csrs mstatus, t0
LOAD x4, 4 * REGBYTES(sp)
LOAD x5, 5 * REGBYTES(sp)
LOAD x6, 6 * REGBYTES(sp)
LOAD x7, 7 * REGBYTES(sp)
LOAD x8, 8 * REGBYTES(sp)
LOAD x9, 9 * REGBYTES(sp)
LOAD x10, 10 * REGBYTES(sp)
LOAD x11, 11 * REGBYTES(sp)
LOAD x12, 12 * REGBYTES(sp)
LOAD x13, 13 * REGBYTES(sp)
LOAD x14, 14 * REGBYTES(sp)
LOAD x15, 15 * REGBYTES(sp)
LOAD x16, 16 * REGBYTES(sp)
LOAD x17, 17 * REGBYTES(sp)
LOAD x18, 18 * REGBYTES(sp)
LOAD x19, 19 * REGBYTES(sp)
LOAD x20, 20 * REGBYTES(sp)
LOAD x21, 21 * REGBYTES(sp)
LOAD x22, 22 * REGBYTES(sp)
LOAD x23, 23 * REGBYTES(sp)
LOAD x24, 24 * REGBYTES(sp)
LOAD x25, 25 * REGBYTES(sp)
LOAD x26, 26 * REGBYTES(sp)
LOAD x27, 27 * REGBYTES(sp)
LOAD x28, 28 * REGBYTES(sp)
LOAD x29, 29 * REGBYTES(sp)
LOAD x30, 30 * REGBYTES(sp)
LOAD x31, 31 * REGBYTES(sp)
addi sp, sp, 32 * REGBYTES
/* load float reg */
#ifdef ARCH_RISCV_FPU
FLOAD f0, 0 * FREGBYTES(sp)
FLOAD f1, 1 * FREGBYTES(sp)
FLOAD f2, 2 * FREGBYTES(sp)
FLOAD f3, 3 * FREGBYTES(sp)
FLOAD f4, 4 * FREGBYTES(sp)
FLOAD f5, 5 * FREGBYTES(sp)
FLOAD f6, 6 * FREGBYTES(sp)
FLOAD f7, 7 * FREGBYTES(sp)
FLOAD f8, 8 * FREGBYTES(sp)
FLOAD f9, 9 * FREGBYTES(sp)
FLOAD f10, 10 * FREGBYTES(sp)
FLOAD f11, 11 * FREGBYTES(sp)
FLOAD f12, 12 * FREGBYTES(sp)
FLOAD f13, 13 * FREGBYTES(sp)
FLOAD f14, 14 * FREGBYTES(sp)
FLOAD f15, 15 * FREGBYTES(sp)
FLOAD f16, 16 * FREGBYTES(sp)
FLOAD f17, 17 * FREGBYTES(sp)
FLOAD f18, 18 * FREGBYTES(sp)
FLOAD f19, 19 * FREGBYTES(sp)
FLOAD f20, 20 * FREGBYTES(sp)
FLOAD f21, 21 * FREGBYTES(sp)
FLOAD f22, 22 * FREGBYTES(sp)
FLOAD f23, 23 * FREGBYTES(sp)
FLOAD f24, 24 * FREGBYTES(sp)
FLOAD f25, 25 * FREGBYTES(sp)
FLOAD f26, 26 * FREGBYTES(sp)
FLOAD f27, 27 * FREGBYTES(sp)
FLOAD f28, 28 * FREGBYTES(sp)
FLOAD f29, 29 * FREGBYTES(sp)
FLOAD f30, 30 * FREGBYTES(sp)
FLOAD f31, 31 * FREGBYTES(sp)
addi sp, sp, 32 * FREGBYTES
#endif
mret
此差异已折叠。
mainmenu "RT-Thread Configuration"
config BSP_DIR
string
option env="BSP_ROOT"
default "."
config RTT_DIR
string
option env="RTT_ROOT"
default "../../../.."
config PKGS_DIR
string
option env="PKGS_ROOT"
default "packages"
source "$RTT_DIR/Kconfig"
source "$PKGS_DIR/Kconfig"
source "../Libraries/Kconfig"
source "board/Kconfig"
import os
from building import *
objs = []
cwd = GetCurrentDir()
list = os.listdir(cwd)
for d in list:
if os.path.isfile(os.path.join(cwd, d, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../../../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
try:
from building import *
except:
print('Cannot find RT-Thread root directory, please check RTT_ROOT')
print('RTT_ROOT: ' + RTT_ROOT)
exit(-1)
TARGET = 'rtthread.' + rtconfig.TARGET_EXT
DefaultEnvironment(tools=[])
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
objs.extend(SConscript('../Libraries/ch56x_drivers/SConscript',
variant_dir='build/libraries/ch56x_drivers', duplicate=0))
# make a building
DoBuilding(TARGET, objs)
from building import *
cwd = GetCurrentDir()
src = Split("""
main.c
""")
path = [cwd, str(Dir('#'))]
group = DefineGroup('Applications', src, depend=[''], CPPPATH=path)
Return('group')
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
* 2022-07-20 Emuzit add watchdog test
* 2022-07-26 Emuzit add hwtimer test
*/
#include <rtthread.h>
#include <rtdebug.h>
#include <drivers/pin.h>
#include <drivers/watchdog.h>
#include <drivers/hwtimer.h>
#include "board.h"
static const rt_base_t gpio_int_pins[8] = GPIO_INT_PINS;
/* note : PIN_IRQ_MODE_RISING_FALLING not supported */
static const uint32_t gpint_mode[] =
{
PIN_IRQ_MODE_RISING,
PIN_IRQ_MODE_RISING,
PIN_IRQ_MODE_RISING,
PIN_IRQ_MODE_RISING,
PIN_IRQ_MODE_FALLING,
PIN_IRQ_MODE_FALLING,
PIN_IRQ_MODE_FALLING,
PIN_IRQ_MODE_FALLING,
};
static struct rt_mailbox *gpint_mb = RT_NULL;
static struct rt_thread *gpint_thread = RT_NULL;
static rt_base_t led0, led1;
static rt_device_t wdg_dev;
static struct rt_device *tmr_dev_0;
static struct rt_device *tmr_dev_1;
static void gpio_int_callback(void *pin)
{
led1 = (led1 == PIN_LOW) ? PIN_HIGH : PIN_LOW;
rt_pin_write(LED1_PIN, led1);
if (gpint_mb != RT_NULL)
{
/* non-block, silently ignore RT_EFULL */
rt_mb_send(gpint_mb, (uint32_t)pin);
}
}
static void gpio_int_thread(void *param)
{
while (1)
{
rt_err_t res;
uint32_t pin;
res = rt_mb_recv(gpint_mb, &pin, RT_WAITING_FOREVER);
if (res == RT_EOK)
{
rt_kprintf("gpio_int #%d (%d)\n", pin, rt_pin_read(pin));
}
rt_thread_mdelay(100);
#ifdef RT_USING_WDT
rt_device_control(wdg_dev, RT_DEVICE_CTRL_WDT_KEEPALIVE, RT_NULL);
#endif
}
}
#ifdef RT_USING_HWTIMER
static rt_err_t tmr_timeout_cb(rt_device_t dev, rt_size_t size)
{
rt_tick_t tick = rt_tick_get();
int tmr = (dev == tmr_dev_1) ? 1 : 0;
rt_kprintf("hwtimer %d timeout callback fucntion @tick %d\n", tmr, tick);
return RT_EOK;
}
#endif
void main(void)
{
rt_hwtimerval_t timerval;
rt_hwtimer_mode_t mode;
rt_size_t tsize;
uint32_t seconds;
rt_err_t res;
int i;
rt_kprintf("\nCH569W-R0-1v0, HCLK: %dMHz\n\n", sys_hclk_get() / 1000000);
/* Enable all gpio interrupt with various modes.
* LED0 or GND touching can be used to trigger pin interrupt.
*/
gpint_mb = rt_mb_create("pximb", 8, RT_IPC_FLAG_FIFO);
if (gpint_mb == RT_NULL)
{
rt_kprintf("gpint mailbox create failed !\n");
}
else
{
gpint_thread = rt_thread_create("pxith", gpio_int_thread, RT_NULL,
512, RT_MAIN_THREAD_PRIORITY, 50);
if (gpint_thread == RT_NULL)
{
rt_kprintf("gpint thread create failed !\n");
}
else
{
rt_thread_startup(gpint_thread);
for (i = 0; i < 8; i++)
{
rt_base_t pin = gpio_int_pins[i];
rt_pin_mode(pin, PIN_MODE_INPUT_PULLUP);
res = rt_pin_attach_irq(
pin, gpint_mode[i], gpio_int_callback, (void *)pin);
if (res != RT_EOK)
{
rt_kprintf("rt_pin_attach_irq failed (%d:%d)\n", i, res);
}
else
{
rt_pin_irq_enable(pin, PIN_IRQ_ENABLE);
}
}
}
}
#ifdef RT_USING_WDT
/* Test watchdog with 30s timeout, keepalive with gpio interrupt.
*
* CAVEAT: With only 8-bit WDOG_COUNT and fixed clocking at Fsys/524288,
* watchdog of ch56x may be quite limited with very short timeout.
*/
seconds = 30;
wdg_dev = rt_device_find("wdt");
if (!wdg_dev)
{
rt_kprintf("watchdog device not found !\n");
}
else if (rt_device_init(wdg_dev) != RT_EOK ||
rt_device_control(wdg_dev, RT_DEVICE_CTRL_WDT_SET_TIMEOUT, &seconds) != RT_EOK)
{
rt_kprintf("watchdog setup failed !\n");
}
else
{
rt_kprintf("WDT_TIMEOUT in %d seconds, trigger gpio interrupt to keep alive.\n\n", seconds);
}
#endif
#ifdef RT_USING_HWTIMER
/* setup two timers, ONESHOT & PERIOD each
*/
tmr_dev_0 = rt_device_find("timer0");
tmr_dev_1 = rt_device_find("timer1");
if (tmr_dev_0 == RT_NULL || tmr_dev_1 == RT_NULL)
{
rt_kprintf("hwtimer device(s) not found !\n");
}
else if (rt_device_open(tmr_dev_0, RT_DEVICE_OFLAG_RDWR) != RT_EOK ||
rt_device_open(tmr_dev_1, RT_DEVICE_OFLAG_RDWR) != RT_EOK)
{
rt_kprintf("hwtimer device(s) open failed !\n");
}
else
{
rt_device_set_rx_indicate(tmr_dev_0, tmr_timeout_cb);
rt_device_set_rx_indicate(tmr_dev_1, tmr_timeout_cb);
timerval.sec = 3;
timerval.usec = 500000;
tsize = sizeof(timerval);
mode = HWTIMER_MODE_ONESHOT;
if (rt_device_control(tmr_dev_0, HWTIMER_CTRL_MODE_SET, &mode) != RT_EOK)
{
rt_kprintf("timer0 set mode failed !\n");
}
else if (rt_device_write(tmr_dev_0, 0, &timerval, tsize) != tsize)
{
rt_kprintf("timer0 start failed !\n");
}
else
{
rt_kprintf("timer0 started !\n");
}
timerval.sec = 5;
timerval.usec = 0;
tsize = sizeof(timerval);
mode = HWTIMER_MODE_PERIOD;
if (rt_device_control(tmr_dev_1, HWTIMER_CTRL_MODE_SET, &mode) != RT_EOK)
{
rt_kprintf("timer1 set mode failed !\n");
}
else if (rt_device_write(tmr_dev_1, 0, &timerval, tsize) != tsize)
{
rt_kprintf("timer1 start failed !\n");
}
else
{
rt_kprintf("timer1 started !\n");
}
}
#endif
rt_pin_mode(LED1_PIN, PIN_MODE_OUTPUT);
rt_pin_write(LED1_PIN, led1 = PIN_HIGH);
rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT);
rt_pin_write(LED0_PIN, led0 = PIN_LOW);
while (1)
{
/* flashing LED0 every 1 second */
rt_thread_mdelay(500);
led0 = (led0 == PIN_LOW) ? PIN_HIGH : PIN_LOW;
rt_pin_write(LED0_PIN, led0);
}
}
menu "Hardware Drivers Config"
config SOC_CH569W
bool
select SOC_FAMILY_CH56X
select SOC_SERIES_CH569
select RT_USING_COMPONENTS_INIT
select RT_USING_USER_MAIN
default y
menu "On-chip Peripheral Drivers"
config BSP_USING_UART
bool "using on-chip uart"
select RT_USING_SERIAL
default y
if BSP_USING_UART
config BSP_USING_UART0
bool "using UART0"
default n
config BSP_USING_UART1
bool "using UART1"
default y
config BSP_USING_UART2
bool "using UART2"
default n
config BSP_USING_UART3
bool "using UART3"
default n
endif
config BSP_USING_TIMER
bool "using on-chip timer"
select RT_USING_HWTIMER
default n
if BSP_USING_TIMER
config BSP_USING_TMR0
bool "using TMR0"
default y
config BSP_USING_TMR1
bool "using TMR1"
default n
config BSP_USING_TMR2
bool "using TMR2"
default n
endif
endmenu
menu "Onboard Peripheral Drivers"
endmenu
menu "Board extended module Drivers"
endmenu
endmenu
from building import *
cwd = GetCurrentDir()
src = Split('''
board.c
startup_gcc.S
''')
path = [cwd]
group = DefineGroup('Drivers', src, depend=[''], CPPPATH=path)
Return('group')
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#include <rthw.h>
#include <drivers/pin.h>
#include "board.h"
#include "ch56x_pfic.h"
#include "ch56x_uart.h"
extern rt_uint32_t rt_thread_switch_interrupt_flag;
/* FIXME: Use rt_interrupt_leave_hook to trigger SWI for context switch.
* Hopefully there's a standard riscv way instead of this clumsy patch.
*/
static void irq_leave_hook(void)
{
if (rt_thread_switch_interrupt_flag)
{
pfic_swi_pendset();
}
}
/*
* _start -> handle_reset
* src/components.c/entry() -> rtthread_startup()
* libcpu/risc-v/common/context_gcc.S/rt_hw_interrupt_disable
*/
void rt_hw_board_init()
{
volatile struct pfic_registers *pfic = (void *)PFIC_REG_BASE;
/* disable all pfic interrupts */
pfic->IRER[0] = PFIC_IREG1_MASK;
pfic->IRER[1] = PFIC_IREG2_MASK;
/* disable hwstack push/pop & nested interrupt */
pfic->CFGR = cfgr_nest_hwstk(CFGR_NESTCTRL_DISABLE | CFGR_HWSTKCTRL_DISABLE);
/* disable clock input for all peripheral devices */
sys_slp_clk_off0(0xff, SYS_SLP_CLK_OFF);
sys_slp_clk_off1(0xff, SYS_SLP_CLK_OFF);
sys_clk_off_by_irqn(ETH_IRQn, SYS_SLP_CLK_OFF);
sys_clk_off_by_irqn(ECDC_IRQn, SYS_SLP_CLK_OFF);
/* setup HCLK for systick & peripheral devices */
sys_hclk_set(SYS_HCLK_FREQ);
/* set SysTick to RT_TICK_PER_SECOND with current HCLK */
systick_init(0);
/* Note: keep MSTATUS_MIE disabled to prevent SysTick from processing
* thread scheduling, which may not be ready upon 1st systick irq.
* MSTATUS_MIE will be set when rt_system_scheduler_start() starts
* the first thread and copies mstatus from stack_frame.
*/
#ifdef RT_USING_HEAP
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
#endif
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
#ifdef RT_USING_CONSOLE
/* console is uart1, TXD1/RXD1 : PA8/PA7 */
rt_pin_mode(GET_PIN(A, 8), PIN_MODE_OUTPUT);
rt_pin_mode(GET_PIN(A, 7), PIN_MODE_INPUT_PULLUP);
rt_hw_uart_init();
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
rt_interrupt_leave_sethook(irq_leave_hook);
}
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-07-15 Emuzit first version
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#include <stdint.h>
#include "ch56x_sys.h"
#include "ch56x_gpio.h"
#define LED0_PIN GET_PIN(B, 24)
#define LED1_PIN GET_PIN(B, 22)
#define LED2_PIN GET_PIN(B, 23)
#define SYS_HCLK_FREQ 80000000 // 80 MHz
#define RAMX_SIZE 32 // USER_MEM 00/01/1x : 32/64/96 KB
#define RAMX_END (RAMX_BASE_ADDRESS + RAMX_SIZE * 1024)
extern uint32_t _ebss, _heap_end;
extern uint32_t _susrstack, _eusrstack;
#define HEAP_BEGIN ((void *)&_ebss)
#define HEAP_END ((void *)&_heap_end)
#define SUSRSTACK ((void *)&_susrstack)
#define EUSRSTACK ((void *)&_eusrstack)
void rt_hw_board_init(void);
#endif /* __BOARD_H__ */
ENTRY( _start )
__stack_size = 2048;
PROVIDE( _stack_size = __stack_size );
MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 96K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 16K
RAMX (xrw) : ORIGIN = 0x20020000, LENGTH = 32K
}
SECTIONS
{
.init :
{
_sinit = .;
. = ALIGN(4);
KEEP(*(SORT_NONE(.init)))
. = ALIGN(4);
_einit = .;
} >FLASH AT>FLASH
.vector :
{
*(.vector);
. = ALIGN(64);
} >FLASH AT>FLASH
.text :
{
. = ALIGN(4);
*(.text)
*(.text.*)
*(.rodata)
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t.*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
. = ALIGN(4);
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
. = ALIGN(4);
/* section information for modules */
. = ALIGN(4);
__rtmsymtab_start = .;
KEEP(*(RTMSymTab))
__rtmsymtab_end = .;
. = ALIGN(4);
} >FLASH AT>FLASH
.fini :
{
KEEP(*(SORT_NONE(.fini)))
. = ALIGN(4);
} >FLASH AT>FLASH
PROVIDE( _etext = . );
PROVIDE( _eitcm = . );
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH AT>FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH AT>FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH AT>FLASH
.ctors :
{
/* gcc uses crtbegin.o to find the start of
the constructors, so we make sure it is
first. Because this is a wildcard, it
doesn't matter if the user does not
actually link against crtbegin.o; the
linker won't look for a file to match a
wildcard. The wildcard also means that it
doesn't matter which directory crtbegin.o
is in. */
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
the crtend.o file until after the sorted ctors.
The .ctor section from the crtend file contains the
end of ctors marker and it must be last */
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
} >FLASH AT>FLASH
.dtors :
{
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
} >FLASH AT>FLASH
.dalign :
{
. = ALIGN(4);
PROVIDE(_data_vma = .);
} >RAM AT>FLASH
.dlalign :
{
. = ALIGN(4);
PROVIDE(_data_lma = .);
} >FLASH AT>FLASH
.data :
{
*(.gnu.linkonce.r.*)
*(.data .data.*)
*(.gnu.linkonce.d.*)
. = ALIGN(8);
PROVIDE( __global_pointer$ = . + 0x800 );
*(.sdata .sdata.*)
*(.sdata2.*)
*(.gnu.linkonce.s.*)
. = ALIGN(8);
*(.srodata.cst16)
*(.srodata.cst8)
*(.srodata.cst4)
*(.srodata.cst2)
*(.srodata .srodata.*)
. = ALIGN(4);
PROVIDE( _edata = .);
} >RAM AT>FLASH
.bss :
{
. = ALIGN(4);
PROVIDE( _sbss = .);
*(.sbss*)
*(.gnu.linkonce.sb.*)
*(.bss*)
*(.gnu.linkonce.b.*)
*(COMMON*)
. = ALIGN(4);
PROVIDE( _ebss = .);
} >RAM AT>FLASH
PROVIDE( _end = _ebss);
PROVIDE( end = . );
.dmadata :
{
. = ALIGN(16);
PROVIDE( _dmadata_start = .);
*(.dmadata*)
*(.dmadata.*)
. = ALIGN(16);
PROVIDE( _dmadata_end = .);
} >RAMX AT>FLASH /**/
.stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size :
{
PROVIDE( _heap_end = . );
. = ALIGN(4);
PROVIDE(_susrstack = . );
. = . + __stack_size;
PROVIDE( _eusrstack = .);
} >RAM
}
/********************************** (C) COPYRIGHT *******************************
* File Name : startup_gcc.s
* Author : WCH
* Version : V1.0
* Date : 2020/07/31
* Description : CH56x vector table for eclipse toolchain.
*******************************************************************************/
.section .init,"ax",@progbits
.global _start
.align 1
_start:
j handle_reset
.section .vector,"ax",@progbits
.align 1
_vector_base:
.option norvc;
.word 0
.word 0
j nmi_handler
j hardfault_handler
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
j systick_handler
.word 0
j swi_handler
.word 0
/* External Interrupts */
j wdog_irq_handler
j tmr0_irq_handler
j gpio_irq_handler
j spi0_irq_handler
j usbss_irq_handler
j link_irq_handler
j tmr1_irq_handler
j tmr2_irq_handler
j uart0_irq_handler
j usbhs_irq_handler
j emmc_irq_handler
j dvp_irq_handler
j hspi_irq_handler
j spi1_irq_handler
j uart1_irq_handler
j uart2_irq_handler
j uart3_irq_handler
j serdes_irq_handler
j eth_irq_handler
j pmt_irq_handler
j ecdc_irq_handler
.option rvc;
.section .text.vector_handler,"ax", @prsocogbits
.weak nmi_handler
.weak hardfault_handler
.weak systick_handler
.weak swi_handler
.weak wdog_irq_handler
.weak tmr0_irq_handler
.weak gpio_irq_handler
.weak spi0_irq_handler
.weak usbss_irq_handler
.weak link_irq_handler
.weak tmr1_irq_handler
.weak tmr2_irq_handler
.weak uart0_irq_handler
.weak usbhs_irq_handler
.weak emmc_irq_handler
.weak dvp_irq_handler
.weak hspi_irq_handler
.weak spi1_irq_handler
.weak uart1_irq_handler
.weak uart2_irq_handler
.weak uart3_irq_handler
.weak serdes_irq_handler
.weak eth_irq_handler
.weak pmt_irq_handler
.weak ecdc_irq_handler
nmi_handler: j .L_rip
hardfault_handler: j .L_rip
systick_handler: j .L_rip
swi_handler: j .L_rip
wdog_irq_handler: j .L_rip
tmr0_irq_handler: j .L_rip
gpio_irq_handler: j .L_rip
spi0_irq_handler: j .L_rip
usbss_irq_handler: j .L_rip
link_irq_handler: j .L_rip
tmr1_irq_handler: j .L_rip
tmr2_irq_handler: j .L_rip
uart0_irq_handler: j .L_rip
usbhs_irq_handler: j .L_rip
emmc_irq_handler: j .L_rip
dvp_irq_handler: j .L_rip
hspi_irq_handler: j .L_rip
spi1_irq_handler: j .L_rip
uart1_irq_handler: j .L_rip
uart2_irq_handler: j .L_rip
uart3_irq_handler: j .L_rip
serdes_irq_handler: j .L_rip
eth_irq_handler: j .L_rip
pmt_irq_handler: j .L_rip
ecdc_irq_handler: j .L_rip
.L_rip:
csrr t0, mepc
csrr t1, mstatus
csrr t2, mcause
csrr t3, mtval
csrr t4, mscratch
1: j 1b
.section .text.handle_reset,"ax",@progbits
.weak handle_reset
.align 1
handle_reset:
.option push
.option norelax
la gp, __global_pointer$
.option pop
1:
la sp, _eusrstack
/* Load data section from flash to RAM */
2:
la a0, _data_lma
la a1, _data_vma
la a2, _edata
bgeu a1, a2, 2f
1:
lw t0, (a0)
sw t0, (a1)
addi a0, a0, 4
addi a1, a1, 4
bltu a1, a2, 1b
/* clear bss section */
2:
la a0, _sbss
la a1, _ebss
bgeu a0, a1, 2f
1:
sw zero, (a0)
addi a0, a0, 4
bltu a0, a1, 1b
/* clear dmadata section */
2:
la a0, _dmadata_start
la a1, _dmadata_end
bgeu a0, a1, 2f
1:
sw zero, (a0)
addi a0, a0, 4
bltu a0, a1, 1b
2:
/* leave all interrupt disabled */
li t0, 0x1800
csrs mstatus, t0
la t0, _vector_base
ori t0, t0, 1
csrw mtvec, t0
la t0, entry
csrw mepc, t0
mret
此差异已折叠。
import os
ARCH = 'risc-v'
CPU = 'ch56x'
# toolchains options
CROSS_TOOL = 'gcc'
#------- toolchains path -------------------------------------------------------
if os.getenv('RTT_CC'):
CROSS_TOOL = os.getenv('RTT_CC')
if CROSS_TOOL == 'gcc':
PLATFORM = 'gcc'
EXEC_PATH = r'/opt/mrs-riscv-none-embed/bin'
else:
print('Please make sure your toolchains is GNU GCC!')
exit(0)
if os.getenv('RTT_EXEC_PATH'):
EXEC_PATH = os.getenv('RTT_EXEC_PATH')
#BUILD = 'debug'
BUILD = 'release'
CORE = 'risc-v'
MAP_FILE = 'rtthread.map'
LINK_FILE = './board/linker_scripts/link.lds'
TARGET_NAME = 'rtthread.bin'
#------- GCC settings ----------------------------------------------------------
if PLATFORM == 'gcc':
# toolchains
PREFIX = 'riscv-none-embed-'
CC = PREFIX + 'gcc'
CXX= PREFIX + 'g++'
AS = PREFIX + 'gcc'
AR = PREFIX + 'ar'
LINK = PREFIX + 'gcc'
TARGET_EXT = 'elf'
SIZE = PREFIX + 'size'
OBJDUMP = PREFIX + 'objdump'
OBJCPY = PREFIX + 'objcopy'
DEVICE = ' -march=rv32imac -mabi=ilp32 -DUSE_PLIC -DUSE_M_TIME -DNO_INIT -mcmodel=medany -msmall-data-limit=8 -L. -nostartfiles -lc '
CFLAGS = DEVICE
CFLAGS += ' -save-temps=obj'
AFLAGS = '-c'+ DEVICE + ' -x assembler-with-cpp'
LFLAGS = DEVICE
LFLAGS += ' -Wl,--gc-sections,-cref,-Map=' + MAP_FILE
LFLAGS += ' -T ' + LINK_FILE
LFLAGS += ' -Wl,-wrap=memset'
CPATH = ''
LPATH = ''
if BUILD == 'debug':
CFLAGS += ' -O0 -g3'
AFLAGS += ' -g3'
else:
CFLAGS += ' -O2'
POST_ACTION = OBJCPY + ' -O binary $TARGET ' + TARGET_NAME + '\n'
POST_ACTION += SIZE + ' $TARGET\n'
......@@ -24,7 +24,7 @@ else :
# cpu porting code files
if rtconfig.CPU == "e9xx" :
group = group + SConscript(os.path.join(rtconfig.VENDOR, rtconfig.CPU, 'SConscript'))
else :
elif rtconfig.CPU in list:
group = group + SConscript(os.path.join(rtconfig.CPU, 'SConscript'))
Return('group')
......@@ -138,7 +138,7 @@ rt_uint8_t *rt_hw_stack_init(void *tentry,
* #endif
*/
#ifndef RT_USING_SMP
void rt_hw_context_switch_interrupt(rt_ubase_t from, rt_ubase_t to)
RT_WEAK void rt_hw_context_switch_interrupt(rt_ubase_t from, rt_ubase_t to)
{
if (rt_thread_switch_interrupt_flag == 0)
rt_interrupt_from_thread = from;
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册