Compare commits

..

2 commits

Author SHA1 Message Date
Kizarm
97ce195c49 reorganize 2025-01-25 12:21:08 +01:00
Kizarm
b8f0033a15 add r6 2025-01-25 10:55:11 +01:00
32 changed files with 14161 additions and 0 deletions

2
.gitignore vendored
View file

@ -8,6 +8,8 @@
*.hex
*.map
*.elf
*.o
*.so
*/midi/melody.c
*/midi/miditone.c
*/midi/ton/gen

4
V203F6P6/README.md Normal file
View file

@ -0,0 +1,4 @@
# V203R6
Koupil jsem na ALI pár levných procesorů CH32V203F6P6,
tak jsem se rozhodl je vyzkoušet. Má to méně paměti (32K flash, 10K ram),
ořezané periferie, ale na pokusy by to mohlo stačit.

53
V203F6P6/blink/Makefile Normal file
View file

@ -0,0 +1,53 @@
TARGET?= ch32v203
TOOL ?= gcc
#TOOL ?= clang
PRJ = example
VPATH = . ./$(TARGET)
BLD = ./build/
DFLAGS = -d
LFLAGS = -g
LDLIBS =
BFLAGS = --strip-unneeded
CFLAGS = -MMD -Wall -Wno-parentheses -ggdb -fno-exceptions -ffunction-sections -fdata-sections
CFLAGS+= -I. -I./$(TARGET)
DEL = rm -f
# zdrojaky
OBJS = main.o
#OBJS +=
include $(TARGET)/$(TOOL).mk
BOBJS = $(addprefix $(BLD),$(OBJS))
all: $(BLD) $(PRJ).elf
# ... atd.
-include $(BLD)*.d
# linker
$(PRJ).elf: $(BOBJS)
-@echo [LD $(TOOL),$(TARGET)] $@
@$(LD) $(LFLAGS) -o $(PRJ).elf $(BOBJS) $(LDLIBS)
-@echo "size:"
@$(SIZE) $(PRJ).elf
-@echo "listing:"
$(DUMP) $(DFLAGS) $(PRJ).elf > $(PRJ).lst
-@echo "OK."
$(COPY) $(BFLAGS) -O binary $(PRJ).elf $(PRJ).bin
# preloz co je potreba
$(BLD)%.o: %.c
-@echo [CC $(TOOL),$(TARGET)] $@
@$(CC) -std=gnu99 -c $(CFLAGS) $< -o $@
$(BLD)%.o: %.cpp
-@echo [CX $(TOOL),$(TARGET)] $@
@$(CXX) -std=c++17 -fno-rtti -c $(CFLAGS) $< -o $@
$(BLD):
mkdir $(BLD)
flash: $(PRJ).elf
minichlink -w $(PRJ).bin flash -b
# vycisti
clean:
$(DEL) $(BLD)* *.lst *.bin *.elf *.map *~
.PHONY: all clean flash run

1
V203F6P6/blink/ch32v203 Symbolic link
View file

@ -0,0 +1 @@
../ch32v203/

28
V203F6P6/blink/main.cpp Normal file
View file

@ -0,0 +1,28 @@
#include "system.h"
#include "gpio.h"
////////////////////////////////////////////////////////////////////////
static constexpr unsigned ticks = SYSTEM_CORE_CLOCK / 1000u;
static volatile unsigned counter = 0u;
extern "C" [[gnu::interrupt]] void SysTick_Handler ();
////////////////////////////////////////////////////////////////////////
void SysTick_Handler () {
SysTick.SR = 0u;
if (counter) counter -= 1u;
}
static void delay (const unsigned dly = 200u) {
counter = dly;
while (counter);
}
int main () {
GpioClass led (GPIOB, 8);
SysTick.Config (ticks);
unsigned pass_cnt = 0u;
for (;;) {
delay();
const bool b = pass_cnt & 1u;
led << b;
pass_cnt += 1u;
}
return 0;
}

12467
V203F6P6/ch32v203/CH32V20xxx.h Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,26 @@
# Use clang / llvm toolchain
#
CC = clang
CXX = clang++
LD = ld.lld
SIZE = llvm-size
AS = riscv64-unknown-elf-as -mno-relax
DUMP = riscv64-unknown-elf-objdump
COPY = riscv64-unknown-elf-objcopy
OBJS += startup.o system.o
CCPU = -march=rv32imac -mabi=ilp32
MCPU = $(CCPU)
TRIP = riscv32-unknown-none-elf
CFLAGS+= -Oz
#CFLAGS+= -flto
CFLAGS+= -fmessage-length=0 -fsigned-char -I/usr/include/newlib
#CFLAGS+= -fconstexpr-steps=2097152
CFLAGS+= --target=$(TRIP) $(MCPU)
LFLAGS+= --Map=$(@:%.elf=%.map) --gc-sections
# 16-bit instrukce se do toho asi dostanou až na úrovni LLVM linkeru.
# Bohužel to není nikde pořádně popsáno.
LFLAGS+= -mllvm -mattr=+c
#LFLAGS+= -lto-O3
LFLAGS+= -nostdlib
LDLIBS+= -L./$(TARGET) -T generated_CH32V203F6P6.ld

21
V203F6P6/ch32v203/gcc.mk Normal file
View file

@ -0,0 +1,21 @@
# Use gcc / binutils toolchain
PREFIX = riscv64-unknown-elf-
CC = $(PREFIX)gcc
CXX = $(PREFIX)g++
LD = $(PREFIX)gcc
AS = $(PREFIX)as
SIZE = $(PREFIX)size
DUMP = $(PREFIX)objdump
COPY = $(PREFIX)objcopy
OBJS += startup.o system.o
CFLAGS+= -Os
#CFLAGS+= -flto
CCPU = -march=rv32imac -mabi=ilp32
MCPU = $(CCPU)
CFLAGS+= $(MCPU) -msmall-data-limit=8 -mno-save-restore -fmessage-length=0 -fsigned-char -I/usr/include/newlib
LFLAGS+= -Wl,--Map=$(@:%.elf=%.map),--gc-sections
#LFLAGS+= -Wl,--print-sysroot -- chyba ld ?
#LFLAGS+= -flto
LFLAGS+= -Os $(MCPU) -nostartfiles -nostdlib
LDLIBS+= -lgcc -L./$(TARGET) -T generated_CH32V203F6P6.ld

View file

@ -0,0 +1,115 @@
ENTRY( InterruptVector )
MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 32K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 10K
}
SECTIONS
{
.init :
{
_sinit = .;
. = ALIGN(4);
KEEP(*(SORT_NONE(.init)))
. = ALIGN(4);
_einit = .;
} >FLASH AT>FLASH
.text :
{
. = ALIGN(4);
*(.text)
*(.text.*)
*(.rodata)
*(.rodata*)
*(.gnu.linkonce.t.*)
. = 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 :
{
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
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 :
{
. = ALIGN(4);
*(.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 = . );
PROVIDE( _eusrstack = ORIGIN(RAM) + LENGTH(RAM));
}

66
V203F6P6/ch32v203/gpio.h Normal file
View file

@ -0,0 +1,66 @@
#ifndef _GPIO_CLASS_H_
#define _GPIO_CLASS_H_
#include "CH32V20xxx.h"
enum GPIO_MODE : uint32_t {
GPIO_Speed_In = 0u,
GPIO_Speed_10MHz = 1u,
GPIO_Speed_2MHz = 2u,
GPIO_Speed_50MHz = 3u,
};
enum GPIO_CNF : uint32_t {
GPIO_AI_PPO = 0u,
GPIO_FI_ODO = 1u << 2,
GPIO_UPDI_MPPO = 2u << 2,
GPIO_none_MPDO = 3u << 2,
};
enum GPIOPuPd_TypeDef {
GPIO_PuPd_NOPULL = 0x00,
GPIO_PuPd_UP = 0x01,
GPIO_PuPd_DOWN = 0x02
};
class GpioClass {
GPIOA_Type & port;
const uint32_t pin;
public:
explicit GpioClass (GPIOA_Type & _port, const uint32_t _pin, const uint32_t _mode = GPIO_AI_PPO | GPIO_Speed_10MHz) noexcept
: port(_port), pin(_pin) {
/* Zapneme vše, ono je to dost jedno. */
RCC.APB2PCENR.modify([](RCC_Type::APB2PCENR_DEF & r)->auto {
r.B.IOPAEN = SET;
r.B.IOPBEN = SET;
//r.B.IOPCEN = SET;
return r.R;
});
if (pin < 8u) {
const uint32_t pos = pin << 2;
port.CFGLR.modify([=](GPIOA_Type::CFGLR_DEF & r)->auto {
uint32_t t = r.R;
t &= ~(0xFu << pos);
t |= _mode << pos;
return t;
});
} else {
const uint32_t pos = (pin - 8u) << 2;
port.CFGHR.modify([=](GPIOA_Type::CFGHR_DEF & r)->auto {
uint32_t t = r.R;
t &= ~(0xFu << pos);
t |= _mode << pos;
return t;
});
}
}
void operator<< (const bool b) const {
port.BSHR.R = b ? 1u << pin : 1u << (pin + 16);
}
operator bool () const {
return port.INDR.R & (1u << pin);
}
void setPuPd (GPIOPuPd_TypeDef p) {
if (p != GPIO_PuPd_UP) return;
port.OUTDR.R |= 1u << pin;
}
};
#endif // _GPIO_CLASS_H_

View file

@ -0,0 +1,265 @@
#include "system.h"
typedef __SIZE_TYPE__ size_t;
extern "C" {
[[using gnu: naked,nothrow,used]] extern void handle_reset ();
[[gnu::used]] extern void user_init ();
[[gnu::used]] extern int main ();
// This is required to allow pure virtual functions to be defined.
extern void __cxa_pure_virtual() { while (1); }
// These magic symbols are provided by the linker.
extern uint32_t _sbss;
extern uint32_t _ebss;
extern uint32_t _data_lma;
extern uint32_t _data_vma;
extern uint32_t _edata;
[[gnu::weak]] extern void (*__preinit_array_start[]) (void);
[[gnu::weak]] extern void (*__preinit_array_end[]) (void);
[[gnu::weak]] extern void (*__init_array_start[]) (void);
[[gnu::weak]] extern void (*__init_array_end[]) (void);
// If you don't override a specific handler, it will just spin forever.
[[gnu::interrupt]] void DefaultIRQHandler( void ) {
// Infinite Loop
for (;;);
}
[[gnu::interrupt]] void NMI_RCC_CSS_IRQHandler( void ) {
RCC.INTR.B.CSSC = RESET; // clear the clock security int flag
}
#define ALIAS(f) __attribute__((nothrow,weak,alias(#f),used))
void Ecall_M_Mode_Handler( void ) ALIAS(DefaultIRQHandler);
void Ecall_U_Mode_Handler( void ) ALIAS(DefaultIRQHandler);
void Break_Point_Handler( void ) ALIAS(DefaultIRQHandler);
void NMI_Handler( void ) ALIAS(NMI_RCC_CSS_IRQHandler);
void HardFault_Handler( void ) ALIAS(DefaultIRQHandler);
void SysTick_Handler( void ) ALIAS(DefaultIRQHandler);
void SW_Handler( void ) ALIAS(DefaultIRQHandler);
void WWDG_IRQHandler (void) ALIAS(DefaultIRQHandler);
void PVD_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TAMPER_IRQHandler (void) ALIAS(DefaultIRQHandler);
void RTC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void FLASH_IRQHandler (void) ALIAS(DefaultIRQHandler);
void RCC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI0_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI1_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI3_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI4_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel1_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel3_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel4_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel5_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel6_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel7_IRQHandler (void) ALIAS(DefaultIRQHandler);
void DMA1_Channel8_IRQHandler (void) ALIAS(DefaultIRQHandler);
void ADC1_2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USB_HP_CAN1_TX_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USB_LP_CAN1_RX0_IRQHandler (void) ALIAS(DefaultIRQHandler);
void CAN1_RX1_IRQHandler (void) ALIAS(DefaultIRQHandler);
void CAN1_SCE_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI9_5_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM1_BRK_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM1_UP_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM1_TRG_COM_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM1_CC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM3_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM4_IRQHandler (void) ALIAS(DefaultIRQHandler);
void I2C1_EV_IRQHandler (void) ALIAS(DefaultIRQHandler);
void I2C1_ER_IRQHandler (void) ALIAS(DefaultIRQHandler);
void I2C2_EV_IRQHandler (void) ALIAS(DefaultIRQHandler);
void I2C2_ER_IRQHandler (void) ALIAS(DefaultIRQHandler);
void SPI1_IRQHandler (void) ALIAS(DefaultIRQHandler);
void SPI2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USART1_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USART2_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USART3_IRQHandler (void) ALIAS(DefaultIRQHandler);
void EXTI15_10_IRQHandler (void) ALIAS(DefaultIRQHandler);
void RTCAlarm_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USBWakeUp_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM8_BRK_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM8_UP__IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM8_TRG_COM_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM8_CC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM5_IRQHandler (void) ALIAS(DefaultIRQHandler);
void SPI3_IRQHandler (void) ALIAS(DefaultIRQHandler);
void UART4_IRQHandler (void) ALIAS(DefaultIRQHandler);
void UART5_IRQHandler (void) ALIAS(DefaultIRQHandler);
void ETH_IRQHandler (void) ALIAS(DefaultIRQHandler);
void ETH_WKUP_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USBFS_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USBFSWakeUp_IRQHandler (void) ALIAS(DefaultIRQHandler);
void USBHD_IRQHandler (void) ALIAS(DefaultIRQHandler);
void UART6_IRQHandler (void) ALIAS(DefaultIRQHandler);
void UART7_IRQHandler (void) ALIAS(DefaultIRQHandler);
void UART8_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM9_BRK_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM9_UP__IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM9_TRG_COM_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM9_CC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM10_BRK_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM10_UP__IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM10_TRG_COM_IRQHandler (void) ALIAS(DefaultIRQHandler);
void TIM10_CC_IRQHandler (void) ALIAS(DefaultIRQHandler);
void ETHWakeUp_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void OSC32KCal_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void OSCWakeUp_IRQHandler( void ) ALIAS(DefaultIRQHandler);
typedef void (*pHandler) (void);
void Init() __attribute__((used,section(".init")));
extern const pHandler InterruptVector [] __attribute__((section(".text.vector"),aligned(8)));
};
const pHandler InterruptVector [] = {
Init,
0,
NMI_Handler, /* NMI */
HardFault_Handler, /* Hard Fault */
0,
Ecall_M_Mode_Handler, /* Ecall M Mode */
0,0,
Ecall_U_Mode_Handler, /* Ecall U Mode */
Break_Point_Handler, /* Break Point */
0,0,
SysTick_Handler, /* SysTick Handler */
0,
SW_Handler, /* SW Handler */
0,
/* External Interrupts */
WWDG_IRQHandler, /* Window Watchdog */
PVD_IRQHandler, /* PVD through EXTI Line detect */
TAMPER_IRQHandler, /* TAMPER */
RTC_IRQHandler, /* RTC */
FLASH_IRQHandler, /* Flash */
RCC_IRQHandler, /* RCC */
EXTI0_IRQHandler, /* EXTI Line 0 */
EXTI1_IRQHandler, /* EXTI Line 1 */
EXTI2_IRQHandler, /* EXTI Line 2 */
EXTI3_IRQHandler, /* EXTI Line 3 */
EXTI4_IRQHandler, /* EXTI Line 4 */
DMA1_Channel1_IRQHandler, /* DMA1 Channel 1 */
DMA1_Channel2_IRQHandler, /* DMA1 Channel 2 */
DMA1_Channel3_IRQHandler, /* DMA1 Channel 3 */
DMA1_Channel4_IRQHandler, /* DMA1 Channel 4 */
DMA1_Channel5_IRQHandler, /* DMA1 Channel 5 */
DMA1_Channel6_IRQHandler, /* DMA1 Channel 6 */
DMA1_Channel7_IRQHandler, /* DMA1 Channel 7 */
ADC1_2_IRQHandler, /* ADC1_2 */
USB_HP_CAN1_TX_IRQHandler, /* USB HP and CAN1 TX */
USB_LP_CAN1_RX0_IRQHandler, /* USB LP and CAN1RX0 */
CAN1_RX1_IRQHandler, /* CAN1 RX1 */
CAN1_SCE_IRQHandler, /* CAN1 SCE */
EXTI9_5_IRQHandler, /* EXTI Line 9..5 */
TIM1_BRK_IRQHandler, /* TIM1 Break */
TIM1_UP_IRQHandler, /* TIM1 Update */
TIM1_TRG_COM_IRQHandler, /* TIM1 Trigger and Commutation */
TIM1_CC_IRQHandler, /* TIM1 Capture Compare */
TIM2_IRQHandler, /* TIM2 */
TIM3_IRQHandler, /* TIM3 */
TIM4_IRQHandler, /* TIM4 */
I2C1_EV_IRQHandler, /* I2C1 Event */
I2C1_ER_IRQHandler, /* I2C1 Error */
I2C2_EV_IRQHandler, /* I2C2 Event */
I2C2_ER_IRQHandler, /* I2C2 Error */
SPI1_IRQHandler, /* SPI1 */
SPI2_IRQHandler, /* SPI2 */
USART1_IRQHandler, /* USART1 */
USART2_IRQHandler, /* USART2 */
USART3_IRQHandler, /* USART3 */
EXTI15_10_IRQHandler, /* EXTI Line 15..10 */
RTCAlarm_IRQHandler, /* RTC Alarm through EXTI Line */
USBWakeUp_IRQHandler, /* USB Wake up from suspend */
USBFS_IRQHandler, /* USBHD Break */
USBFSWakeUp_IRQHandler, /* USBHD Wake up from suspend */
ETH_IRQHandler, /* ETH global */
ETHWakeUp_IRQHandler, /* ETH Wake up */
0, /* BLE BB */
0, /* BLE LLE */
TIM5_IRQHandler, /* TIM5 */
UART4_IRQHandler, /* UART4 */
DMA1_Channel8_IRQHandler, /* DMA1 Channel8 */
OSC32KCal_IRQHandler, /* OSC32KCal */
OSCWakeUp_IRQHandler, /* OSC Wake Up */
};
void Init() {
asm volatile( R"---(
.align 1
_start:
j handle_reset
)---");
}
void handle_reset() noexcept {
asm volatile(R"---(
.option push
.option norelax
la gp, __global_pointer$
.option pop
la sp, _eusrstack
)---"
#if __GNUC__ > 10
".option arch, +zicsr\n"
#endif
// Setup the interrupt vector, processor status and INTSYSCR.
R"---(
/* Configure pipelining and instruction prediction */
li t0, 0x1f
csrw 0xbc0, t0
/* Enabled nested and hardware stack */
li t0, 0x88
csrs mstatus, t0
/* Configure the interrupt vector table recognition mode and entry address mode */
la t0, InterruptVector
ori t0, t0, 3
csrw mtvec, t0
/* Takhle RISC-V přejde do uživatelského programu. */
csrw mepc, %[main]
mret
)---"
: : [main]"r"(user_init)/*, [InterruptVector]"r"(InterruptVector)*/
: "t0", "memory" );
}
static void init_variables () {
uint32_t * dst, * end;
/* Zero fill the bss section */
dst = &_sbss;
end = &_ebss;
while (dst < end) * dst++ = 0U;
/* Copy data section from flash to RAM */
uint32_t * src;
src = &_data_lma;
dst = &_data_vma;
end = &_edata;
if (src != dst) {
while (dst < end) * dst++ = * src++;
}
}
static void init_constructors () {
/* Pro Cortex-Mx bylo toto zbytečné, lze předpokládat, že je to tak i zde.
count = __preinit_array_end - __preinit_array_start;
for (unsigned i = 0; i < count; i++) __preinit_array_start[i]();
*/
const size_t count = __init_array_end - __init_array_start;
for (unsigned i = 0; i < count; i++) __init_array_start[i]();
}
void user_init () {
init_variables();
SystemInit();
SystemCoreClockUpdate();
init_constructors(); // Konstruktory zavolat až po inicializaci hodin
main ();
for (;;);
}

View file

@ -0,0 +1,164 @@
//#include "CH32V20xxx.h"
#include "system.h"
extern "C" void SystemInit ();
enum CLKSRC : uint32_t {
CLK_HSI = 0u,
CLK_HSE,
CLK_PLL,
};
static constexpr unsigned HSI_VALUE = 8000000u; /* Value of the Internal oscillator in Hz */
static constexpr unsigned HSE_VALUE = 8000000u; /* Value of the External oscillator in Hz */
/* In the following line adjust the External High Speed oscillator (HSE) Startup Timeout value */
static constexpr unsigned HSE_STARTUP_TIMEOUT = 0x1000u; /* Time out for HSE start up */
// HSE i HSI mají frekvenci 8 MHz
static constexpr uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
uint32_t SystemCoreClock = SYSTEM_CORE_CLOCK; /* System Clock Frequency (Core Clock) */
static void SetSysClock_HSE(void) {
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
RCC.CTLR.B.HSEON = SET;
/* Wait till HSE is ready and if Time out is reached exit */
do {
HSEStatus = RCC.CTLR.B.HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC.CTLR.B.HSERDY) != RESET) {
HSEStatus = (uint32_t)0x01;
} else {
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01) {
RCC.CFGR0.modify([](RCC_Type::CFGR0_DEF & r) -> auto {
r.B.HPRE = 0u; /* HCLK = SYSCLK */
r.B.PPRE2 = 0u; /* PCLK2 = HCLK */
r.B.PPRE1 = 4u; /* PCLK1 = HCLK */
/* CH32V20x_D6-PLL configuration: PLLCLK = HSE * 12 = 96 MHz (HSE=8MHZ)
* CH32V20x_D8-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz (HSE=32MHZ)
* CH32V20x_D8W-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz (HSE=32MHZ)
*/
r.B.PLLSRC = SET;
r.B.PLLXTPRE = RESET;
r.B.PLLMUL = 15u; // or 10u for 96 MHz
return r.R;
});
/* Enable PLL */
RCC.CTLR.B.PLLON = SET;
/* Wait till PLL is ready */
while((RCC.CTLR.B.PLLRDY) == RESET) {}
/* Select PLL as system clock source */
RCC.CFGR0.B.SW = CLK_PLL;
/* Wait till PLL is used as system clock source */
while (RCC.CFGR0.B.SWS != CLK_PLL) {}
} else {
/*
* If HSE fails to start-up, the application will have wrong clock
* configuration. User can add here some code to deal with this error
*/
}
}
void SystemInit(void) {
RCC.CTLR.R |= 0x00000001u;
RCC.CFGR0.R &= 0xF0FF0000u;
RCC.CTLR.R &= 0xFEF6FFFFu;
RCC.CTLR.R &= 0xFFFBFFFFu;
RCC.CFGR0.R &= 0xFF00FFFFu;
RCC.INTR.R = 0x009F0000u;
SetSysClock_HSE();
}
/*********************************************************************
* @fn SystemCoreClockUpdate
*
* @brief Update SystemCoreClock variable according to Clock Register Values.
*
* @return none
*/
void SystemCoreClockUpdate (void) {
uint32_t tmp = 0, pllmull = 0, pllsource = 0;
tmp = RCC.CFGR0.B.SWS;
switch (tmp) {
case 0x00:
SystemCoreClock = HSI_VALUE;
break;
case 0x01:
SystemCoreClock = HSE_VALUE;
break;
case 0x02:
pllmull = RCC.CFGR0.B.PLLMUL;
pllsource = RCC.CFGR0.B.PLLSRC;
pllmull += 2u;
if(pllmull == 17) pllmull = 18;
if (pllsource == 0u) {
if(EXTEND.EXTEND_CTR.B.PLL_HSI_PRE){
SystemCoreClock = HSI_VALUE * pllmull;
} else {
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
} else {
if (RCC.CFGR0.B.PLLXTPRE) {
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
} else {
SystemCoreClock = HSE_VALUE * pllmull;
}
}
break;
default:
SystemCoreClock = HSI_VALUE;
break;
}
tmp = AHBPrescTable[RCC.CFGR0.B.HPRE];
SystemCoreClock >>= tmp;
}
static uint32_t p_us = 0u;
static bool timeout;
void delay_init () {
// default clock is HCLK / 8
p_us = SystemCoreClock / 8000000;
}
void delay_us (const unsigned dly) {
const uint32_t i = (uint32_t) dly * p_us;
SysTick.SR &= ~(1 << 0);
SysTick.CMPLR = i;
SysTick.CTLR.modify([](SysTick_Type::CTLR_DEF & r) -> uint32_t {
r.B.MODE = SET;
r.B.INIT = SET;
return r.R;
});
SysTick.CTLR.B.STE = SET;
while((SysTick.SR & (1u << 0)) != (1u << 0));
SysTick.CTLR.B.STE = RESET;
}
void set_timeout_us (const uint32_t time) {
SysTick.CTLR.B.STE = RESET;
timeout = false;
const uint32_t i = (uint32_t) time * p_us;
SysTick.SR &= ~(1 << 0);
SysTick.CMPLR = i;
SysTick.CTLR.modify([](SysTick_Type::CTLR_DEF & r) -> uint32_t {
r.B.MODE = SET;
r.B.INIT = SET;
return r.R;
});
SysTick.CTLR.B.STE = SET;
}
bool is_timeout () {
if (SysTick.SR & (1u << 0)) {
SysTick.CTLR.B.STE = RESET;
timeout = true;
} else {
}
return timeout;
}

View file

@ -0,0 +1,93 @@
#ifndef SYSTEM_H
#define SYSTEM_H
#include "CH32V20xxx.h"
struct NVIC_Type {
__I uint32_t ISR[8];
__I uint32_t IPR[8];
__IO uint32_t ITHRESDR;
__IO uint32_t RESERVED;
__IO uint32_t CFGR;
__I uint32_t GISR;
__IO uint8_t VTFIDR[4];
uint8_t RESERVED0[12];
__IO uint32_t VTFADDR[4];
uint8_t RESERVED1[0x90];
__O uint32_t IENR[8];
uint8_t RESERVED2[0x60];
__O uint32_t IRER[8];
uint8_t RESERVED3[0x60];
__O uint32_t IPSR[8];
uint8_t RESERVED4[0x60];
__O uint32_t IPRR[8];
uint8_t RESERVED5[0x60];
__IO uint32_t IACTR[8];
uint8_t RESERVED6[0xE0];
__IO uint8_t IPRIOR[256];
uint8_t RESERVED7[0x810];
__IO uint32_t SCTLR;
void EnableIRQ (IRQn IRQ) {
IENR [((uint32_t)(IRQ) >> 5)] = (1 << ((uint32_t)(IRQ) & 0x1F));
}
void DisableIRQ (IRQn IRQ) {
IRER [((uint32_t)(IRQ) >> 5)] = (1 << ((uint32_t)(IRQ) & 0x1F));
}
void SetPriority(IRQn IRQ, uint8_t priority) {
IPRIOR[(uint32_t)(IRQ)] = priority;
}
};
static NVIC_Type & NVIC = * reinterpret_cast<NVIC_Type * const> (0xE000E000);
struct SysTick_Type {
union CTLR_DEF {
struct {
__IO ONE_BIT STE : 1; //!<[00] System counter enable
__IO ONE_BIT STIE : 1; //!<[01] System counter interrupt enable
__IO ONE_BIT STCLK : 1; //!<[02] System selects the clock source
__IO ONE_BIT STRE : 1; //!<[03] System reload register
__IO ONE_BIT MODE : 1; //!<[04] System Mode
__IO ONE_BIT INIT : 1; //!<[05] System Initialization update
uint32_t UNUSED0 : 25; //!<[06]
__IO ONE_BIT SWIE : 1; //!<[31] System software triggered interrupts enable
} B;
__IO uint32_t R;
template<typename F> void modify (F f) volatile {
CTLR_DEF r; r.R = R;
R = f (r);
}
};
__IO CTLR_DEF CTLR ; //!< [1000](04)[0x00000000]
__IO uint32_t SR ; //!< [1004](04)[0x00000000]
__IO uint32_t CNTL ; //!< [1008](04)[0x00000000]
__IO uint32_t CNTH ; //!< [100c](04)[0x00000000]
__IO uint32_t CMPLR ; //!< [1010](04)[0x00000000]
__IO uint32_t CMPHR ; //!< [1014](04)[0x00000000]
void Config (const uint32_t ticks) {
CNTL = 0u;
CNTH = 0u;
CMPLR = ticks - 1u;
CMPHR = 0u;
CTLR.modify ([] (CTLR_DEF & r) -> auto { // TODO ???
r.B.STE = SET;
r.B.STIE = SET;
r.B.STCLK = SET;
r.B.STRE = SET;
return r.R;
});
NVIC.EnableIRQ (SysTicK_IRQn);
}
};
static SysTick_Type & SysTick = * reinterpret_cast<SysTick_Type * const> (0xE000F000);
static constexpr unsigned SYSTEM_CORE_CLOCK = 144'000'000u; // or 96'000'000u
extern "C" {
extern uint32_t SystemCoreClock;
extern void SystemCoreClockUpdate (void);
extern void SystemInit(void);
extern void delay_init ();
extern void delay_us (const unsigned dly);
extern void set_timeout_us (const uint32_t time);
extern bool is_timeout ();
};
#endif // SYSTEM_H

View file

@ -0,0 +1,74 @@
#ifndef BASELAYER_H
#define BASELAYER_H
#include <stdint.h>
#ifdef __arm__
#define debug(...)
#else // ARCH_CM0
#ifdef DEBUG
#define debug printf
#else // DEBUG
#define debug(...)
#endif // DEBUG
#endif // ARCH_CM0
/** @brief Bázová třída pro stack trochu obecnějšího komunikačního protokolu.
*
* @class BaseLayer
* @brief Od této třídy budeme dále odvozovat ostatní.
*
*/
class BaseLayer {
public:
/** Konstruktor
*/
explicit constexpr BaseLayer () noexcept : pUp(nullptr), pDown(nullptr) {};
/** Virtuální metoda, přesouvající data směrem nahoru, pokud s nimi nechceme dělat něco jiného.
@param data ukazatel na pole dat
@param len delka dat v bytech
@return počet přenesených bytů
*/
virtual uint32_t Up (const char * data, const uint32_t len) {
if (pUp) return pUp->Up (data, len);
return 0;
};
/** Virtuální metoda, přesouvající data směrem dolů, pokud s nimi nechceme dělat něco jiného.
@param data ukazatel na pole dat
@param len delka dat v bytech
@return počet přenesených bytů
*/
virtual uint32_t Down (const char * data, const uint32_t len) {
if (pDown) return pDown->Down (data, len);
return len;
};
/** @brief Zřetězení stacku.
* Tohle je vlastně to nejdůležitější. V čistém C by se musely
* nastavovat ukazatele na callback funkce, tady je to čitší - pro uživatele neviditelné,
* ale je to to samé.
@param bl Třída, ležící pod, spodní
@return Odkaz na tuto třídu (aby se to dalo řetězit)
*/
virtual BaseLayer & operator += (BaseLayer & bl) {
bl.setUp (this); // ta spodní bude volat při Up tuto třídu
setDown (& bl); // a tato třída bude volat při Down tu spodní
return * this;
};
/** Getter pro pDown
@return pDown
*/
BaseLayer * getDown (void) const { return pDown; };
protected:
/** Lokální setter pro pUp
@param p Co budeme do pUp dávat
*/
void setUp (BaseLayer * p) { pUp = p; };
/** Lokální setter pro pDown
@param p Co budeme do pDown dávat
*/
void setDown (BaseLayer * p) { pDown = p; };
private:
// Ono to je vlastně oboustranně vázaný spojový seznam.
BaseLayer * pUp; //!< Ukazatel na třídu, která bude dále volat Up
BaseLayer * pDown; //!< Ukazatel na třídu, která bude dále volat Down
};
#endif // BASELAYER_H

73
V203F6P6/common/fifo.h Normal file
View file

@ -0,0 +1,73 @@
#ifndef FIFO_H
#define FIFO_H
/** Typ dbus_w_t je podobně definován jako sig_atomic_t v hlavičce signal.h.
* Je to prostě největší typ, ke kterému je "atomický" přístup. V GCC je definováno
* __SIG_ATOMIC_TYPE__, šlo by použít, ale je znaménkový.
* */
#ifdef __SIG_ATOMIC_TYPE__
typedef unsigned __SIG_ATOMIC_TYPE__ dbus_w_t;
#else
typedef unsigned int dbus_w_t; // pro AVR by to měl být uint8_t (šířka datové sběrnice)
#endif //__SIG_ATOMIC_TYPE__
/// Tahle podivná rekurzívní formule je použita pro validaci délky bufferu.
static constexpr bool isValidM (const int N, const dbus_w_t M) {
// constexpr má raději rekurzi než cyklus (c++11)
return (N > 12) ? false : (((1u << N) == M) ? true : isValidM (N+1, M));
}
/** @class FIFO
* @brief Jednoduchá fronta (kruhový buffer).
*
* V tomto přikladu je vidět, že synchronizace mezi přerušením a hlavní smyčkou programu
* může být tak jednoduchá, že je v podstatě neviditelná. Využívá se toho, že pokud
* do kruhového buferu zapisujeme jen z jednoho bodu a čteme také jen z jednoho bodu
* (vlákna), zápis probíhá nezávisle pomocí indexu m_head a čtení pomocí m_tail.
* Délka dat je dána rozdílem tt. indexů, pokud v průběhu výpočtu délky dojde k přerušení,
* v zásadě se nic špatného neděje, maximálně je délka určena špatně a to tak,
* že zápis nebo čtení je nutné opakovat. Důležité je, že po výpočtu se nová délka zapíše
* do paměti "atomicky". Takže např. pro 8-bit procesor musí být indexy jen 8-bitové.
* To není moc velké omezení, protože tyto procesory obvykle mají dost malou RAM, takže
* velikost bufferu stejně nebývá být větší než nějakých 64 položek.
* Opět nijak nevadí že přijde přerušení při zápisu nebo čtení položky - to se provádí
* dříve než změna indexu, zápis a čtení je vždy na jiném místě RAM. Celé je to uděláno
* jako šablona, takže je možné řadit do fronty i složitější věci než je pouhý byte.
* Druhým parametrem šablony je délka bufferu (aby to šlo konstruovat jako statický objekt),
* musí to být mocnina dvou v rozsahu 8 4096, default je 64. Mocnina 2 je zvolena proto,
* aby se místo zbytku po dělení mohl použít jen bitový and, což je rychlejší.
* */
template<typename T, const dbus_w_t M = 64> class FIFO {
T m_data [M];
volatile dbus_w_t m_head; //!< index pro zápis (hlava)
volatile dbus_w_t m_tail; //!< index pro čtení (ocas)
/// vrací skutečnou délku dostupných dat
constexpr dbus_w_t lenght () const { return (M + m_head - m_tail) & (M - 1); };
/// zvětší a saturuje index, takže se tento motá v kruhu @param n index
void sat_inc (volatile dbus_w_t & n) const { n = (n + 1) & (M - 1); };
public:
/// Konstruktor
explicit constexpr FIFO<T,M> () noexcept {
// pro 8-bit architekturu může být byte jako index poměrně malý
static_assert (1ul << (8 * sizeof(dbus_w_t) - 1) >= M, "atomic type too small");
// a omezíme pro jistotu i delku buferu na nějakou rozumnou delku
static_assert (isValidM (3, M), "M must be power of two in range <8,4096> or <8,128> for 8-bit data bus (AVR)");
m_head = 0;
m_tail = 0;
}
/// Čtení položky
/// @return true, pokud se úspěšně provede
const bool Read (T & c) {
if (lenght() == 0) return false;
c = m_data [m_tail];
sat_inc (m_tail);
return true;
}
/// Zápis položky
/// @return true, pokud se úspěšně provede
const bool Write (const T & c) {
if (lenght() >= (M - 1)) return false;
m_data [m_head] = c;
sat_inc (m_head);
return true;
}
};
#endif // FIFO_H

10
V203F6P6/common/oneway.h Normal file
View file

@ -0,0 +1,10 @@
#ifndef ONEWAY_H
#define ONEWAY_H
#include <stdint.h>
/* C++ interface (jako callback v C) */
template<typename T> class OneWay {
public:
virtual unsigned Send (T * const ptr, const unsigned len) = 0;
};
#endif // ONEWAY_H

85
V203F6P6/common/print.cpp Normal file
View file

@ -0,0 +1,85 @@
#include "print.h"
#define sleep()
static const char * hexStr = "0123456789ABCDEF";
static const uint16_t numLen[] = {1, 32, 1, 11, 8, 0};
Print::Print (PrintBases b) : BaseLayer () {
base = b;
}
// Výstup blokujeme podle toho, co se vrací ze spodní vrstvy
uint32_t Print::BlockDown (const char * buf, uint32_t len) {
uint32_t n, ofs = 0, req = len;
for (;;) {
// spodní vrstva může vrátit i nulu, pokud je FIFO plné
n = BaseLayer::Down (buf + ofs, req);
ofs += n; // Posuneme ukazatel
req -= n; // Zmenšíme další požadavek
if (!req) break;
sleep(); // A klidně můžeme spát
}
return ofs;
}
Print& Print::operator<< (const char * str) {
uint32_t i = 0;
while (str[i++]); // strlen
BlockDown (str, --i);
return *this;
}
Print& Print::operator<< (const int num) {
uint32_t i = BUFLEN;
if (base == DEC) {
unsigned int u;
if (num < 0) u = -num;
else u = num;
do {
// Knihovní div() je nevhodné - dělí 2x.
// Přímočaré a funkční řešení
uint32_t rem;
rem = u % (unsigned) DEC; // 1.dělení
u = u / (unsigned) DEC; // 2.dělení
buf [--i] = hexStr [rem];
} while (u);
if (num < 0) buf [--i] = '-';
} else {
uint32_t m = (1U << (uint32_t) base) - 1U;
uint32_t l = (uint32_t) numLen [(int) base];
uint32_t u = (uint32_t) num;
for (unsigned n=0; n<l; n++) {
buf [--i] = hexStr [u & m];
u >>= (unsigned) base;
}
if (base == BIN) buf [--i] = 'b';
if (base == HEX) buf [--i] = 'x';
buf [--i] = '0';
}
BlockDown (buf+i, BUFLEN-i);
return *this;
}
Print& Print::operator<< (const PrintBases num) {
base = num;
return *this;
}
void Print::out (const void * p, uint32_t l) {
const unsigned char* q = (const unsigned char*) p;
unsigned char uc;
uint32_t k, n = 0;
for (uint32_t i=0; i<l; i++) {
uc = q[i];
buf[n++] = '<';
k = uc >> 4;
buf[n++] = hexStr [k];
k = uc & 0x0f;
buf[n++] = hexStr [k];
buf[n++] = '>';
}
buf[n++] = '\r';
buf[n++] = '\n';
BlockDown (buf, n);
}

73
V203F6P6/common/print.h Normal file
View file

@ -0,0 +1,73 @@
#ifndef PRINT_H
#define PRINT_H
#include "baselayer.h"
#define EOL "\r\n"
#define BUFLEN 64
/**
* @file
* @brief Něco jako ostream.
*
*/
/// Základy pro zobrazení čísla.
enum PrintBases {
BIN=1, OCT=3, DEC=10, HEX=4
};
/**
* @class Print
* @brief Třída pro výpisy do Down().
*
*
* V main pak přibude jen definice instance této třídy
* @code
static Print print;
* @endcode
* a ukázka, jak se s tím pracuje:
* @snippet main.cpp Main print example
* Nic na tom není - operátor << přetížení pro string, číslo a volbu formátu čísla (enum PrintBases).
* Výstup je pak do bufferu a aby nám to "neutíkalo", tedy aby se vypsalo vše,
* zavedeme blokování, vycházející z toho, že spodní třída vrátí jen počet bytů,
* které skutečně odeslala. Při čekání spí, takže nepoužívat v přerušení.
* @snippet src/print.cpp Block example
* Toto blokování pak není použito ve vrchních třídách stacku,
* blokovaná metoda je BlockDown(). Pokud bychom použili přímo Down(), blokování by pak
* používaly všechny vrstvy nad tím. A protože mohou Down() používat v přerušení, byl by problém.
*
* Metody pro výpisy jsou sice dost zjednodušené, ale zase to nezabere
* moc místa - pro ladění se to použít . Délka vypisovaného stringu není omezena
* délkou použitého buferu.
*
*/
class Print : public BaseLayer {
public:
/// Konstruktor @param b Default decimální výpisy.
Print (PrintBases b = DEC);
/// Blokování výstupu
/// @param buf Ukazatel na data
/// @param len Délka přenášených dat
/// @return Počet přenesených bytů (rovno len)
uint32_t BlockDown (const char * buf, uint32_t len);
/// Výstup řetězce bytů
/// @param str Ukazatel na řetězec
/// @return Odkaz na tuto třídu kvůli řetězení.
Print & operator << (const char * str);
/// Výstup celého čísla podle base
/// @param num Číslo
/// @return Odkaz na tuto třídu kvůli řetězení.
Print & operator << (const int num);
/// Změna základu pro výstup čísla
/// @param num enum PrintBases
/// @return Odkaz na tuto třídu kvůli řetězení.
Print & operator << (const PrintBases num);
void out (const void* p, uint32_t l);
private:
PrintBases base; //!< Základ pro výstup čísla.
char buf[BUFLEN]; //!< Buffer pro výstup čísla.
};
#endif // PRINT_H

21
V203F6P6/common/usart.h Normal file
View file

@ -0,0 +1,21 @@
#ifndef USART_H
#define USART_H
#include "fifo.h"
#include "baselayer.h"
/** @class Usart
* @brief Sériový port.
*
* Zde RS485, jen výstup.
*/
class Usart : public BaseLayer {
FIFO<char, 64> tx_ring;
public:
explicit Usart (const uint32_t baud = 9600) noexcept;
uint32_t Down (const char * data, const uint32_t len) override;
void SetRS485 (const bool polarity) const;
void irq (void);
void SetHalfDuplex (const bool on) const;
};
#endif // USART_H

54
V203F6P6/ws2812b/Makefile Normal file
View file

@ -0,0 +1,54 @@
#TARGET?= linux
TARGET?= ch32v203
TOOL ?= gcc
#TOOL ?= clang
PRJ = example
VPATH = . ./$(TARGET)
BLD = ./build/
DFLAGS = -d
LFLAGS = -g
LDLIBS =
BFLAGS = --strip-unneeded
CFLAGS = -MMD -Wall -ggdb -fno-exceptions -ffunction-sections -fdata-sections
CFLAGS+= -I. -I./common -I./$(TARGET)
DEL = rm -f
# zdrojaky
OBJS = main.o ws2812b.o spiclass.o hack.o table.o
#OBJS +=
include $(TARGET)/$(TOOL).mk
BOBJS = $(addprefix $(BLD),$(OBJS))
all: $(BLD) $(PRJ).elf
# ... atd.
-include $(BLD)*.d
# linker
$(PRJ).elf: $(BOBJS)
-@echo [LD $(TOOL),$(TARGET)] $@
@$(LD) $(LFLAGS) -o $(PRJ).elf $(BOBJS) $(LDLIBS)
-@echo "size:"
@$(SIZE) $(PRJ).elf
-@echo "listing:"
$(DUMP) $(DFLAGS) $(PRJ).elf > $(PRJ).lst
-@echo "OK."
$(COPY) $(BFLAGS) -O binary $(PRJ).elf $(PRJ).bin
# preloz co je potreba
$(BLD)%.o: %.c
-@echo [CC $(TOOL),$(TARGET)] $@
@$(CC) -std=gnu99 -c $(CFLAGS) $< -o $@
$(BLD)%.o: %.cpp
-@echo [CX $(TOOL),$(TARGET)] $@
@$(CXX) -std=c++17 -fno-rtti -c $(CFLAGS) $< -o $@
$(BLD):
mkdir $(BLD)
flash: $(PRJ).elf
minichlink -w $(PRJ).bin flash -b
# vycisti
clean:
$(DEL) $(BLD)* *.lst *.bin *.elf *.map *~
.PHONY: all clean flash run

1
V203F6P6/ws2812b/ch32v203 Symbolic link
View file

@ -0,0 +1 @@
../ch32v203/

1
V203F6P6/ws2812b/common Symbolic link
View file

@ -0,0 +1 @@
../common/

21
V203F6P6/ws2812b/hack.c Normal file
View file

@ -0,0 +1,21 @@
#include <stdint.h>
#include <stdarg.h>
typedef __SIZE_TYPE__ size_t;
size_t strlen (const char *s) {
size_t l = 0;
while (*s++) l++;
return l;
}
void *memcpy (void *dest, const void *src, size_t n) {
const char *s = (const char *) src;
char *d = (char *) dest;
int i;
for (i=0; i<n; i++) d[i] = s[i];
return dest;
}
void *memset (void *s, int c, size_t n) {
char *p = (char *) s;
int i;
for (i=0; i<n; i++) p[i] = c;
return s;
}

View file

@ -0,0 +1,19 @@
CC = gcc
CX = g++
LD = ld
CFLAGS = -c -Os -fPIC
OBJS = main.o
SLIB = graph.so
all: $(SLIB)
$(SLIB): $(OBJS)
$(CX) -shared $(OBJS) -o $(SLIB)
%.o: %.c
$(CC) $(CFLAGS) $< -o $@
%.o: %.cpp
$(CX) $(CFLAGS) $< -o $@
clean:
rm -f $(OBJS) *.png

42
V203F6P6/ws2812b/linux/graph.py Executable file
View file

@ -0,0 +1,42 @@
#!/usr/bin/python3
# -*- coding: utf-8 -*-
import os
import cffi
import numpy as np
import matplotlib.pyplot as plt
c_header = '''
void print_table (void);
double ComputeRed (double);
double ComputeGreen (double);
double ComputeBlue (double);
'''
def plot_colors(C):
yr = []; yg = []; yb = [];
xs = np.arange(0.0, 256.0, 1.0)
for x in xs: yr.append (C.ComputeRed (x))
for x in xs: yg.append (C.ComputeGreen(x))
for x in xs: yb.append (C.ComputeBlue (x))
fig,ap = plt.subplots (1, figsize=(6.0,4.0))
fig.suptitle ('Color functions', fontsize=15)
ap.plot (xs, yr, 'r-')
ap.plot (xs, yg, 'g-')
ap.plot (xs, yb, 'b-')
ap.legend (['R','G','B'])
plt.grid()
plt.ylabel('Intenzity')
plt.xlabel('N')
#plt.savefig('color.png')
plt.show()
############################ MAIN ##############################################################
def main_func():
ffi = cffi.FFI()
ffi.cdef(c_header)
C = ffi.dlopen("./graph.so")
plot_colors(C)
#C.print_table()
ffi.dlclose(C)
return True
if __name__ == '__main__':
r = main_func()
print ('END {:s}'.format(str(r)))

View file

@ -0,0 +1,74 @@
#include <stdint.h>
#include <cmath>
#include <cstdio>
extern "C" {
extern void print_table (void);
extern double ComputeRed (double);
extern double ComputeGreen (double);
extern double ComputeBlue (double);
};
union Color {
struct _c {
uint8_t g, r, b, a;
explicit _c (const uint8_t _r, const uint8_t _g, const uint8_t _b) noexcept :
g(_g), r(_r), b(_b), a(0u) {}
} c;
uint32_t number;
explicit Color (const uint8_t r, const uint8_t g, const uint8_t b) : c(r, g, b) {}
};
#if 0
static Color getColor (const int index) {
const double fi = 2.0 * M_PI / 3.0; // úhel posunu argumentu barvy
const double ph = M_PI / 128.0;
double a1, a2, a3;
uint8_t r,g,b; // proměnné barvy
// výpočet barvy - duha
a1 = (double) index * ph; // argument pro r
a2 = a1 + fi; // argument pro g
a3 = a2 + fi; // argument pro b
r = (int)(127.0 + 127.0*sin(a1));
g = (int)(127.0 + 127.0*sin(a2));
b = (int)(127.0 + 127.0*sin(a3));
Color color(r, g, b);
return color;
}
#else
static uint8_t Gauss (const double x, const double x0) {
const double sigma = 1.0 / 2048.0, arg = x - x0;
double r = 256.0 * exp (-sigma * arg * arg);
return uint8_t (r);
}
static Color getColor (const int index) {
uint8_t r=0,g=0,b=0; // proměnné barvy
r = Gauss(index, 85.333);
g = Gauss(index, 170.67);
b = Gauss(index, 0.01) + Gauss(index, 256.0);
Color color(r, g, b);
return color;
}
#endif
double ComputeRed (double x) {
Color c = getColor(x);
return double (c.c.r);
}
double ComputeGreen (double x) {
Color c = getColor(x);
return double (c.c.g);
}
double ComputeBlue (double x) {
Color c = getColor(x);
return double (c.c.b);
}
void print_table () {
FILE * out = fopen("../table.c","w");
if (!out) return;
fprintf(out, "const unsigned table [] = {");
for (unsigned n=0u; n<256u; n++) {
if ((n%8) == 0u) fprintf(out, "\n");
const Color c = getColor(n);
fprintf(out, " 0x%06X,", c.number);
}
fprintf(out, "\n};\n");
fclose(out);
}

32
V203F6P6/ws2812b/main.cpp Normal file
View file

@ -0,0 +1,32 @@
#include "fifo.h"
#include "spiclass.h"
#include "system.h"
#include "gpio.h"
extern "C" {
extern const unsigned table []; // generováno linux/graph.py
};
static FIFO<uint32_t, FIFOLEN> ring;
static ws2812b driver(ring);
static SpiClass spi (driver);
static GpioClass led (GPIOB, 8);
static constexpr unsigned timeout = 10'000u;
int main () {
led << true;
delay_init();
spi.Init();
unsigned counter = 0u;
for (;;) {
delay_us(timeout);
const bool b = counter & 0x100u;
led << b;
counter += 1u;
for (unsigned n=0u; n<NUMLEDS; n++) {
unsigned cmd = ((counter + 64u * n) & 0xFFu);
cmd = table [cmd] | (n << 24);
ring.Write (cmd);
}
}
return 0;
}

View file

@ -0,0 +1,115 @@
#include "system.h"
#include "spiclass.h"
typedef __SIZE_TYPE__ size_t;
enum SPICLK : uint32_t {
FPCLK_2 = 0u, // 72 MHz
FPCLK_4, // 36 MHz
FPCLK_8, // 18 MHz
FPCLK_16, // 9 MHz
FPCLK_32, // 4.5 MHz
FPCLK_64, // 2.25 MHz
FPCLK_128, // 1.125 MHz
FPCLK_256, // 0.5625 MHz
};
static SpiClass * pSpiInstance = nullptr;
extern "C" {
//[[gnu::interrupt]] extern void DMA1_Channel2_IRQHandler();
[[gnu::interrupt]] extern void DMA1_Channel3_IRQHandler();
extern void * memcpy (void * dest, const void * src, size_t n);
};
void DMA1_Channel3_IRQHandler() { // transmit channel
if (pSpiInstance) pSpiInstance->drq();
}
static constexpr unsigned FM = 3u; // 50 MHz
static void InitPins () noexcept {
// PA4 - NSS, PA5 - SCK, PA6 - MISO, PA7 - MOSI
GPIOA.CFGLR.modify([](GPIOA_Type::CFGLR_DEF & r) -> uint32_t {
/*r.B.MODE4 = FM;
r.B.CNF4 = 2u; // alt push - pull
r.B.MODE6 = 0u; // input mode
r.B.CNF6 = 1u; // floating */
r.B.MODE5 = FM;
r.B.CNF5 = 2u; // alt push - pull
r.B.MODE7 = FM;
r.B.CNF7 = 2u; // alt push - pull
return r.R;
});
// AFIO - default
}
void SpiClass::drq() {
if (!driver) return;
DMA1_Type::INTFR_DEF state (DMA1.INTFR);
/*if (state.B.HTIF3) {
DMA1.INTFCR.B.CHTIF3 = SET; // clear half
} */
if (state.B.TCIF3) {
DMA1.INTFCR.B.CTCIF3 = SET; // clear complete
driver->Send (ptrh, LEDS_LEN);
}
}
SpiClass::SpiClass(OneWay<uint8_t> & base) noexcept : driver (& base), ptrl (buffer), ptrh (buffer + PADDING) {
pSpiInstance = this;
for (unsigned n=0u; n<FULL_LEN; n++) buffer[n] = 0u;
Color * ptr = reinterpret_cast<Color*>(ptrh);
const OneColor oz(0x00);
for (unsigned n=0; n<NUMLEDS; n++) {
Color & c = ptr [n];
c.b = oz; c.g = oz; c.r = oz;
}
}
void SpiClass::Init() {
RCC.APB2PCENR.modify([](RCC_Type::APB2PCENR_DEF & r) -> uint32_t {
r.B.SPI1EN = SET;
r.B.IOPAEN = SET;
r.B.AFIOEN = SET;
return r.R;
});
RCC.AHBPCENR.B.DMA1EN = SET;
InitPins();
// Configure the peripheral data register address
DMA1.PADDR3.R = reinterpret_cast<size_t> (& SPI1.DATAR);
// Configure the memory address
DMA1.MADDR3.R = reinterpret_cast<size_t> (buffer);
// Configure the number of DMA tranfer to be performs on DMA channel 3
DMA1.CNTR3 .R = FULL_LEN;
// Configure increment, size, interrupts and circular mode
DMA1.CFGR3.modify([] (DMA1_Type::CFGR3_DEF & r) -> uint32_t {
r.B.PL = 3u; // highest priority
r.B.DIR = SET; // memory -> periferal
r.B.MINC = SET; // memory increment
r.B.MSIZE = 0u; // 8-bit
r.B.PSIZE = 0u; // 8-bit
//r.B.HTIE = SET; // INT Enable HALF
r.B.TCIE = SET; // INT Enable FULL
r.B.CIRC = SET; // Circular MODE
// Enable DMA Channel 1
r.B.EN = SET;
return r.R;
});
SPI1.CTLR1.modify([](SPI1_Type::CTLR1_DEF & r) -> uint32_t {
r.B.CPHA = RESET;
r.B.CPOL = RESET;
r.B.MSTR = SET;
r.B.DFF = RESET; // 8 bit
r.B.SSM = SET;
r.B.SSI = SET;
r.B.LSBFIRST = SET;
/* 2.25 MHz - 1bit = 444 ns
* 1 LED => 9 x 8 x 0.444 = 32 us DMA celkem (10 + 4) x 32 = 0.448 ms
* */
r.B.BR = FPCLK_64;
return r.R;
});
SPI1.CTLR2.modify([](SPI1_Type::CTLR2_DEF & r) -> uint32_t {
r.B.SSOE = SET;
//r.B.RXNEIE = SET;
//r.B.TXEIE = SET;
r.B.TXDMAEN = SET;
return r.R;
});
NVIC.EnableIRQ(DMA1_Channel3_IRQn);
SPI1.CTLR1.B.SPE = SET;
}

View file

@ -0,0 +1,23 @@
#ifndef SPICLASS_H
#define SPICLASS_H
#include <stdint.h>
#include "ws2812b.h"
/**
*/
static constexpr unsigned PADDING = 10 * sizeof (Color);
static constexpr unsigned LEDS_LEN = NUMLEDS * sizeof (Color);
static constexpr unsigned FULL_LEN = PADDING + LEDS_LEN;
class SpiClass {
OneWay<uint8_t> * driver;
uint8_t * const ptrl;
uint8_t * const ptrh;
uint8_t buffer [FULL_LEN];
public:
explicit SpiClass (OneWay<uint8_t> & base) noexcept;
void Init ();
void drq ();
protected:
};
#endif // SPICLASS_H

34
V203F6P6/ws2812b/table.c Normal file
View file

@ -0,0 +1,34 @@
const unsigned table [] = {
0xFF0700, 0xFF0700, 0xFF0800, 0xFE0900, 0xFE0A00, 0xFC0A00, 0xFB0B00, 0xF90C00,
0xF80D00, 0xF60E00, 0xF31000, 0xF11100, 0xEE1200, 0xEB1300, 0xE81500, 0xE51600,
0xE11800, 0xDE1A00, 0xDA1B00, 0xD61D00, 0xD21F00, 0xCE2100, 0xCA2400, 0xC52600,
0xC12800, 0xBC2B00, 0xB82D00, 0xB33000, 0xAE3300, 0xA93600, 0xA43900, 0xA03C00,
0x9B3F00, 0x964300, 0x914600, 0x8C4A00, 0x874E00, 0x835100, 0x7E5500, 0x795900,
0x755D00, 0x706200, 0x6C6600, 0x676A00, 0x636F00, 0x5F7300, 0x5B7800, 0x577C00,
0x538100, 0x4F8600, 0x4B8B00, 0x478F00, 0x449400, 0x409900, 0x3D9E00, 0x3AA300,
0x37A800, 0x34AC00, 0x31B100, 0x2EB600, 0x2CBB00, 0x29BF00, 0x27C400, 0x24C800,
0x22CD00, 0x20D101, 0x1ED501, 0x1CD901, 0x1ADD01, 0x19E001, 0x17E401, 0x15E702,
0x14EA02, 0x12ED02, 0x11F002, 0x10F302, 0x0FF503, 0x0EF703, 0x0DF903, 0x0CFB04,
0x0BFC04, 0x0AFD05, 0x09FE05, 0x08FF06, 0x08FF06, 0x07FF07, 0x06FF07, 0x06FF08,
0x05FF09, 0x05FE09, 0x04FD0A, 0x04FC0B, 0x04FA0C, 0x03F80D, 0x03F60E, 0x03F40F,
0x02F210, 0x02EF12, 0x02EC13, 0x02E914, 0x01E616, 0x01E317, 0x01DF19, 0x01DB1B,
0x01D71D, 0x01D31F, 0x01CF21, 0x00CB23, 0x00C725, 0x00C227, 0x00BE2A, 0x00B92C,
0x00B42F, 0x00B032, 0x00AB35, 0x00A638, 0x00A13B, 0x009C3E, 0x009842, 0x009345,
0x008E49, 0x00894C, 0x008450, 0x008054, 0x007B58, 0x00765C, 0x007260, 0x006D64,
0x006969, 0x00646D, 0x006072, 0x005C76, 0x00587B, 0x005480, 0x005084, 0x004C89,
0x00498E, 0x004593, 0x004298, 0x003E9C, 0x003BA1, 0x0038A6, 0x0035AB, 0x0032B0,
0x002FB4, 0x002CB9, 0x002ABE, 0x0027C2, 0x0025C7, 0x0023CB, 0x0121CF, 0x011FD3,
0x011DD7, 0x011BDB, 0x0119DF, 0x0117E3, 0x0116E6, 0x0214E9, 0x0213EC, 0x0212EF,
0x0210F2, 0x030FF4, 0x030EF6, 0x030DF8, 0x040CFA, 0x040BFC, 0x040AFD, 0x0509FE,
0x0509FF, 0x0608FF, 0x0607FF, 0x0707FF, 0x0806FF, 0x0806FF, 0x0905FE, 0x0A05FD,
0x0B04FC, 0x0C04FB, 0x0D03F9, 0x0E03F7, 0x0F03F5, 0x1002F3, 0x1102F0, 0x1202ED,
0x1402EA, 0x1502E7, 0x1701E4, 0x1901E0, 0x1A01DD, 0x1C01D9, 0x1E01D5, 0x2001D1,
0x2200CD, 0x2400C8, 0x2700C4, 0x2900BF, 0x2C00BB, 0x2E00B6, 0x3100B1, 0x3400AC,
0x3700A8, 0x3A00A3, 0x3D009E, 0x400099, 0x440094, 0x47008F, 0x4B008B, 0x4F0086,
0x530081, 0x57007C, 0x5B0078, 0x5F0073, 0x63006F, 0x67006A, 0x6C0066, 0x700062,
0x75005D, 0x790059, 0x7E0055, 0x830051, 0x87004E, 0x8C004A, 0x910046, 0x960043,
0x9B003F, 0xA0003C, 0xA40039, 0xA90036, 0xAE0033, 0xB30030, 0xB8002D, 0xBC002B,
0xC10028, 0xC50026, 0xCA0024, 0xCE0021, 0xD2001F, 0xD6001D, 0xDA001B, 0xDE001A,
0xE10018, 0xE50016, 0xE80015, 0xEB0013, 0xEE0012, 0xF10011, 0xF30010, 0xF6000E,
0xF8000D, 0xF9000C, 0xFB000B, 0xFC000A, 0xFE000A, 0xFE0009, 0xFF0008, 0xFF0007,
};

View file

@ -0,0 +1,52 @@
#include "ws2812b.h"
enum WS2812B_SPI : uint32_t {
BIT_LOW = 1u, BIT_HIGH = 3u,
};
OneColor::OneColor(const uint8_t color) noexcept {
b0 = (color & 0x80u) ? BIT_HIGH : BIT_LOW;
b1 = (color & 0x40u) ? BIT_HIGH : BIT_LOW;
b2 = (color & 0x20u) ? BIT_HIGH : BIT_LOW;
b3 = (color & 0x10u) ? BIT_HIGH : BIT_LOW;
b4 = (color & 0x08u) ? BIT_HIGH : BIT_LOW;
b5 = (color & 0x04u) ? BIT_HIGH : BIT_LOW;
b6 = (color & 0x02u) ? BIT_HIGH : BIT_LOW;
b7 = (color & 0x01u) ? BIT_HIGH : BIT_LOW;
}
unsigned OneColor::to_string(char * ptr, const int m) {
auto f = [=](const uint32_t x, char * buf) -> unsigned {
unsigned i = 0;
for (int k=0; k<m; k++) {
buf [i++] = x & (1u << k) ? '1' : '0';
}
return i;
};
unsigned n = 0;
n += f (b0, ptr + n);
n += f (b1, ptr + n);
n += f (b2, ptr + n);
n += f (b3, ptr + n);
n += f (b4, ptr + n);
n += f (b5, ptr + n);
n += f (b6, ptr + n);
n += f (b7, ptr + n);
ptr [n] = '\0';
return n;
}
ws2812b::ws2812b (FIFO<uint32_t,8> & r) noexcept : OneWay (), ring(r) {
}
unsigned int ws2812b::Send (uint8_t * const ptr, const unsigned int len) {
uint32_t cmd;
while (ring.Read(cmd)) {
const Entry ne (cmd);
if (ne.ws.order < NUMLEDS) {
Color * cptr = reinterpret_cast<Color*>(ptr);
Color & c = cptr [ne.ws.order];
const OneColor cb (ne.ws.b), cg (ne.ws.g), cr (ne.ws.r);
c.b = cb; c.g = cg; c.r = cr;
}
}
return len;
}

View file

@ -0,0 +1,52 @@
#ifndef WS2812B_H
#define WS2812B_H
#include <stdint.h>
#include "oneway.h"
#include "fifo.h"
static constexpr int BWW = 3;
struct OneColor {
uint32_t b0 : BWW;
uint32_t b1 : BWW;
uint32_t b2 : BWW;
uint32_t b3 : BWW;
uint32_t b4 : BWW;
uint32_t b5 : BWW;
uint32_t b6 : BWW;
uint32_t b7 : BWW;
explicit OneColor (const uint8_t c) noexcept;
unsigned to_string (char * ptr, const int m = BWW);
}__attribute__((packed));
struct Color {
OneColor g,r,b;
}__attribute__((packed));
union Entry {
struct _ws {
uint8_t g,r,b;
uint8_t order; // určuje pořadí LED
} ws;
uint32_t number;
explicit Entry (const uint32_t e) noexcept { number = e; }
};
/*************************************************************************************/
static constexpr unsigned NUMLEDS = 4u;
static constexpr unsigned FIFOLEN = 8u; // min. depth je 8, jinak mocnina 2 >= NUMLEDS
/*************************************************************************************/
/** @class ws2812b
* @brief Driver pro WS2812B
* On ten driver je trochu divný. Běží nad SPI s použitím pinu MOSI, 1 bit barvy
* jsou 3 bity SPI. Funguje to tak, že SPI běží přes DMA v cirkulárním módu, tedy
* pořád, v 1. části dělá "reset", tedy časování rámce (vysílá nuly).
* V 2. části si vybere z fronty ring data a uloží je do buferu ve správném
* tvaru. Využívá se toho, že přerušení přijde na konci a naplnění daty
* netrvá dlouho, takže se přepisuje jen část, která se nevysílá.
* Fronta byla použita (celkem zbytečně) protože zatím netuším jaká data posílat.
* */
class ws2812b : public OneWay<uint8_t> {
FIFO<uint32_t,FIFOLEN> & ring;
public:
explicit ws2812b (FIFO<uint32_t,FIFOLEN> & r) noexcept;
unsigned int Send (uint8_t * const ptr, const unsigned int len) override;
protected:
};
#endif // WS2812B_H