add files

This commit is contained in:
Kizarm 2024-02-29 12:22:16 +01:00
parent 18390d8b4f
commit fdcc93ce96
21 changed files with 14354 additions and 0 deletions

9
.gitignore vendored Normal file
View file

@ -0,0 +1,9 @@
# kdevelop
.kde*
*.kdev4
# other
**/build/*
*.lst
*.bin
*.map
*.elf

View file

@ -1,2 +1,12 @@
# RISC-V
Po 32-bit jednočipech založených na jádru Cortex-Mx nastal čas vyzkoušet něco nového.
CH32V003 od čínské firmy WCH se zdá být dobrá volba. Je to levné, malé, má to
podporu open source a snese to 5V napájení.
Základem je projekt https://github.com/cnlohr/ch32v003fun. Pokusil jsem se z toho
vybrat jen to, co je nezbytně nutné a přepsat to do C++. Je potřeba prográmek
minichlink, který umí flashnout firmware a GDB server.
## hello
Základní program, používá GPIO a SysTick v režimu přerušení pro blikání LEDkou.

4179
ch32v003/CH32V00xxx.h Normal file

File diff suppressed because it is too large Load diff

20
ch32v003/clang.mk Normal file
View file

@ -0,0 +1,20 @@
# Use clang / llvm toolchain
# zatim blbost
CC = clang
CXX = clang++
LD = ld.lld
#LD = riscv64-unknown-elf-gcc
SIZE = llvm-size
DUMP = riscv64-unknown-elf-objdump
COPY = riscv64-unknown-elf-objcopy
OBJS += startup.o system.o
CCPU = -march=rv32ec -mabi=ilp32e
MCPU = $(CCPU)
TRIP = riscv32-unknown-none-elf
CFLAGS+= -Oz -flto
#CFLAGS+= -fconstexpr-steps=2097152
CFLAGS+= --target=$(TRIP) -mllvm -mattr=+c,+e -mno-relax
LFLAGS+= --Map=$(@:%.elf=%.map) --gc-sections -mllvm -mattr=+c
LFLAGS+= -lto-O3 -nostdlib
LDLIBS+= -L./$(TARGET) -T generated_ch32v003.ld

17
ch32v003/gcc.mk Normal file
View file

@ -0,0 +1,17 @@
# Use gcc / binutils toolchain
PREFIX = riscv64-unknown-elf-
CC = $(PREFIX)gcc
CXX = $(PREFIX)g++
LD = $(PREFIX)gcc
SIZE = $(PREFIX)size
DUMP = $(PREFIX)objdump
COPY = $(PREFIX)objcopy
OBJS += startup.o system.o
CFLAGS+= -Os -flto
CCPU = -march=rv32ec -mabi=ilp32e
MCPU = $(CCPU)
CFLAGS+= $(MCPU)
LFLAGS+= -Wl,--Map=$(@:%.elf=%.map),--gc-sections
#LFLAGS+= -Wl,--print-sysroot -- chyba ld ?
LFLAGS+= -flto -O3 $(MCPU) -nostartfiles -nostdlib
LDLIBS+= -lgcc -L./$(TARGET) -T generated_ch32v003.ld

View file

@ -0,0 +1,115 @@
ENTRY( InterruptVector )
MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 16K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 2K
}
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));
}

47
ch32v003/gpio.h Normal file
View file

@ -0,0 +1,47 @@
#ifndef _GPIO_CLASS_H_
#define _GPIO_CLASS_H_
#include "CH32V00xxx.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,
};
class GpioClass {
GPIOA_Type & port;
const uint32_t pin;
public:
explicit constexpr 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.IOPCEN = SET;
r.B.IOPDEN = SET;
return r.R;
});
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;
});
}
void operator<< (const bool b) const {
port.BSHR.R = b ? 1u << pin : 1u << (pin + 16);
}
operator bool () const {
return port.INDR.R & (1u << pin);
}
};
#endif // _GPIO_CLASS_H_

168
ch32v003/startup.cpp Normal file
View file

@ -0,0 +1,168 @@
#include "CH32V00xxx.h"
typedef __SIZE_TYPE__ size_t;
extern "C" {
extern void handle_reset () __attribute__((naked,nothrow,used));
extern void user_prog () __attribute__((used));
extern int main () __attribute__((used));
extern void SystemInit() __attribute__((used));
// 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;
extern void (*__preinit_array_start[]) (void) __attribute__((weak));
extern void (*__preinit_array_end[]) (void) __attribute__((weak));
extern void (*__init_array_start[]) (void) __attribute__((weak));
extern void (*__init_array_end[]) (void) __attribute__((weak));
static void __init_array () {
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++;
}
size_t count;
/* 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]();
*/
count = __init_array_end - __init_array_start;
for (unsigned i = 0; i < count; i++) __init_array_start[i]();
}
// If you don't override a specific handler, it will just spin forever.
void DefaultIRQHandler( void ) {
// Infinite Loop
for (;;);
}
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 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 FLASH_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void RCC_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void EXTI7_0_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void AWU_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 ADC1_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 I2C1_EV_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void I2C1_ER_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void USART1_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void SPI1_IRQHandler( void ) ALIAS(DefaultIRQHandler);
void InterruptVector() __attribute__((nothrow,naked,section(".init"),weak,alias("InterruptVectorDefault")));
void InterruptVectorDefault() __attribute__((nothrow,naked,section(".init")));
};
void InterruptVectorDefault() noexcept {
asm volatile( R"---(
.align 2
.option push
.option norvc
j handle_reset
.word 0
.word NMI_Handler /* NMI Handler */
.word HardFault_Handler /* Hard Fault Handler */
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word 0
.word SysTick_Handler /* SysTick Handler */
.word 0
.word SW_Handler /* SW Handler */
.word 0
/* External Interrupts */
.word WWDG_IRQHandler /* Window Watchdog */
.word PVD_IRQHandler /* PVD through EXTI Line detect */
.word FLASH_IRQHandler /* Flash */
.word RCC_IRQHandler /* RCC */
.word EXTI7_0_IRQHandler /* EXTI Line 7..0 */
.word AWU_IRQHandler /* AWU */
.word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
.word DMA1_Channel2_IRQHandler /* DMA1 Channel 2 */
.word DMA1_Channel3_IRQHandler /* DMA1 Channel 3 */
.word DMA1_Channel4_IRQHandler /* DMA1 Channel 4 */
.word DMA1_Channel5_IRQHandler /* DMA1 Channel 5 */
.word DMA1_Channel6_IRQHandler /* DMA1 Channel 6 */
.word DMA1_Channel7_IRQHandler /* DMA1 Channel 7 */
.word ADC1_IRQHandler /* ADC1 */
.word I2C1_EV_IRQHandler /* I2C1 Event */
.word I2C1_ER_IRQHandler /* I2C1 Error */
.word USART1_IRQHandler /* USART1 */
.word SPI1_IRQHandler /* SPI1 */
.word TIM1_BRK_IRQHandler /* TIM1 Break */
.word TIM1_UP_IRQHandler /* TIM1 Update */
.word TIM1_TRG_COM_IRQHandler /* TIM1 Trigger and Commutation */
.word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
.word TIM2_IRQHandler /* TIM2 */
.option pop
)---");
}
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"---(
li a0, 0x80
csrw mstatus, a0
li a3, 0x3
la a0, InterruptVector
or a0, a0, a3
csrw mtvec, a0
/* Takhle RISC-V přejde do uživatelského programu. */
csrw mepc, %[user]
mret
)---"
: : [user]"r"(user_prog)
: "a0", "a3", "memory" );
}
void user_prog () {
SystemInit ();
__init_array();
main();
for (;;);
}

24
ch32v003/system.cpp Normal file
View file

@ -0,0 +1,24 @@
#include "CH32V00xxx.h"
extern "C" void SystemInit ();
enum CLKSRC : uint32_t {
CLK_HSI = 0u,
CLK_HSE,
CLK_PLL,
};
void SystemInit(void) {
RCC.CFGR0.R = 0u; // prescaler OFF
RCC.CTLR.modify([](RCC_Type::CTLR_DEF & r) -> auto {
r.B.HSITRIM = 0x10u;
r.B.HSION = SET;
r.B.HSEBYP = SET;
r.B.CSSON = SET;
r.B.PLLON = SET;
return r.R;
});
FLASH.ACTLR.B.LATENCY = SET;
RCC.INTR.R = 0x009F0000u; // clear interrupts
while (RCC.CTLR.B.PLLRDY == RESET);
RCC.CFGR0.B.SW = CLK_PLL;
while (RCC.CFGR0.B.SWS != CLK_PLL);
}

73
ch32v003/system.h Normal file
View file

@ -0,0 +1,73 @@
#ifndef SYSTEM_H
#define SYSTEM_H
#include "CH32V00xxx.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));
}
};
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
uint32_t UNUSED0 : 27; //!<[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;
__IO uint32_t SR;
__IO uint32_t CNT;
uint32_t RESERVED0;
__IO uint32_t CMP;
uint32_t RESERVED1;
void Config (const uint32_t ticks) {
CNT = 0u;
CMP = ticks - 1u;
CTLR.modify ([] (CTLR_DEF & r) -> auto {
r.B.STE = SET;
r.B.STIE = SET;
r.B.STCLK = SET;
r.B.STRE = SET;
return r.R;
});
NVIC.EnableIRQ (SysTicK_IRQn);
}
};
SysTick_Type & SysTick = * reinterpret_cast<SysTick_Type * const> (0xE000F000);
#endif // SYSTEM_H

BIN
doc/CH32V003DS0.PDF Normal file

Binary file not shown.

BIN
doc/CH32V003RM.PDF Normal file

Binary file not shown.

BIN
doc/CH32V00xSCH.pdf Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

9530
doc/ch32v003.svd Normal file

File diff suppressed because it is too large Load diff

53
hello/Makefile Normal file
View file

@ -0,0 +1,53 @@
# ch32v003
TARGET?= ch32v003
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./$(TARGET) -I/usr/include/newlib
DEL = rm -f
# zdrojaky
OBJS = main.o morse.o
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) -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

1
hello/ch32v003 Symbolic link
View file

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

11
hello/main.cpp Normal file
View file

@ -0,0 +1,11 @@
/* SIMPLE EXAMPLE: LED blinking */
#include "morse.h"
//////////////////////////////////////
int main () {
GpioClass led (GPIOD, 4);
Morse morse (led, 333);
for (;;) {
morse << "hello world";
}
return 0;
}

73
hello/morse.cpp Normal file
View file

@ -0,0 +1,73 @@
#include "system.h"
#include "morse.h"
static constexpr unsigned slen (const char * const str) {
unsigned n = 0;
while (str[n]) n++;
return n;
}
static const unsigned char compressed_table [] = {
0x00, 0x00, 0xd2, 0x00, 0x00, 0x00, 0x00, 0xde, 0xad, 0xed, 0x00, 0xaa, 0xf3, 0xe1, 0xea, 0xa9,
0xbf, 0xbe, 0xbc, 0xb8, 0xb0, 0xa0, 0xa1, 0xa3, 0xa7, 0xaf, 0xc7, 0xd5, 0x00, 0xb1, 0x00, 0xcc,
0xd6, 0x42, 0x81, 0x85, 0x61, 0x20, 0x84, 0x63, 0x80, 0x40, 0x8e, 0x65, 0x82, 0x43, 0x41, 0x67,
0x86, 0x8b, 0x62, 0x60, 0x21, 0x64, 0x88, 0x66, 0x89, 0x8d, 0x83, 0x00, 0x00, 0x00, 0x00, 0xec,
};
extern "C" void SysTick_Handler() __attribute__((interrupt));
static volatile unsigned count = 0u;
void SysTick_Handler () {
SysTick.SR = 0u;
if (count) count -= 1;
}
static void delay (const unsigned ms) {
count = ms;
while (count);
}
Morse::Morse(const GpioClass & pin, const unsigned int ms) noexcept : unit (ms), led (pin) {
SysTick.Config (48000u);
}
const Morse & Morse::operator<< (const char * text) const {
const unsigned len = slen (text);
for (unsigned n=0; n<len; n++) {
const char c = text [n];
morse_byte mb;
if (c < '\x20') {
} else if (c < '`') {
const int i = c - '\x20';
mb.byte = compressed_table [i];
} else if (c == '`') {
} else if (c <= 'z') {
const int i = c - '\x40';
mb.byte = compressed_table [i];
} else {
}
out (mb);
}
delay (10 * unit);
return * this;
}
/* . => 1 x unit
* - => 3 x unit
* mezera mezi značkami => 1 x unit
* mezera mezi znaky => 3 x unit
* mezera mezi slovy => 7 x unit
* */
void Morse::out (const morse_byte mb) const {
/* Finta je v tom, že i když se pole mlen a bits překrývají,
* nevadí to - maximální délka je 6, takže v nejnižším bitu
* mlen může být obsažen 1 bit 6.bitového znaku.
* Takhle napsáno to běhá jen na malém indiánu, přepisovat
* to do bitových posunů nebudu, i když by to bylo čistší.
* */
const unsigned len = mb.mlen > 6u ? 6u : mb.mlen;
if (!len) { delay (4 * unit); return; }
for (unsigned n=0; n<len; n++) {
led << false;
delay (unit);
const unsigned v = (1u << n) & mb.bits;
const unsigned d = v ? 3u : 1u;
led << true;
delay (d * unit);
led << false;
}
delay (3 * unit);
}

24
hello/morse.h Normal file
View file

@ -0,0 +1,24 @@
#ifndef MORSE_H
#define MORSE_H
#include "gpio.h"
union morse_byte {
struct {
unsigned char bits : 5;
unsigned char mlen : 3;
};
unsigned char byte;
explicit constexpr morse_byte () noexcept : byte (0u) {}
};
class Morse {
const unsigned unit;
const GpioClass & led;
public:
explicit Morse (const GpioClass & pin, const unsigned ms = 100) noexcept;
const Morse & operator<< (const char * text) const;
protected:
void out (const morse_byte mb) const;
};
#endif // MORSE_H