diff --git a/examples/spi_dac/.gdbinit b/examples/spi_dac/.gdbinit
new file mode 100644
index 0000000000000000000000000000000000000000..427595ae0e4d2332e7e580facfd2c4327e8441c6
--- /dev/null
+++ b/examples/spi_dac/.gdbinit
@@ -0,0 +1,2 @@
+file tim1_pwm.elf
+target extended-remote localhost:3333
diff --git a/examples/spi_dac/Makefile b/examples/spi_dac/Makefile
new file mode 100644
index 0000000000000000000000000000000000000000..0978583b8bd06cec951a805c6aa6dc4ca5e58d32
--- /dev/null
+++ b/examples/spi_dac/Makefile
@@ -0,0 +1,48 @@
+TARGET:=spi_dac
+
+all : flash
+
+PREFIX:=riscv64-unknown-elf
+
+GPIO_Toggle:=EXAM/GPIO/GPIO_Toggle/User
+
+CH32V003FUN:=../../ch32v003fun
+MINICHLINK:=../../minichlink
+
+ifeq ($(OS),Windows_NT)
+# On Windows, all the major RISC-V GCC installs are missing the -ec libgcc.
+LIB_GCC=../../misc/libgcc.a
+else
+LIB_GCC=-lgcc
+endif
+
+CFLAGS:= \
+	-g -Os -flto -ffunction-sections \
+	-static-libgcc $(LIB_GCC) \
+	-march=rv32ec \
+	-mabi=ilp32e \
+	-I/usr/include/newlib \
+	-I$(CH32V003FUN) \
+	-nostdlib \
+	-I. -DSTDOUT_UART -Wall
+
+LDFLAGS:=-T $(CH32V003FUN)/ch32v003fun.ld -Wl,--gc-sections
+
+SYSTEM_C:=$(CH32V003FUN)/ch32v003fun.c
+
+$(TARGET).elf : $(SYSTEM_C) $(TARGET).c
+	$(PREFIX)-gcc -o $@ $^ $(CFLAGS) $(LDFLAGS)
+
+$(TARGET).bin : $(TARGET).elf
+	$(PREFIX)-size $^
+	$(PREFIX)-objdump -S $^ > $(TARGET).lst
+	$(PREFIX)-objdump -t $^ > $(TARGET).map
+	$(PREFIX)-objcopy -O binary $< $(TARGET).bin
+	$(PREFIX)-objcopy -O ihex $< $(TARGET).hex
+
+flash : $(TARGET).bin
+	$(MINICHLINK)/minichlink -w $< flash -b
+
+clean :
+	rm -rf $(TARGET).elf $(TARGET).bin $(TARGET).hex $(TARGET).lst $(TARGET).map $(TARGET).hex
+
diff --git a/examples/spi_dac/README.md b/examples/spi_dac/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..3930ef0992e20727293018e1bc3750fda4051826
--- /dev/null
+++ b/examples/spi_dac/README.md
@@ -0,0 +1,54 @@
+# SPI DAC Demo
+This example shows how to set up the SPI port with a timer, circular DMA and
+IRQs to do continuous audio output through an inexpensive I2S DAC.
+
+![Scope image of sine and sawtooth waves](oscope.png) 
+
+## Theory
+The CH32V003 does not have an I2S port which is usually required for driving
+audio DACs, but the inexpensive PT8211 stereo audio DAC is very forgiving of
+the signal format used to drive it so we can approximate an I2S signal using
+one of the CH32V003 on-chip timers to generate the frame sync signal. The SPI
+port then provides the bit clock and serial data.
+
+### Timer setup
+TIM1 on the CH32V003 is set up to generate a 48kHz square wave which is output
+on GPIO pin PC4 and serves as the frame sync or WS. The timer is configured to
+run in center-aligned mode 3 which generates DMA requests on both rising and
+falling edges. Channel 4 is configured as the output and the threshold is set
+to 50% and the overall period is set to 48kHz.
+
+### SPI setup
+SPI1 is configured for 16-bit TX with a bit clock of 48MHz/8 (3MHz) which is
+fast enough to clock out 16 bits of data between the edges of the frame sync
+signal. Transmit data arrives via DMA, but the SPI port does not control DMA -
+that is triggered from the timer above.
+
+### DMA setup
+DMA1 channel 4 is used because that channel is connected to TIM1 Chl 4 output
+and is set up in circular mode with both Half-transfer and Transfer-Complete
+interrupts. It continuously pulls data out of a 32-word buffer and sends it to
+the SPI port when the timer fires.
+
+### Interrupts
+The DMA TC and HT IRQs trigger execution of a buffer fill routine which simply
+indexes through a sinewave table at variable rates using fixed-point math to
+fill the buffer as requested. This process uses up only about 4% of the
+available CPU cycles so there's plenty leftover for foreground processing or
+more complex waveform calculations like interpolation or synthesis.
+
+## Use
+Connect a PT8211 DAC as follows:
+* DAC pin 1 (BCK) - MCU pin 15 (PC5/SCK)
+* DAC pin 2 (WS)  - MCU pin 14 (PC4/T1CH4)
+* DAC pin 3 (DIN) - MCU pin 16 {PC6/MOSI)
+* DAC pin 4 (GND) - ground
+* DAC pin 5 (VCC) - 3.3V or 5V supply
+* DAC pin 6 (LCH) - left channel output
+* DAC pin 8 (RCH) - right channel output
+
+![Schematic of SPI DAC hookup](spi_dac_schem.png)
+
+Connect an oscilloscope to the left and right channel outputs and observe a
+sine waveform at 187Hz on the right channel output and a sawtooth wave at
+47Hz on the left channel output.
diff --git a/examples/spi_dac/Sine16bit.h b/examples/spi_dac/Sine16bit.h
new file mode 100644
index 0000000000000000000000000000000000000000..5e7a55efc74d703d6f470e80063272d5f8f7d718
--- /dev/null
+++ b/examples/spi_dac/Sine16bit.h
@@ -0,0 +1,259 @@
+/* Sinewave LUT */
+const int16_t Sine16bit[256] = {
+	      0,
+	    804,
+	   1608,
+	   2410,
+	   3212,
+	   4011,
+	   4808,
+	   5602,
+	   6393,
+	   7179,
+	   7962,
+	   8739,
+	   9512,
+	  10278,
+	  11039,
+	  11793,
+	  12539,
+	  13279,
+	  14010,
+	  14732,
+	  15446,
+	  16151,
+	  16846,
+	  17530,
+	  18204,
+	  18868,
+	  19519,
+	  20159,
+	  20787,
+	  21403,
+	  22005,
+	  22594,
+	  23170,
+	  23731,
+	  24279,
+	  24811,
+	  25329,
+	  25832,
+	  26319,
+	  26790,
+	  27245,
+	  27683,
+	  28105,
+	  28510,
+	  28898,
+	  29268,
+	  29621,
+	  29956,
+	  30273,
+	  30571,
+	  30852,
+	  31113,
+	  31356,
+	  31580,
+	  31785,
+	  31971,
+	  32137,
+	  32285,
+	  32412,
+	  32521,
+	  32609,
+	  32678,
+	  32728,
+	  32757,
+	  32767,
+	  32757,
+	  32728,
+	  32678,
+	  32609,
+	  32521,
+	  32412,
+	  32285,
+	  32137,
+	  31971,
+	  31785,
+	  31580,
+	  31356,
+	  31113,
+	  30852,
+	  30571,
+	  30273,
+	  29956,
+	  29621,
+	  29268,
+	  28898,
+	  28510,
+	  28105,
+	  27683,
+	  27245,
+	  26790,
+	  26319,
+	  25832,
+	  25329,
+	  24811,
+	  24279,
+	  23731,
+	  23170,
+	  22594,
+	  22005,
+	  21403,
+	  20787,
+	  20159,
+	  19519,
+	  18868,
+	  18204,
+	  17530,
+	  16846,
+	  16151,
+	  15446,
+	  14732,
+	  14010,
+	  13279,
+	  12539,
+	  11793,
+	  11039,
+	  10278,
+	   9512,
+	   8739,
+	   7962,
+	   7179,
+	   6393,
+	   5602,
+	   4808,
+	   4011,
+	   3212,
+	   2410,
+	   1608,
+	    804,
+	      0,
+	   -804,
+	  -1608,
+	  -2410,
+	  -3212,
+	  -4011,
+	  -4808,
+	  -5602,
+	  -6393,
+	  -7179,
+	  -7962,
+	  -8739,
+	  -9512,
+	 -10278,
+	 -11039,
+	 -11793,
+	 -12539,
+	 -13279,
+	 -14010,
+	 -14732,
+	 -15446,
+	 -16151,
+	 -16846,
+	 -17530,
+	 -18204,
+	 -18868,
+	 -19519,
+	 -20159,
+	 -20787,
+	 -21403,
+	 -22005,
+	 -22594,
+	 -23170,
+	 -23731,
+	 -24279,
+	 -24811,
+	 -25329,
+	 -25832,
+	 -26319,
+	 -26790,
+	 -27245,
+	 -27683,
+	 -28105,
+	 -28510,
+	 -28898,
+	 -29268,
+	 -29621,
+	 -29956,
+	 -30273,
+	 -30571,
+	 -30852,
+	 -31113,
+	 -31356,
+	 -31580,
+	 -31785,
+	 -31971,
+	 -32137,
+	 -32285,
+	 -32412,
+	 -32521,
+	 -32609,
+	 -32678,
+	 -32728,
+	 -32757,
+	 -32767,
+	 -32757,
+	 -32728,
+	 -32678,
+	 -32609,
+	 -32521,
+	 -32412,
+	 -32285,
+	 -32137,
+	 -31971,
+	 -31785,
+	 -31580,
+	 -31356,
+	 -31113,
+	 -30852,
+	 -30571,
+	 -30273,
+	 -29956,
+	 -29621,
+	 -29268,
+	 -28898,
+	 -28510,
+	 -28105,
+	 -27683,
+	 -27245,
+	 -26790,
+	 -26319,
+	 -25832,
+	 -25329,
+	 -24811,
+	 -24279,
+	 -23731,
+	 -23170,
+	 -22594,
+	 -22005,
+	 -21403,
+	 -20787,
+	 -20159,
+	 -19519,
+	 -18868,
+	 -18204,
+	 -17530,
+	 -16846,
+	 -16151,
+	 -15446,
+	 -14732,
+	 -14010,
+	 -13279,
+	 -12539,
+	 -11793,
+	 -11039,
+	 -10278,
+	  -9512,
+	  -8739,
+	  -7962,
+	  -7179,
+	  -6393,
+	  -5602,
+	  -4808,
+	  -4011,
+	  -3212,
+	  -2410,
+	  -1608,
+	   -804
+};
diff --git a/examples/spi_dac/debug.sh b/examples/spi_dac/debug.sh
new file mode 100755
index 0000000000000000000000000000000000000000..bb05a9465959cb153fad95bba4b2175667830528
--- /dev/null
+++ b/examples/spi_dac/debug.sh
@@ -0,0 +1,5 @@
+#!/bin/bash
+# before running this you should start OOCD server
+#../../../MRS_Toolchain_Linux_x64_V1.70/OpenOCD/bin/openocd -f ../../../MRS_Toolchain_Linux_x64_V1.70/OpenOCD/bin/wch-riscv.cfg
+ 
+../../../MRS_Toolchain_Linux_x64_V1.70/RISC-V\ Embedded\ GCC/bin/riscv-none-embed-gdb
diff --git a/examples/spi_dac/oscope.png b/examples/spi_dac/oscope.png
new file mode 100644
index 0000000000000000000000000000000000000000..5f1bb342e937763e11fb6447903d830a9d6ec603
Binary files /dev/null and b/examples/spi_dac/oscope.png differ
diff --git a/examples/spi_dac/spi_dac.c b/examples/spi_dac/spi_dac.c
new file mode 100644
index 0000000000000000000000000000000000000000..cab61e6c82b4548f9d0ed090abf40f23b0e41a4a
--- /dev/null
+++ b/examples/spi_dac/spi_dac.c
@@ -0,0 +1,41 @@
+/*
+ * Example for SPI with circular DMA for audio output
+ * 04-10-2023 E. Brombaugh
+ */
+
+// Could be defined here, or in the processor defines.
+#define SYSTEM_CORE_CLOCK 48000000
+#define APB_CLOCK SYSTEM_CORE_CLOCK
+
+#include "ch32v003fun.h"
+#include <stdio.h>
+#include "spidac.h"
+
+int main()
+{
+	SystemInit48HSI();
+
+	// start serial @ default 115200bps
+	SetupUART( UART_BRR );
+	Delay_Ms( 100 );
+	printf("\r\r\n\nspi_dac example\n\r");
+
+	// GPIO C0 Push-Pull for foreground blink
+	RCC->APB2PCENR |= RCC_APB2Periph_GPIOC;
+	GPIOC->CFGLR &= ~(0xf<<(4*0));
+	GPIOC->CFGLR |= (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP)<<(4*0);
+	
+	// init SPI DAC
+	printf("initializing spi dac...");
+	spidac_init();
+	printf("done.\n\r");
+		
+	printf("looping...\n\r");
+	while(1)
+	{
+		GPIOC->BSHR = 1;
+		Delay_Ms( 250 );
+		GPIOC->BSHR = (1<<16);
+		Delay_Ms( 250 );
+	}
+}
diff --git a/examples/spi_dac/spi_dac_schem.png b/examples/spi_dac/spi_dac_schem.png
new file mode 100644
index 0000000000000000000000000000000000000000..ef399d3786a7d22fe61571fe6de4a04ced98796e
Binary files /dev/null and b/examples/spi_dac/spi_dac_schem.png differ
diff --git a/examples/spi_dac/spidac.h b/examples/spi_dac/spidac.h
new file mode 100644
index 0000000000000000000000000000000000000000..e8242b9321abaada92d2d6c7bcd513cc15de2c26
--- /dev/null
+++ b/examples/spi_dac/spidac.h
@@ -0,0 +1,203 @@
+/*
+ * Single-File-Header for SPI with circular DMA for audio output
+ * 04-10-2023 E. Brombaugh
+ */
+
+#ifndef _SPIDAC_H
+#define _SPIDAC_H
+
+#include <stdint.h>
+#include "Sine16bit.h"
+
+// uncomment this to enable GPIO diag
+#define DAC_DIAG
+
+// uncomment this to fill the buffer with static test data
+//#define DAC_STATIC
+
+// uncomment this for timer-generated DMA
+#define DAC_TIMDMA
+
+#define DACBUFSZ 32
+
+uint16_t dac_buffer[DACBUFSZ];
+uint32_t osc_phs[2], osc_frq[2];
+
+/*
+ * initialize SPI and DMA
+ */
+void spidac_init( void )
+{
+#ifdef DAC_STATIC
+	// fill output buffer with diag data
+	uint16_t data = 0xffff;
+	for(int i=0;i<DACBUFSZ;i++)
+	{
+		/* just a full-scale ramp for now */
+		dac_buffer[i] = data;
+		data >>= 1;
+	}
+#else
+	// init two oscillators
+	osc_phs[0] = 0;
+	osc_phs[1] = 0;
+	osc_frq[0] = 0x01000000;
+	osc_frq[1] = 0x00400000;
+#endif
+	
+	// Enable DMA + Peripherals
+	RCC->AHBPCENR |= RCC_AHBPeriph_DMA1;
+	RCC->APB2PCENR |= RCC_APB2Periph_GPIOC | RCC_APB2Periph_SPI1;
+
+#ifdef DAC_DIAG
+	// GPIO D0 Push-Pull for diags
+	RCC->APB2PCENR |= RCC_APB2Periph_GPIOD;
+	GPIOD->CFGLR &= ~(0xf<<(4*0));
+	GPIOD->CFGLR |= (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP)<<(4*0);
+#endif
+	
+	// MOSI on PC6
+	GPIOC->CFGLR &= ~(0xf<<(4*6));
+	GPIOC->CFGLR |= (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP_AF)<<(4*6);
+	// SCK on PC5
+	GPIOC->CFGLR &= ~(0xf<<(4*5));
+	GPIOC->CFGLR |= (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP_AF)<<(4*5);
+	// NSS on PC1 is GPIO
+	GPIOC->CFGLR &= ~(0xf<<(4*1));
+	GPIOC->CFGLR |= (GPIO_Speed_10MHz | GPIO_CNF_OUT_PP)<<(4*1);
+
+	// Configure SPI 
+	SPI1->CTLR1 = 
+		SPI_NSS_Soft | SPI_CPHA_1Edge | SPI_CPOL_Low | SPI_DataSize_16b |
+		SPI_Mode_Master | SPI_Direction_1Line_Tx |
+		SPI_BaudRatePrescaler_16;
+
+	// enable SPI port
+	SPI1->CTLR1 |= CTLR1_SPE_Set;
+
+	// TIM1 generates DMA Req and external signal
+	// Enable TIM1
+	RCC->APB2PCENR |= RCC_APB2Periph_TIM1;
+	
+	// PC4 is T1CH4, 50MHz Output PP CNF = 10: Mux PP, MODE = 11: Out 50MHz
+	GPIOC->CFGLR &= ~(GPIO_CFGLR_MODE4 | GPIO_CFGLR_CNF4);
+	GPIOC->CFGLR |= GPIO_CFGLR_CNF4_1 | GPIO_CFGLR_MODE4_0 | GPIO_CFGLR_MODE4_1;
+		
+	// Reset TIM1 to init all regs
+	RCC->APB2PRSTR |= RCC_APB2Periph_TIM1;
+	RCC->APB2PRSTR &= ~RCC_APB2Periph_TIM1;
+	
+	// CTLR1: default is up, events generated, edge align
+	// CTLR1: up/down, events on both edges
+	TIM1->CTLR1 = TIM_CMS;
+	// SMCFGR: default clk input is CK_INT
+	
+	// Prescaler 
+	TIM1->PSC = 0x0000;
+	
+	// Auto Reload - sets period to ~47kHz
+	TIM1->ATRLR = 499;
+	
+	// Reload immediately
+	TIM1->SWEVGR |= TIM_UG;
+	
+	// Enable CH4 output, positive pol
+	TIM1->CCER |= TIM_CC4E;// | TIM_CC4P;
+	
+	// CH2 Mode is output, PWM1 (CC1S = 00, OC1M = 110)
+	TIM1->CHCTLR2 |= TIM_OC4M_2 | TIM_OC4M_1;
+	
+	// Set the Capture Compare Register value to 50% initially
+	TIM1->CH4CVR = 256;
+	
+	// Enable TIM1 outputs
+	TIM1->BDTR |= TIM_MOE;
+	
+	// Enable CH4 DMA Req
+	TIM1->DMAINTENR |= TIM_CC4DE;
+	
+	// Enable TIM1
+	TIM1->CTLR1 |= TIM_CEN;
+
+	//DMA1_Channel4 is for TIM1CH4 
+	DMA1_Channel4->PADDR = (uint32_t)&SPI1->DATAR;
+	DMA1_Channel4->MADDR = (uint32_t)dac_buffer;
+	DMA1_Channel4->CNTR  = DACBUFSZ;
+	DMA1_Channel4->CFGR  =
+		DMA_M2M_Disable |		 
+		DMA_Priority_VeryHigh |
+		DMA_MemoryDataSize_HalfWord |
+		DMA_PeripheralDataSize_HalfWord |
+		DMA_MemoryInc_Enable |
+		DMA_Mode_Circular |
+		DMA_DIR_PeripheralDST |
+		DMA_IT_TC | DMA_IT_HT;
+
+	NVIC_EnableIRQ( DMA1_Channel4_IRQn );
+	DMA1_Channel4->CFGR |= DMA_CFGR1_EN;
+}
+
+/*
+ * DAC buffer updates - called at IRQ time
+ */
+void dac_update(uint16_t *buffer)
+{
+	int i;
+	
+	// fill the buffer with stereo data
+	for(i=0;i<DACBUFSZ/2;i+=2)
+	{
+		// right chl
+		*buffer++ = Sine16bit[osc_phs[0]>>24];
+		osc_phs[0] += osc_frq[0];
+		
+		// left chl
+		//*buffer++ = Sine16bit[osc_phs[1]>>24];
+		*buffer++ = osc_phs[1]>>16;
+		osc_phs[1] += osc_frq[1];
+	}
+}
+
+/*
+ * TIM1CH4 DMA IRQ Handler
+ */
+void DMA1_Channel4_IRQHandler( void ) __attribute__((interrupt));
+void DMA1_Channel4_IRQHandler( void ) 
+{
+#ifdef DAC_DIAG
+	GPIOD->BSHR = 1;
+#endif
+	
+	// why is this needed? Can't just direct compare the reg in tests below
+	volatile uint16_t intfr = DMA1->INTFR;
+
+	if( intfr & DMA1_IT_TC4 )
+	{
+		// Transfer complete - update 2nd half
+		dac_update(dac_buffer+DACBUFSZ/2);
+		
+		// clear TC IRQ
+		DMA1->INTFCR = DMA1_IT_TC4;
+		
+		GPIOC->BSHR = (1<<1); // NSS 1
+	}
+	
+	if( intfr & DMA1_IT_HT4 )
+	{
+		// Half transfer - update first half
+		dac_update(dac_buffer);
+		
+		// clear HT IRQ
+		DMA1->INTFCR = DMA1_IT_HT4;
+		
+		GPIOC->BSHR = (1<<(1+16)); // NSS 0
+	}
+
+	// clear the Global IRQ
+	DMA1->INTFCR = DMA1_IT_GL4;
+	
+#ifdef DAC_DIAG
+	GPIOD->BSHR = 1<<16;
+#endif
+}
+#endif