├── icestorm ├── up5k_riscv.sdc ├── up5k_riscv.pcf ├── Makefile └── up5k_riscv.v ├── c ├── font_8x8.h ├── clkcnt.h ├── acia.h ├── i2c.h ├── clkcnt.c ├── flash.h ├── spi.h ├── acia.c ├── Makefile ├── lnk-app.lds ├── ili9341.h ├── spi.c ├── up5k_riscv.h ├── start.S ├── i2c.c ├── main.c ├── flash.c ├── printf.h ├── printf.c └── ili9341.c ├── .gitmodules ├── tools └── png2rgb565.sh ├── src ├── bram_512x32.v ├── spram_16kx32.v ├── acia_tx.v ├── wb_master.v ├── acia_rx.v ├── acia.v ├── system.v ├── save │ └── wb_bus.v └── wb_bus.v ├── icarus ├── Makefile ├── tb_system.v └── tb_system.gtkw ├── LICENSE └── README.md /icestorm/up5k_riscv.sdc: -------------------------------------------------------------------------------- 1 | ctx.addClock("clk", 24) 2 | -------------------------------------------------------------------------------- /c/font_8x8.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/emeb/up5k_riscv/HEAD/c/font_8x8.h -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "picorv32"] 2 | path = picorv32 3 | url = https://github.com/cliffordwolf/picorv32 4 | -------------------------------------------------------------------------------- /tools/png2rgb565.sh: -------------------------------------------------------------------------------- 1 | #!/bin/sh 2 | # convert a PNG file to a raw 565 w/ endian swap 3 | ffmpeg -vcodec png -i $1 -vcodec rawvideo -f rawvideo -pix_fmt rgb565 temp.565 4 | dd conv=swab $1.565 5 | rm temp.565 6 | -------------------------------------------------------------------------------- /c/clkcnt.h: -------------------------------------------------------------------------------- 1 | /* 2 | * clkcnt.h - clock cycle counter driver 3 | * 07-03-19 E. Brombaugh 4 | */ 5 | 6 | #ifndef __clkcnt__ 7 | #define __clkcnt__ 8 | 9 | #include "up5k_riscv.h" 10 | 11 | void clkcnt_wait(uint32_t clks); 12 | void clkcnt_delayms(uint32_t ms); 13 | 14 | #endif 15 | 16 | -------------------------------------------------------------------------------- /c/acia.h: -------------------------------------------------------------------------------- 1 | /* 2 | * acia.h - serial port driver 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | #ifndef __acia__ 7 | #define __acia__ 8 | 9 | #include "up5k_riscv.h" 10 | 11 | void acia_putc(char c); 12 | void acia_printf_putc(void* p, char c); 13 | void acia_puts(char *str); 14 | int acia_getc(void); 15 | 16 | #endif 17 | 18 | -------------------------------------------------------------------------------- /c/i2c.h: -------------------------------------------------------------------------------- 1 | /* 2 | * i2c.h - I2C IP core driver 3 | * 06-23-20 E. Brombaugh 4 | */ 5 | 6 | #ifndef __i2c__ 7 | #define __i2c__ 8 | 9 | #include "up5k_riscv.h" 10 | 11 | /* i2c functions */ 12 | void i2c_init(I2C_TypeDef *s); 13 | int8_t i2c_tx(I2C_TypeDef *s, uint8_t addr, uint8_t *data, uint8_t sz); 14 | 15 | #endif 16 | 17 | -------------------------------------------------------------------------------- /c/clkcnt.c: -------------------------------------------------------------------------------- 1 | /* 2 | * clkcnt.h - clock cycle counter driver 3 | * 07-03-19 E. Brombaugh 4 | */ 5 | 6 | #include "clkcnt.h" 7 | 8 | /* 9 | * delay for clocks 10 | */ 11 | void clkcnt_wait(uint32_t clks) 12 | { 13 | clkcnt_reg = 0; 14 | 15 | while(clkcnt_reg < clks); 16 | } 17 | 18 | /* 19 | * delay for exactly 1 millisecond 20 | */ 21 | void clkcnt_1ms(void) 22 | { 23 | clkcnt_wait(24000); 24 | } 25 | 26 | /* 27 | * delay for number of milliseconds 28 | */ 29 | void clkcnt_delayms(uint32_t ms) 30 | { 31 | while(ms--) 32 | clkcnt_1ms(); 33 | } 34 | -------------------------------------------------------------------------------- /icestorm/up5k_riscv.pcf: -------------------------------------------------------------------------------- 1 | # for rev 0.1 of up5k_usb board use clk_16 = 44 2 | # for rev 0.2 of up5k_usb board use clk_16 = 35 3 | set_io clk_16 35 4 | 5 | set_io RX 26 6 | set_io TX 25 7 | 8 | set_io spi0_mosi 14 9 | set_io spi0_miso 17 10 | set_io spi0_sclk 15 11 | set_io spi0_cs0 16 12 | 13 | set_io spi1_mosi 42 14 | set_io spi1_miso 44 15 | set_io spi1_sclk 37 16 | set_io spi1_cs0 38 17 | 18 | set_io i2c0_sda 21 19 | set_io i2c0_scl 19 20 | 21 | set_io lcd_nrst 34 22 | set_io lcd_dc 36 23 | 24 | set_io d1 27 25 | set_io d2 28 26 | 27 | set_io RGB0 39 28 | set_io RGB1 40 29 | set_io RGB2 41 30 | 31 | -------------------------------------------------------------------------------- /c/flash.h: -------------------------------------------------------------------------------- 1 | /* 2 | * flash.h - flash memory driver 3 | * 07-03-19 E. Brombaugh 4 | */ 5 | 6 | #ifndef __flash__ 7 | #define __flash__ 8 | 9 | #include "up5k_riscv.h" 10 | 11 | void flash_init(SPI_TypeDef *s); 12 | void flash_read(SPI_TypeDef *s, uint8_t *dst, uint32_t addr, uint32_t len); 13 | uint8_t flash_rdreg(SPI_TypeDef *s, uint8_t cmd); 14 | uint8_t flash_status(SPI_TypeDef *s); 15 | void flash_busy_wait(SPI_TypeDef *s); 16 | void flash_eraseblk(SPI_TypeDef *s, uint32_t addr); 17 | void flash_write(SPI_TypeDef *s, uint8_t *src, uint32_t addr, uint32_t len); 18 | uint32_t flash_id(SPI_TypeDef *s); 19 | 20 | #endif 21 | 22 | -------------------------------------------------------------------------------- /c/spi.h: -------------------------------------------------------------------------------- 1 | /* 2 | * spi.h - SPI IP core driver 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | #ifndef __spi__ 7 | #define __spi__ 8 | 9 | #include "up5k_riscv.h" 10 | 11 | /* some common operation macros */ 12 | #define spi_tx_wait(s) while(!(((s)->SPISR)&0x10)) 13 | #define spi_rx_wait(s) while(!(((s)->SPISR)&0x08)) 14 | #define spi_cs_low(s) ((s)->SPICSR=0xfe) 15 | #define spi_cs_high(s) ((s)->SPICSR=0xff) 16 | 17 | /* spi functions */ 18 | void spi_init(SPI_TypeDef *s); 19 | void spi_tx_byte(SPI_TypeDef *s, uint8_t data); 20 | uint8_t spi_txrx_byte(SPI_TypeDef *s, uint8_t data); 21 | void spi_transmit(SPI_TypeDef *s, uint8_t *src, uint16_t sz); 22 | void spi_receive(SPI_TypeDef *s, uint8_t *dst, uint16_t sz); 23 | 24 | #endif 25 | 26 | -------------------------------------------------------------------------------- /c/acia.c: -------------------------------------------------------------------------------- 1 | /* 2 | * acia.c - serial port driver 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | #include 7 | #include "acia.h" 8 | 9 | /* 10 | * serial transmit character 11 | */ 12 | void acia_putc(char c) 13 | { 14 | /* wait for tx ready */ 15 | while(!(acia_ctlstat & 2)); 16 | 17 | /* send char */ 18 | acia_data = c; 19 | } 20 | 21 | /* 22 | * output for tiny printf 23 | */ 24 | void acia_printf_putc(void* p, char c) 25 | { 26 | acia_putc(c); 27 | } 28 | 29 | /* 30 | * serial transmit string 31 | */ 32 | void acia_puts(char *str) 33 | { 34 | uint8_t c; 35 | 36 | while((c=*str++)) 37 | acia_putc(c); 38 | } 39 | 40 | /* 41 | * serial receive char 42 | */ 43 | int acia_getc(void) 44 | { 45 | if(!(acia_ctlstat & 1)) 46 | return EOF; 47 | else 48 | return acia_data; 49 | } 50 | -------------------------------------------------------------------------------- /src/bram_512x32.v: -------------------------------------------------------------------------------- 1 | /* 2 | * bram_512x32.v - byte-addressable RAM in block ram 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | `default_nettype none 7 | 8 | module bram_512x32( 9 | input clk, 10 | input sel, 11 | input [3:0] we, 12 | input [10:0] addr, 13 | input [31:0] wdat, 14 | output reg [31:0] rdat 15 | ); 16 | // memory 17 | reg [31:0] ram[511:0]; 18 | 19 | // write logic 20 | always @(posedge clk) 21 | if(sel) 22 | begin 23 | if(we[0]) 24 | ram[addr[10:2]][7:0] <= wdat[7:0]; 25 | if(we[1]) 26 | ram[addr[10:2]][15:8] <= wdat[15:8]; 27 | if(we[2]) 28 | ram[addr[10:2]][23:16] <= wdat[23:16]; 29 | if(we[3]) 30 | ram[addr[10:2]][31:24] <= wdat[31:24]; 31 | end 32 | 33 | // read logic 34 | always @(posedge clk) 35 | rdat <= ram[addr[10:2]]; 36 | 37 | endmodule 38 | -------------------------------------------------------------------------------- /src/spram_16kx32.v: -------------------------------------------------------------------------------- 1 | /* 2 | * spram_16kx32.v - byte-addressable RAM in SPRAM 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | `default_nettype none 7 | 8 | module spram_16kx32( 9 | input clk, 10 | input sel, 11 | input [3:0] we, 12 | input [15:0] addr, 13 | input [31:0] wdat, 14 | output [31:0] rdat 15 | ); 16 | // instantiate the big RAMs 17 | SB_SPRAM256KA mem_lo ( 18 | .ADDRESS(addr[15:2]), 19 | .DATAIN(wdat[15:0]), 20 | .MASKWREN({we[1],we[1],we[0],we[0]}), 21 | .WREN(|we), 22 | .CHIPSELECT(sel), 23 | .CLOCK(clk), 24 | .STANDBY(1'b0), 25 | .SLEEP(1'b0), 26 | .POWEROFF(1'b1), 27 | .DATAOUT(rdat[15:0]) 28 | ); 29 | SB_SPRAM256KA mem_hi ( 30 | .ADDRESS(addr[15:2]), 31 | .DATAIN(wdat[31:16]), 32 | .MASKWREN({we[3],we[3],we[2],we[2]}), 33 | .WREN(|we), 34 | .CHIPSELECT(sel), 35 | .CLOCK(clk), 36 | .STANDBY(1'b0), 37 | .SLEEP(1'b0), 38 | .POWEROFF(1'b1), 39 | .DATAOUT(rdat[31:16]) 40 | ); 41 | endmodule 42 | -------------------------------------------------------------------------------- /icarus/Makefile: -------------------------------------------------------------------------------- 1 | # Makefile for Icarus Verilog simulation 2 | # 02-11-2019 E. Brombaugh 3 | 4 | # sources 5 | SOURCES = tb_system.v ../src/system.v ../src/spram_16kx32.v \ 6 | ../src/acia.v ../src/acia_rx.v ../src/acia_tx.v \ 7 | ../src/wb_bus.v ../src/wb_master.v \ 8 | ../picorv32/picorv32.v 9 | 10 | # preparing the machine code 11 | HEX = rom.hex 12 | 13 | # top level 14 | TOP = tb_system 15 | 16 | # Executables 17 | VLOG = iverilog 18 | WAVE = gtkwave 19 | TECH_LIB = /usr/local/share/yosys/ice40/cells_sim.v 20 | 21 | # targets 22 | all: $(TOP).vcd 23 | 24 | $(HEX): 25 | $(MAKE) -C ../c/ main.hex 26 | cp ../c/main.hex ./$(HEX) 27 | 28 | wave: $(TOP).vcd $(TOP).gtkw 29 | $(WAVE) $(TOP).gtkw 30 | 31 | $(TOP).vcd: $(TOP) 32 | ./$(TOP) 33 | 34 | $(TOP): $(SOURCES) $(HEX) 35 | $(VLOG) -D icarus -l $(TECH_LIB) -o $(TOP) $(SOURCES) 36 | 37 | clean: 38 | $(MAKE) -C ../c/ clean 39 | rm -rf a.out *.obj $(HEX) $(RPT) $(TOP) $(TOP).vcd 40 | 41 | -------------------------------------------------------------------------------- /c/Makefile: -------------------------------------------------------------------------------- 1 | CROSS = /opt/riscv-none-gcc/8.1.0-2-20181019-0952/bin/riscv-none-embed- 2 | CC = $(CROSS)gcc 3 | OBJCOPY = $(CROSS)objcopy 4 | OBJDUMP = $(CROSS)objdump 5 | ICEPROG = iceprog 6 | HEXDUMP = hexdump 7 | HEXDUMP_ARGS = -v -e '1/4 "%08x" "\n"' 8 | 9 | #CFLAGS=-Wall -Os -march=rv32i -mabi=ilp32 -ffreestanding -nostartfiles -flto 10 | CFLAGS=-Wall -Os -march=rv32i -mabi=ilp32 -ffreestanding -flto -nostartfiles -fomit-frame-pointer 11 | 12 | HEADER = up5k_riscv.h acia.h spi.h flash.h clkcnt.h ili9341.h i2c.h printf.h 13 | 14 | SOURCES = start.S main.c acia.c spi.c flash.c clkcnt.c ili9341.c i2c.c printf.c 15 | 16 | main.elf: lnk-app.lds $(HEADERS) $(SOURCES) 17 | $(CC) $(CFLAGS) -Wl,-Bstatic,-T,lnk-app.lds,--strip-debug -o $@ $(SOURCES) 18 | 19 | disassemble: main.elf 20 | $(OBJDUMP) -d main.elf > main.dis 21 | 22 | %.bin: %.elf 23 | $(OBJCOPY) -O binary $< $@ 24 | 25 | %.hex: %.bin 26 | $(HEXDUMP) $(HEXDUMP_ARGS) $< >$@ 27 | 28 | clean: 29 | rm -f *.bin *.hex *.elf *.dis 30 | -------------------------------------------------------------------------------- /c/lnk-app.lds: -------------------------------------------------------------------------------- 1 | MEMORY 2 | { 3 | ROM (rx) : ORIGIN = 0x00000000, LENGTH = 0x2000 4 | RAM (xrw) : ORIGIN = 0x10000000, LENGTH = 0x10000 5 | } 6 | SECTIONS { 7 | .text : 8 | { 9 | . = ALIGN(4); 10 | *(.text) 11 | *(.text*) 12 | *(.rodata) 13 | *(.rodata*) 14 | *(.srodata) 15 | *(.srodata*) 16 | . = ALIGN(4); 17 | _etext = .; 18 | _sidata = _etext; 19 | } >ROM 20 | .data : AT ( _sidata ) 21 | { 22 | . = ALIGN(4); 23 | _sdata = .; 24 | _ram_start = .; 25 | . = ALIGN(4); 26 | *(.data) 27 | *(.data*) 28 | *(.sdata) 29 | *(.sdata*) 30 | . = ALIGN(4); 31 | _edata = .; 32 | } >RAM 33 | .bss : 34 | { 35 | . = ALIGN(4); 36 | _sbss = .; 37 | *(.bss) 38 | *(.bss*) 39 | *(.sbss) 40 | *(.sbss*) 41 | *(COMMON) 42 | . = ALIGN(4); 43 | _ebss = .; 44 | } >RAM 45 | .heap : 46 | { 47 | . = ALIGN(4); 48 | _heap_start = .; 49 | } >RAM 50 | } 51 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2019 Eric Brombaugh 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /icarus/tb_system.v: -------------------------------------------------------------------------------- 1 | // tb_system.v - testbench for riscv system 2 | // 06-30-19 E. Brombaugh 3 | 4 | `timescale 1ns/1ps 5 | `default_nettype none 6 | 7 | module tb_system; 8 | reg clk24; 9 | reg reset; 10 | reg RX; 11 | wire TX; 12 | wire spi0_mosi, spi0_miso, spi0_sclk, spi0_cs0; 13 | wire [31:0] gp_out; 14 | 15 | // 24MHz clock source 16 | always 17 | #21 clk24 = ~clk24; 18 | 19 | // reset 20 | initial 21 | begin 22 | `ifdef icarus 23 | $dumpfile("tb_system.vcd"); 24 | $dumpvars; 25 | `endif 26 | 27 | // init regs 28 | clk24 = 1'b0; 29 | reset = 1'b1; 30 | RX = 1'b1; 31 | 32 | // release reset 33 | #100 34 | reset = 1'b0; 35 | 36 | `ifdef icarus 37 | // stop after 1 sec 38 | #2000000 $finish; 39 | `endif 40 | end 41 | 42 | // Unit under test 43 | system uut( 44 | .clk24(clk24), // 24MHz system clock 45 | .reset(reset), // high-true reset 46 | 47 | .RX(RX), // serial input 48 | .TX(TX), // serial output 49 | 50 | .spi0_mosi(spi0_mosi), // SPI port 51 | .spi0_miso(spi0_miso), 52 | .spi0_sclk(spi0_sclk), 53 | .spi0_cs0(spi0_cs0), 54 | 55 | .gp_out(gp_out) // general purpose output 56 | ); 57 | endmodule 58 | -------------------------------------------------------------------------------- /src/acia_tx.v: -------------------------------------------------------------------------------- 1 | // acia_tx.v - serial transmit submodule 2 | // 06-02-19 E. Brombaugh 3 | 4 | module acia_tx( 5 | input clk, // system clock 6 | input rst, // system reset 7 | input [7:0] tx_dat, // transmit data byte 8 | input tx_start, // trigger transmission 9 | output tx_serial, // tx serial output 10 | output reg tx_busy // tx is active (not ready) 11 | ); 12 | // sym rate counter for 115200bps @ 16MHz clk 13 | parameter SCW = 8; // rate counter width 14 | parameter sym_cnt = 139; // rate count value 15 | 16 | // transmit machine 17 | reg [8:0] tx_sr; 18 | reg [3:0] tx_bcnt; 19 | reg [SCW-1:0] tx_rcnt; 20 | always @(posedge clk) 21 | begin 22 | if(rst) 23 | begin 24 | tx_sr <= 9'h1ff; 25 | tx_bcnt <= 4'h0; 26 | tx_rcnt <= {SCW{1'b0}}; 27 | tx_busy <= 1'b0; 28 | end 29 | else 30 | begin 31 | if(!tx_busy) 32 | begin 33 | if(tx_start) 34 | begin 35 | // start transmission 36 | tx_busy <= 1'b1; 37 | tx_sr <= {tx_dat,1'b0}; 38 | tx_bcnt <= 4'd9; 39 | tx_rcnt <= sym_cnt; 40 | end 41 | end 42 | else 43 | begin 44 | if(~|tx_rcnt) 45 | begin 46 | // shift out next bit and restart 47 | tx_sr <= {1'b1,tx_sr[8:1]}; 48 | tx_bcnt <= tx_bcnt - 1; 49 | tx_rcnt <= sym_cnt; 50 | 51 | if(~|tx_bcnt) 52 | begin 53 | // done - return to inactive state 54 | tx_busy <= 1'b0; 55 | end 56 | end 57 | else 58 | tx_rcnt <= tx_rcnt - 1; 59 | end 60 | end 61 | end 62 | 63 | // hook up output 64 | assign tx_serial = tx_sr; 65 | endmodule 66 | -------------------------------------------------------------------------------- /c/ili9341.h: -------------------------------------------------------------------------------- 1 | /* 2 | * ili9341.h - ILI9341 LCD driver 3 | * 07-03-19 E. Brombaugh 4 | * portions based on Adafruit ILI9341 driver for Arduino 5 | */ 6 | 7 | #ifndef __ili9341__ 8 | #define __ili9341__ 9 | 10 | #include "up5k_riscv.h" 11 | 12 | // Color definitions 13 | #define ILI9341_BLACK 0x0000 14 | #define ILI9341_BLUE 0x001F 15 | #define ILI9341_RED 0xF800 16 | #define ILI9341_GREEN 0x07E0 17 | #define ILI9341_CYAN 0x07FF 18 | #define ILI9341_MAGENTA 0xF81F 19 | #define ILI9341_YELLOW 0xFFE0 20 | #define ILI9341_WHITE 0xFFFF 21 | 22 | #define ILI9341_TFTWIDTH 240 23 | #define ILI9341_TFTHEIGHT 320 24 | 25 | void ili9341_init(SPI_TypeDef *s); 26 | void ili9341_drawPixel(int16_t x, int16_t y, uint16_t color); 27 | void ili9341_drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color); 28 | void ili9341_drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color); 29 | void ili9341_hsv2rgb(uint8_t rgb[], uint8_t hsv[]); 30 | uint16_t ili9342_Color565(uint8_t r, uint8_t g, uint8_t b); 31 | void ili9341_emptyRect(int16_t x, int16_t y, int16_t w, int16_t h, 32 | uint16_t color); 33 | void ili9341_fillRect(int16_t x, int16_t y, int16_t w, int16_t h, 34 | uint16_t color); 35 | void ili9341_fillScreen(uint16_t color); 36 | void ili9341_drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, 37 | uint16_t color); 38 | void ili9341_drawchar(int16_t x, int16_t y, uint8_t chr, 39 | uint16_t fg, uint16_t bg); 40 | void ili9341_drawstr(int16_t x, int16_t y, char *str, 41 | uint16_t fg, uint16_t bg); 42 | void ili9341_blit(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t *src); 43 | #endif 44 | 45 | -------------------------------------------------------------------------------- /icestorm/Makefile: -------------------------------------------------------------------------------- 1 | # Makefile for icestorm tools + yosys + nextpnr 2 | # Modified from examples in icestorm distribution 3 | # 01-16-18 E. Brombaugh 4 | 5 | # src directory 6 | VPATH = ../src:../picorv32 7 | 8 | SRC = up5k_riscv.v ../src/system.v ../src/spram_16kx32.v \ 9 | ../src/acia.v ../src/acia_rx.v ../src/acia_tx.v \ 10 | ../src/wb_bus.v ../src/wb_master.v \ 11 | ../picorv32/picorv32.v 12 | 13 | # preparing the machine code 14 | FAKE_HEX = rom.hex 15 | REAL_HEX = code.hex 16 | 17 | # project stuff 18 | PROJ = up5k_riscv 19 | PIN_DEF = up5k_riscv.pcf 20 | SDC = up5k_riscv.sdc 21 | DEVICE = up5k 22 | 23 | YOSYS = /usr/local/bin/yosys 24 | NEXTPNR = nextpnr-ice40 25 | NEXTPNR_ARGS = --pre-pack $(SDC) --placer heap --timing-allow-fail 26 | ICEPACK = icepack 27 | ICETIME = icetime 28 | ICEPROG = iceprog 29 | ICEBRAM = icebram 30 | CDCPROG = cdc_prog 31 | VERILATOR = verilator 32 | TECH_LIB = /usr/local/share/yosys/ice40/cells_sim.v 33 | 34 | all: $(PROJ).bin 35 | 36 | $(FAKE_HEX): 37 | $(ICEBRAM) -g 32 2048 > $(FAKE_HEX) 38 | 39 | %.json: $(SRC) $(FAKE_HEX) 40 | $(YOSYS) -p 'synth_ice40 -dsp -top $(PROJ) -json $@' $(SRC) 41 | 42 | %.asc: %.json $(PIN_DEF) 43 | $(NEXTPNR) $(NEXTPNR_ARGS) --$(DEVICE) --json $< --pcf $(PIN_DEF) --asc $@ 44 | 45 | $(REAL_HEX): 46 | $(MAKE) -C ../c/ main.hex 47 | cp ../c/main.hex ./$(REAL_HEX) 48 | 49 | %.bin: %.asc $(REAL_HEX) 50 | $(ICEBRAM) $(FAKE_HEX) $(REAL_HEX) < $< > temp.asc 51 | $(ICEPACK) temp.asc $@ 52 | 53 | %.rpt: %.asc 54 | $(ICETIME) -d $(DEVICE) -mtr $@ $< 55 | 56 | prog: $(PROJ).bin 57 | $(CDCPROG) -p /dev/ttyACM0 $< 58 | 59 | recode: 60 | rm -f $(REAL_HEX) $(PROJ).bin 61 | $(MAKE) prog 62 | 63 | flash: $(PROJ).bin 64 | $(CDCPROG) -w -p /dev/ttyACM0 $< 65 | 66 | lint: $(SRC) 67 | $(VERILATOR) --lint-only -Wall --top-module $(PROJ) $(TECH_LIB) $(SRC) 68 | 69 | clean: 70 | $(MAKE) -C ../c/ clean 71 | rm -f *.json *.asc *.rpt *.bin *.hex 72 | 73 | .SECONDARY: 74 | .PHONY: all prog clean 75 | -------------------------------------------------------------------------------- /src/wb_master.v: -------------------------------------------------------------------------------- 1 | // wb_master.v - wishbone master 2 | // 07-01-19 E. Brombaugh 3 | 4 | `default_nettype none 5 | 6 | module wb_master( 7 | input clk, // system clock 8 | input rst, // system reset 9 | input cs, // chip select 10 | input we, // write enable 11 | input [7:0] addr, // register select 12 | input [7:0] din, // data bus input 13 | output reg [7:0] dout, // data bus output 14 | output reg rdy, // low-true processor stall 15 | 16 | output reg wb_stbo, // wishbone STB 17 | output reg [7:0] wb_adro, // wishbone Address 18 | output reg wb_rwo, // wishbone read/write 19 | output reg [7:0] wb_dato, // wishbone data out 20 | input wb_acki, // wishbone ACK 21 | input [7:0] wb_dati // wishbone data in 22 | ); 23 | 24 | // start bus transactions 25 | reg [3:0] timeout; // 16-clock timeout counter 26 | reg busy; // busy state 27 | always @(posedge clk) 28 | if(rst == 1'b1) 29 | begin 30 | // clear all at reset 31 | dout <= 8'h55; 32 | busy <= 1'b0; 33 | rdy <= 1'b0; 34 | timeout <= 4'h0; 35 | wb_stbo <= 1'b0; 36 | wb_adro <= 8'h00; 37 | wb_rwo <= 1'b1; 38 | wb_dato <= 8'h00; 39 | end 40 | else 41 | begin 42 | if(busy == 1'b0) 43 | begin 44 | // always disable rdy bit 45 | rdy <= 1'b0; 46 | 47 | // No transaction pending - start new one 48 | if((rdy == 1'b0) && (cs == 1'b1)) 49 | begin 50 | wb_stbo <= 1'b1; 51 | wb_adro <= addr; 52 | wb_rwo <= we; 53 | busy <= 1'b1; 54 | timeout <= 4'hf; 55 | 56 | if(we == 1'b1) 57 | begin 58 | // write cycle 59 | wb_dato <= din; 60 | end 61 | end 62 | end 63 | else 64 | begin 65 | // Transaction in process 66 | if((wb_acki == 1'b1) || (|timeout == 1'b0)) 67 | begin 68 | // finish cycle 69 | wb_stbo <= 1'b0; 70 | busy <= 1'b0; 71 | rdy <= 1'b1; 72 | if((wb_rwo == 1'b0) && (|timeout == 1'b1)) 73 | begin 74 | // finish read cycle 75 | dout <= wb_dati; 76 | end 77 | end 78 | 79 | // update timeout counter 80 | timeout <= timeout - 4'h1; 81 | end 82 | end 83 | endmodule 84 | -------------------------------------------------------------------------------- /c/spi.c: -------------------------------------------------------------------------------- 1 | /* 2 | * spi.c - spi port driver 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | #include 7 | #include "spi.h" 8 | 9 | /* 10 | * initialize spi port 11 | */ 12 | void spi_init(SPI_TypeDef *s) 13 | { 14 | s->SPICR0 = 0xff; // max delay counts on all auto CS timing 15 | s->SPICR1 = 0x84; // enable spi, disable scsni(undocumented!) 16 | s->SPICR2 = 0xc0; // master, hold cs low while busy 17 | s->SPIBR = 0x02; // divide clk by 3 for spi clk 18 | s->SPICSR = 0x0f; // all CS outs high 19 | } 20 | 21 | /* 22 | * send a single byte with CS 23 | */ 24 | void spi_tx_byte(SPI_TypeDef *s, uint8_t data) 25 | { 26 | spi_cs_low(s); 27 | 28 | /* check for tx ready */ 29 | spi_tx_wait(s); 30 | 31 | /* send data */ 32 | s->SPITXDR = data; 33 | 34 | /* wait for rx ready (transmission complete) */ 35 | spi_rx_wait(s); 36 | 37 | spi_cs_high(s); 38 | } 39 | 40 | /* 41 | * send & receive a single byte with CS 42 | */ 43 | uint8_t spi_txrx_byte(SPI_TypeDef *s, uint8_t data) 44 | { 45 | spi_cs_low(s); 46 | 47 | /* check for tx ready */ 48 | spi_tx_wait(s); 49 | 50 | /* send data */ 51 | s->SPITXDR = data; 52 | 53 | /* wait for rx ready (transmission complete) */ 54 | spi_rx_wait(s); 55 | 56 | spi_cs_high(s); 57 | 58 | /* get data */ 59 | return s->SPIRXDR; 60 | } 61 | 62 | /* 63 | * send a buffer of data without CS 64 | */ 65 | void spi_transmit(SPI_TypeDef *s, uint8_t *src, uint16_t sz) 66 | { 67 | /* loop */ 68 | while(sz--) 69 | { 70 | /* wait for tx ready */ 71 | spi_tx_wait(s); 72 | 73 | /* transmit a byte */ 74 | s->SPITXDR = *src++; 75 | } 76 | 77 | /* wait for end of transmision */ 78 | spi_rx_wait(s); 79 | } 80 | 81 | /* 82 | * receive a buffer of data without CS 83 | */ 84 | void spi_receive(SPI_TypeDef *s, uint8_t *dst, uint16_t sz) 85 | { 86 | /* wait for tx ready */ 87 | spi_tx_wait(s); 88 | 89 | /* loop */ 90 | while(sz--) 91 | { 92 | /* send dummy data */ 93 | s->SPITXDR = 0; 94 | 95 | /* wait for rx ready */ 96 | spi_rx_wait(s); 97 | 98 | /* get read data */ 99 | *dst++ = s->SPIRXDR; 100 | } 101 | } -------------------------------------------------------------------------------- /src/acia_rx.v: -------------------------------------------------------------------------------- 1 | // acia_rx.v - asynchronous serial receive submodule 2 | // 06-02-19 E. Brombaugh 3 | 4 | module acia_rx( 5 | input clk, // system clock 6 | input rst, // system reset 7 | input rx_serial, // raw serial input 8 | output reg [7:0] rx_dat, // received byte 9 | output reg rx_stb, // received data available 10 | output reg rx_err // received data error 11 | ); 12 | // sym rate counter for 115200bps @ 16MHz clk 13 | parameter SCW = 8; 14 | parameter sym_cnt = 139; 15 | 16 | // input sync & deglitch 17 | reg [7:0] in_pipe; 18 | reg in_state; 19 | wire all_zero = ~|in_pipe; 20 | wire all_one = &in_pipe; 21 | always @(posedge clk) 22 | if(rst) 23 | begin 24 | // assume RX input idle at start 25 | in_pipe <= 8'hff; 26 | in_state <= 1'b1; 27 | end 28 | else 29 | begin 30 | // shift in a bit 31 | in_pipe <= {in_pipe[6:0],rx_serial}; 32 | 33 | // update state 34 | if(in_state && all_zero) 35 | in_state <= 1'b0; 36 | else if(!in_state && all_one) 37 | in_state <= 1'b1; 38 | end 39 | 40 | // receive machine 41 | reg [8:0] rx_sr; 42 | reg [3:0] rx_bcnt; 43 | reg [SCW-1:0] rx_rcnt; 44 | reg rx_busy; 45 | always @(posedge clk) 46 | if(rst) 47 | begin 48 | rx_busy <= 1'b0; 49 | rx_stb <= 1'b0; 50 | rx_err <= 1'b0; 51 | end 52 | else 53 | begin 54 | if(!rx_busy) 55 | begin 56 | if(!in_state) 57 | begin 58 | // found start bit - wait 1/2 bit to sample 59 | rx_bcnt <= 4'h9; 60 | rx_rcnt <= sym_cnt/2; 61 | rx_busy <= 1'b1; 62 | end 63 | 64 | // clear the strobe 65 | rx_stb <= 1'b0; 66 | end 67 | else 68 | begin 69 | if(~|rx_rcnt) 70 | begin 71 | // sample data and restart for next bit 72 | rx_sr <= {in_state,rx_sr[8:1]}; 73 | rx_rcnt <= sym_cnt; 74 | rx_bcnt <= rx_bcnt - 1; 75 | 76 | if(~|rx_bcnt) 77 | begin 78 | // final bit - check for err and finish 79 | rx_dat <= rx_sr[8:1]; 80 | rx_busy <= 1'b0; 81 | if(in_state && ~rx_sr[0]) 82 | begin 83 | // framing OK 84 | rx_err <= 1'b0; 85 | rx_stb <= 1'b1; 86 | end 87 | else 88 | // framing err 89 | rx_err <= 1'b1; 90 | end 91 | end 92 | else 93 | rx_rcnt <= rx_rcnt - 1; 94 | end 95 | end 96 | endmodule 97 | -------------------------------------------------------------------------------- /c/up5k_riscv.h: -------------------------------------------------------------------------------- 1 | /* 2 | * up5k_riscv.h - hardware definitions for up5k_riscv 3 | * 07-01-19 E. Brombaugh 4 | */ 5 | 6 | #ifndef __up5k_riscv__ 7 | #define __up5k_riscv__ 8 | 9 | #include 10 | 11 | // 32-bit parallel out 12 | #define gp_out (*(volatile uint32_t *)0x20000000) 13 | 14 | // 32-bit clock counter 15 | #define clkcnt_reg (*(volatile uint32_t *)0x50000000) 16 | 17 | // ACIA serial 18 | #define acia_ctlstat (*(volatile uint8_t *)0x30000000) 19 | #define acia_data (*(volatile uint8_t *)0x30000004) 20 | 21 | // SPI cores @ BUS_ADDR74 = 0b0000 and 0b0010 22 | #define SPI0_BASE 0x40000000 23 | #define SPI1_BASE 0x40000080 24 | 25 | typedef struct 26 | { 27 | uint32_t reserved0[8]; 28 | volatile uint8_t SPICR0; 29 | uint8_t reserved1[3]; 30 | volatile uint8_t SPICR1; 31 | uint8_t reserved2[3]; 32 | volatile uint8_t SPICR2; 33 | uint8_t reserved3[3]; 34 | volatile uint8_t SPIBR; 35 | uint8_t reserved4[3]; 36 | volatile uint8_t SPISR; 37 | uint8_t reserved5[3]; 38 | volatile uint8_t SPITXDR; 39 | uint8_t reserved6[3]; 40 | volatile uint8_t SPIRXDR; 41 | uint8_t reserved7[3]; 42 | volatile uint8_t SPICSR; 43 | uint8_t reserved8[3]; 44 | } SPI_TypeDef; 45 | 46 | #define SPI0 ((SPI_TypeDef *) SPI0_BASE) 47 | #define SPI1 ((SPI_TypeDef *) SPI1_BASE) 48 | 49 | // I2C cores @ BUS_ADDR74 = 0b0001 and 0b0011 50 | #define I2C0_BASE 0x40000040 51 | #define I2C1_BASE 0x400000C0 52 | 53 | typedef struct 54 | { 55 | uint32_t reserved0; // 0 56 | uint32_t reserved1; // 1 57 | uint32_t reserved2; // 2 58 | volatile uint8_t I2CSADDR; // 3 59 | uint8_t reserved3[3]; 60 | uint32_t reserved4; // 4 61 | uint32_t reserved5; // 5 62 | volatile uint8_t I2CIRQ; // 6 63 | uint8_t reserved6[3]; 64 | volatile uint8_t I2CIRQEN; // 7 65 | uint8_t reserved7[3]; 66 | volatile uint8_t I2CCR1; // 8 67 | uint8_t reserved8[3]; 68 | volatile uint8_t I2CCMDR; // 9 69 | uint8_t reserved9[3]; 70 | volatile uint8_t I2CBRLSB; // A 71 | uint8_t reservedA[3]; 72 | volatile uint8_t I2CBRMSB; // B 73 | uint8_t reservedB[3]; 74 | volatile uint8_t I2CSR; // C 75 | uint8_t reservedC[3]; 76 | volatile uint8_t I2CTXDR; // D 77 | uint8_t reservedD[3]; 78 | volatile uint8_t I2CRXDR; // E 79 | uint8_t reservedE[3]; 80 | volatile uint8_t I2CGCDR; // F 81 | uint8_t reservedF[3]; 82 | } I2C_TypeDef; 83 | 84 | #define I2C0 ((I2C_TypeDef *) I2C0_BASE) 85 | #define I2C1 ((I2C_TypeDef *) I2C1_BASE) 86 | 87 | #endif -------------------------------------------------------------------------------- /icarus/tb_system.gtkw: -------------------------------------------------------------------------------- 1 | [*] 2 | [*] GTKWave Analyzer v3.3.94 (w)1999-2018 BSI 3 | [*] Tue Jul 2 05:14:05 2019 4 | [*] 5 | [dumpfile] "/home/ericb/Engineering/KBADC/lattice/up5k_riscv/icarus/tb_system.vcd" 6 | [dumpfile_mtime] "Tue Jul 2 05:10:06 2019" 7 | [dumpfile_size] 17342314 8 | [savefile] "/home/ericb/Engineering/KBADC/lattice/up5k_riscv/icarus/tb_system.gtkw" 9 | [timestart] 0 10 | [size] 1366 669 11 | [pos] -1 -1 12 | *-23.000000 13377000 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 -1 13 | [treeopen] tb_system. 14 | [treeopen] tb_system.uut. 15 | [treeopen] tb_system.uut.uwbb. 16 | [sst_width] 219 17 | [signals_width] 228 18 | [sst_expanded] 1 19 | [sst_vpaned_height] 162 20 | @200 21 | -TB 22 | @28 23 | tb_system.RX 24 | tb_system.TX 25 | tb_system.clk24 26 | @22 27 | tb_system.gp_out[31:0] 28 | @28 29 | tb_system.reset 30 | @200 31 | -UUT 32 | @28 33 | tb_system.uut.RX 34 | tb_system.uut.TX 35 | tb_system.uut.clk24 36 | @22 37 | tb_system.uut.gp_out[31:0] 38 | @28 39 | tb_system.uut.gpo_sel 40 | @22 41 | tb_system.uut.mem_addr[31:0] 42 | @28 43 | tb_system.uut.mem_instr 44 | @22 45 | tb_system.uut.mem_rdata[31:0] 46 | @28 47 | tb_system.uut.mem_rdy 48 | tb_system.uut.mem_ready 49 | tb_system.uut.mem_valid 50 | @22 51 | tb_system.uut.mem_wdata[31:0] 52 | tb_system.uut.mem_wstrb[3:0] 53 | tb_system.uut.ram_do[31:0] 54 | @28 55 | tb_system.uut.ram_sel 56 | tb_system.uut.reset 57 | @22 58 | tb_system.uut.rom_do[31:0] 59 | @28 60 | tb_system.uut.rom_sel 61 | @22 62 | tb_system.uut.ser_do[7:0] 63 | @28 64 | tb_system.uut.ser_sel 65 | tb_system.uut.spi0_cs0 66 | tb_system.uut.spi0_miso 67 | tb_system.uut.spi0_mosi 68 | tb_system.uut.spi0_sclk 69 | @22 70 | tb_system.uut.wbb_do[7:0] 71 | @28 72 | tb_system.uut.wbb_rdy 73 | tb_system.uut.wbb_sel 74 | @201 75 | -WB 76 | @22 77 | tb_system.uut.uwbb.uwbm.addr[7:0] 78 | @28 79 | tb_system.uut.uwbb.uwbm.busy 80 | tb_system.uut.uwbb.uwbm.clk 81 | tb_system.uut.uwbb.uwbm.cs 82 | @22 83 | tb_system.uut.uwbb.uwbm.din[7:0] 84 | tb_system.uut.uwbb.uwbm.dout[7:0] 85 | @28 86 | tb_system.uut.uwbb.uwbm.rdy 87 | tb_system.uut.uwbb.uwbm.rst 88 | @22 89 | tb_system.uut.uwbb.uwbm.timeout[3:0] 90 | @28 91 | tb_system.uut.uwbb.uwbm.wb_acki 92 | @22 93 | tb_system.uut.uwbb.uwbm.wb_adro[7:0] 94 | tb_system.uut.uwbb.uwbm.wb_dati[7:0] 95 | tb_system.uut.uwbb.uwbm.wb_dato[7:0] 96 | @28 97 | tb_system.uut.uwbb.uwbm.wb_rwo 98 | tb_system.uut.uwbb.uwbm.wb_stbo 99 | tb_system.uut.uwbb.uwbm.we 100 | [pattern_trace] 1 101 | [pattern_trace] 0 102 | -------------------------------------------------------------------------------- /c/start.S: -------------------------------------------------------------------------------- 1 | /* 2 | * start.S 3 | * 4 | * Startup code taken from picosoc/picorv32 and adapted for use here 5 | * 6 | * Copyright (C) 2017 Clifford Wolf 7 | * Copyright (C) 2019 Sylvain Munaut 8 | * 9 | * Permission to use, copy, modify, and/or distribute this software for any 10 | * purpose with or without fee is hereby granted, provided that the above 11 | * copyright notice and this permission notice appear in all copies. 12 | * 13 | * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES 14 | * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF 15 | * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR 16 | * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES 17 | * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN 18 | * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF 19 | * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. 20 | */ 21 | 22 | .section .text 23 | 24 | start: 25 | 26 | // zero-initialize register file 27 | addi x1, zero, 0 28 | // x2 (sp) is initialized by reset 29 | addi x3, zero, 0 30 | addi x4, zero, 0 31 | addi x5, zero, 0 32 | addi x6, zero, 0 33 | addi x7, zero, 0 34 | addi x8, zero, 0 35 | addi x9, zero, 0 36 | addi x10, zero, 0 37 | addi x11, zero, 0 38 | addi x12, zero, 0 39 | addi x13, zero, 0 40 | addi x14, zero, 0 41 | addi x15, zero, 0 42 | addi x16, zero, 0 43 | addi x17, zero, 0 44 | addi x18, zero, 0 45 | addi x19, zero, 0 46 | addi x20, zero, 0 47 | addi x21, zero, 0 48 | addi x22, zero, 0 49 | addi x23, zero, 0 50 | addi x24, zero, 0 51 | addi x25, zero, 0 52 | addi x26, zero, 0 53 | addi x27, zero, 0 54 | addi x28, zero, 0 55 | addi x29, zero, 0 56 | addi x30, zero, 0 57 | addi x31, zero, 0 58 | 59 | #if 0 60 | // zero initialize entire scratchpad memory 61 | // assumes sp points to end of RAM 62 | li a0, 0x10000000 63 | li a1, 0 64 | setmemloop: 65 | sw a1, 0(a0) 66 | addi a0, a0, 4 67 | blt a0, sp, setmemloop 68 | #endif 69 | 70 | // copy data section 71 | la a0, _sidata 72 | la a1, _sdata 73 | la a2, _edata 74 | bge a1, a2, end_init_data 75 | loop_init_data: 76 | lw a3, 0(a0) 77 | sw a3, 0(a1) 78 | addi a0, a0, 4 79 | addi a1, a1, 4 80 | blt a1, a2, loop_init_data 81 | end_init_data: 82 | 83 | // zero-init bss section 84 | la a0, _sbss 85 | la a1, _ebss 86 | bge a0, a1, end_init_bss 87 | loop_init_bss: 88 | sw zero, 0(a0) 89 | addi a0, a0, 4 90 | blt a0, a1, loop_init_bss 91 | end_init_bss: 92 | 93 | // call main 94 | call main 95 | loop: 96 | j loop 97 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # up5k_riscv 2 | There are many RISC V projects on iCE40. This one is mine. 3 | 4 | ## What is it? 5 | A small RISC V system built on an iCE40 UP5k FPGA which includes the following: 6 | 7 | * Claire Wolf's PicoRV32 CPU 8 | * 8kB boot ROM in dedicated BRAM 9 | * 64kB instruction/data RAM in SPRAM 10 | * Dedicated hard IP core SPI interface to configuration flash 11 | * Additional hard IP core SPI, currently used for an ILI9341 LCD 12 | * Dedicated hard IP core I2C for testing 13 | * 115k serial port 14 | * 32-bit output port (for LEDs, LCD control, etc) 15 | * GCC firmware build 16 | 17 | ## Prerequisites 18 | To build this you will need the following FPGA tools 19 | 20 | * Icestorm - ice40 FPGA tools 21 | * Yosys - Synthesis 22 | * Nextpnr - Place and Route (version newer than Mar 23 2019 is needed to support IP cores) 23 | 24 | Info on these can be found at http://www.clifford.at/icestorm/ 25 | 26 | You will also need a RISC V GCC toolchain to build the startup ROM. I used: 27 | 28 | * https://gnu-mcu-eclipse.github.io/blog/2018/10/19/riscv-none-gcc-v8-1-0-2-20181019-released/ 29 | 30 | ## Building 31 | 32 | git clone https://github.com/emeb/up5k_riscv.git 33 | cd up5k_riscv 34 | git submodule update --init 35 | cd icestorm 36 | make 37 | 38 | ## Loading 39 | I built this system on a custom up5k board and programmed it with a custom 40 | USB->SPI board that I built so you will definitely need to tweak the programming 41 | target of the Makefile in the icestorm directory to match your own hardware. 42 | 43 | ## Booting up 44 | Connect a 115.2kbps terminal to the TX/RX pins of the FPGA and apply power. 45 | You should see a message: 46 | 47 | up5k_riscv - starting up 48 | spi id: 0x00EF4016 49 | LCD initialized 50 | I2C0 Initialized 51 | xxxx... 52 | 53 | If you have an LCD connected to the SPI1 port pins on the FPGA then it should 54 | display several different screens to demonstrate the graphics. You can store 55 | a raw rgb565-encoded image in 240x320 dimensions at flash location 0x200000 56 | which will be BLITed to the screen. A helper script to properly format the 57 | image is located in the "tools" directory. 58 | 59 | A new addition is testing of the SB_I2C hard core. If you have an I2C device 60 | on the bus at the expected address then you will see "." characters, otherwise 61 | "x" will be printed. 62 | 63 | ## Thanks 64 | 65 | Thanks to the developers of all the tools and cores used for this. In particular 66 | 67 | * Claire Wolf for the picorv32 and icestorm, etc. 68 | * Sylvain Munaut for working examples and assistance. 69 | * Dave Shah for knowing almost everything. 70 | -------------------------------------------------------------------------------- /c/i2c.c: -------------------------------------------------------------------------------- 1 | /* 2 | * i2c.c - i2c port driver 3 | * 06-23-20 E. Brombaugh 4 | */ 5 | 6 | #include 7 | #include "printf.h" 8 | #include "clkcnt.h" 9 | #include "i2c.h" 10 | #include "up5k_riscv.h" 11 | 12 | /* contro reg bits */ 13 | #define I2C_CCR_EN 0x80 14 | 15 | #define I2C_CMD_STA 0x80 16 | #define I2C_CMD_STO 0x40 17 | #define I2C_CMD_RD 0x20 18 | #define I2C_CMD_WR 0x10 19 | #define I2C_CMD_ACK 0x08 20 | #define I2C_CMD_CKSDIS 0x04 21 | 22 | #define I2C_SR_TIP 0x80 23 | #define I2C_SR_BUSY 0x40 24 | #define I2C_SR_RARC 0x20 25 | #define I2C_SR_SRW 0x10 26 | #define I2C_SR_ARBL 0x08 27 | #define I2C_SR_TRRDY 0x04 28 | #define I2C_SR_TROE 0x02 29 | #define I2C_SR_HGC 0x01 30 | 31 | /* some common operation macros */ 32 | #define i2c_trrdy_wait(s) while(!(((s)->I2CSR)&I2C_SR_TRRDY)) 33 | 34 | /* 35 | * initialize i2c port 36 | */ 37 | void i2c_init(I2C_TypeDef *s) 38 | { 39 | #if 1 40 | 41 | s->I2CCR1 = I2C_CCR_EN | 12; // enable I2C 42 | s->I2CBRMSB = 0; // high 2 bits - resets I2C core 43 | s->I2CBRLSB = 60; // low 8 bits - (24MHz/100kHz)/4 = 60 44 | #else 45 | s->reserved0 = 0xff; // 0 46 | s->reserved1 = 0xff; // 1 47 | s->reserved2 = 0xff; // 2 48 | s->I2CSADDR = 0xff; // 3 49 | s->reserved4 = 0xff; // 4 50 | s->reserved5 = 0xff; // 5 51 | s->I2CIRQ = 0xff; // 6 52 | s->I2CIRQEN = 0xff; // 7 53 | s->I2CCR1 = 0xff; // 8 54 | s->I2CCMDR = 0xff; // 9 55 | s->I2CBRLSB = 0xff; // A 56 | s->I2CBRMSB = 0xff; // B 57 | s->I2CSR = 0xff; // C 58 | s->I2CTXDR = 0xff; // D 59 | s->I2CRXDR = 0xff; // E 60 | s->I2CGCDR = 0xff; // F 61 | 62 | #endif 63 | } 64 | 65 | /* 66 | * i2c transmit bytes to addr 67 | */ 68 | int8_t i2c_tx(I2C_TypeDef *s, uint8_t addr, uint8_t *data, uint8_t sz) 69 | { 70 | uint8_t err = 0; 71 | uint8_t stat; 72 | uint32_t timeout; 73 | 74 | /* diagnostic flag for I2C activity */ 75 | gp_out |= 1; 76 | 77 | /* transmit address and no read bit */ 78 | s->I2CTXDR = addr<<1; 79 | s->I2CCMDR = I2C_CMD_STA | I2C_CMD_WR | I2C_CMD_CKSDIS; 80 | 81 | /* loop over data */ 82 | while(sz--) 83 | { 84 | /* wait for TRRDY */ 85 | timeout = 3000; 86 | while(timeout--) 87 | { 88 | if(s->I2CSR & I2C_SR_TRRDY) 89 | break; 90 | } 91 | if(!timeout) 92 | err = 3; 93 | 94 | /* transmit data */ 95 | s->I2CTXDR = *data++; 96 | s->I2CCMDR = I2C_CMD_WR | I2C_CMD_CKSDIS; 97 | } 98 | 99 | /* wait for TRRDY */ 100 | timeout = 3000; 101 | while(timeout--) 102 | { 103 | if(s->I2CSR & I2C_SR_TRRDY) 104 | break; 105 | } 106 | if(!timeout) 107 | err = 3; 108 | 109 | /* send stop after last byte */ 110 | s->I2CCMDR = I2C_CMD_STO | I2C_CMD_CKSDIS; 111 | 112 | /* check for error */ 113 | stat = s->I2CSR; 114 | if(stat & I2C_SR_RARC) 115 | { 116 | if(stat & I2C_SR_TROE) 117 | { 118 | /* overrun + NACK */ 119 | printf("i2c_tx: overrun error, status = %02X, resetting\n\r", s->I2CSR); 120 | err = 2; 121 | 122 | /* reset the core */ 123 | s->I2CBRMSB = 0; 124 | } 125 | else 126 | { 127 | /* just a nack */ 128 | err = 1; 129 | } 130 | } 131 | 132 | /* drop flag */ 133 | gp_out &= ~1; 134 | 135 | return err; 136 | } -------------------------------------------------------------------------------- /c/main.c: -------------------------------------------------------------------------------- 1 | /* 2 | * main.c - top level of picorv32 firmware 3 | * 06-30-19 E. Brombaugh 4 | */ 5 | 6 | #include 7 | #include "up5k_riscv.h" 8 | #include "acia.h" 9 | #include "printf.h" 10 | #include "spi.h" 11 | #include "flash.h" 12 | #include "clkcnt.h" 13 | #include "ili9341.h" 14 | #include "i2c.h" 15 | 16 | /* 17 | * main... duh 18 | */ 19 | void main() 20 | { 21 | uint32_t cnt, spi_id, i, j; 22 | //int c; 23 | 24 | init_printf(0,acia_printf_putc); 25 | printf("\n\n\rup5k_riscv - starting up\n\r"); 26 | 27 | /* test both SPI ports */ 28 | spi_init(SPI0); 29 | spi_init(SPI1); 30 | 31 | /* get spi flash id */ 32 | flash_init(SPI0); // wake up the flash chip 33 | spi_id = flash_id(SPI0); 34 | printf("spi flash id: 0x%08X\n\r", spi_id); 35 | 36 | #if 0 37 | /* read some data */ 38 | { 39 | uint8_t read[256]; 40 | flash_read(SPI0, read, 0, 256); 41 | for(i=0;i<256;i+=8) 42 | { 43 | printf("0x%02X: ", i); 44 | for(j=0;j<8;j++) 45 | { 46 | printf("0x%02X ", read[i+j]); 47 | } 48 | printf("\n\r"); 49 | } 50 | } 51 | #endif 52 | 53 | /* Test LCD */ 54 | ili9341_init(SPI1); 55 | printf("LCD initialized\n\r"); 56 | 57 | #if 1 58 | /* color fill + text fonts */ 59 | ili9341_fillRect(20, 20, 200, 280, ILI9341_MAGENTA); 60 | ili9341_drawstr(120-44, (160-12*8), "Hello World", ILI9341_WHITE, ILI9341_MAGENTA); 61 | 62 | /* test font */ 63 | for(i=0;i<256;i+=16) 64 | for(j=0;j<16;j++) 65 | ili9341_drawchar((120-8*8)+(j*8), (160-8*8)+(i/2), i+j, 66 | ILI9341_GREEN, ILI9341_BLACK); 67 | 68 | clkcnt_delayms(1000); 69 | #endif 70 | 71 | #if 0 72 | /* test colored lines */ 73 | { 74 | uint8_t rgb[3], hsv[3]; 75 | uint16_t color; 76 | ili9341_fillScreen(ILI9341_BLACK); 77 | hsv[1] = 255; 78 | hsv[2] = 255; 79 | j=256; 80 | while(j--) 81 | { 82 | for(i=0;i<320;i++) 83 | { 84 | hsv[0] = (i+j); 85 | 86 | ili9341_hsv2rgb(rgb, hsv); 87 | color = ili9342_Color565(rgb[0],rgb[1],rgb[2]); 88 | #if 0 89 | ili9341_drawLine(i, 0, ILI9341_TFTWIDTH-1, i, color); 90 | ili9341_drawLine(ILI9341_TFTWIDTH-1, i, ILI9341_TFTWIDTH-1-i, ILI9341_TFTWIDTH-1, color); 91 | ili9341_drawLine(ILI9341_TFTWIDTH-1-i, ILI9341_TFTWIDTH-1, 0, ILI9341_TFTWIDTH-1-i, color); 92 | ili9341_drawLine(0, ILI9341_TFTWIDTH-1-i, i, 0, color); 93 | #else 94 | ili9341_drawFastHLine(0, i, 240, color); 95 | #endif 96 | } 97 | } 98 | } 99 | clkcnt_delayms(1000); 100 | #endif 101 | 102 | #if 0 103 | /* test image blit from flash */ 104 | { 105 | uint16_t blit[ILI9341_TFTWIDTH*4]; 106 | uint32_t blitaddr, blitsz; 107 | blitaddr = 0x200000; 108 | blitsz = ILI9341_TFTWIDTH*4*sizeof(uint16_t); 109 | for(i=0;i 10us afer PLL lock 71 | reg [7:0] reset_cnt; 72 | reg reset; 73 | always @(posedge clk) 74 | begin 75 | if(!pll_lock) 76 | begin 77 | reset_cnt <= 8'h00; 78 | reset <= 1'b1; 79 | end 80 | else 81 | begin 82 | if(reset_cnt != 8'hff) 83 | begin 84 | reset_cnt <= reset_cnt + 8'h01; 85 | reset <= 1'b1; 86 | end 87 | else 88 | reset <= 1'b0; 89 | end 90 | end 91 | 92 | // system core 93 | wire [3:0] tst; 94 | wire [31:0] gpio_o; 95 | wire raw_rx, raw_tx; 96 | system uut( 97 | .clk24(clk), 98 | .reset(reset), 99 | 100 | .RX(raw_rx), 101 | .TX(raw_tx), 102 | 103 | .spi0_mosi(spi0_mosi), 104 | .spi0_miso(spi0_miso), 105 | .spi0_sclk(spi0_sclk), 106 | .spi0_cs0(spi0_cs0), 107 | 108 | .spi1_mosi(spi1_mosi), 109 | .spi1_miso(spi1_miso), 110 | .spi1_sclk(spi1_sclk), 111 | .spi1_cs0(spi1_cs0), 112 | 113 | .i2c0_sda(i2c0_sda), 114 | .i2c0_scl(i2c0_scl), 115 | 116 | .gp_out(gpio_o) 117 | ); 118 | 119 | // Serial I/O w/ pullup on RX 120 | SB_IO #( 121 | .PIN_TYPE(6'b101001), 122 | .PULLUP(1'b1), 123 | .NEG_TRIGGER(1'b0), 124 | .IO_STANDARD("SB_LVCMOS") 125 | ) urx_io ( 126 | .PACKAGE_PIN(RX), 127 | .LATCH_INPUT_VALUE(1'b0), 128 | .CLOCK_ENABLE(1'b0), 129 | .INPUT_CLK(1'b0), 130 | .OUTPUT_CLK(1'b0), 131 | .OUTPUT_ENABLE(1'b0), 132 | .D_OUT_0(1'b0), 133 | .D_OUT_1(1'b0), 134 | .D_IN_0(raw_rx), 135 | .D_IN_1() 136 | ); 137 | SB_IO #( 138 | .PIN_TYPE(6'b101001), 139 | .PULLUP(1'b0), 140 | .NEG_TRIGGER(1'b0), 141 | .IO_STANDARD("SB_LVCMOS") 142 | ) utx_io ( 143 | .PACKAGE_PIN(TX), 144 | .LATCH_INPUT_VALUE(1'b0), 145 | .CLOCK_ENABLE(1'b0), 146 | .INPUT_CLK(1'b0), 147 | .OUTPUT_CLK(1'b0), 148 | .OUTPUT_ENABLE(1'b1), 149 | .D_OUT_0(raw_tx), 150 | .D_OUT_1(1'b0), 151 | .D_IN_0(), 152 | .D_IN_1() 153 | ); 154 | 155 | assign d1 = gpio_o[0]; 156 | assign d2 = raw_tx; 157 | 158 | // RGB LED Driver IP core 159 | SB_RGBA_DRV #( 160 | .CURRENT_MODE("0b1"), 161 | .RGB0_CURRENT("0b000001"), 162 | .RGB1_CURRENT("0b000001"), 163 | .RGB2_CURRENT("0b000011") 164 | ) RGBA_DRIVER ( 165 | .CURREN(1'b1), 166 | .RGBLEDEN(1'b1), 167 | .RGB0PWM(gpio_o[17]), 168 | .RGB1PWM(gpio_o[18]), 169 | .RGB2PWM(gpio_o[19]), 170 | .RGB0(RGB0), 171 | .RGB1(RGB1), 172 | .RGB2(RGB2) 173 | ); 174 | 175 | // LCD control lines 176 | assign lcd_nrst = gpio_o[31]; 177 | assign lcd_dc = gpio_o[30]; 178 | endmodule 179 | -------------------------------------------------------------------------------- /c/flash.c: -------------------------------------------------------------------------------- 1 | /* 2 | * flash.c - flash memory driver 3 | * 07-03-19 E. Brombaugh 4 | */ 5 | 6 | #include "flash.h" 7 | #include "spi.h" 8 | 9 | /* flash commands */ 10 | #define FLASH_WRPG 0x02 // write page 11 | #define FLASH_READ 0x03 // read data 12 | #define FLASH_RSR1 0x05 // read status reg 1 13 | #define FLASH_RSR2 0x35 // read status reg 2 14 | #define FLASH_RSR3 0x15 // read status reg 3 15 | #define FLASH_WSR1 0x01 // write status reg 1 16 | #define FLASH_WSR2 0x31 // write status reg 2 17 | #define FLASH_WSR3 0x11 // write status reg 3 18 | #define FLASH_WEN 0x06 // write enable 19 | #define FLASH_EB32 0x52 // erase block 32k 20 | #define FLASH_GBUL 0x98 // global unlock 21 | #define FLASH_WKUP 0xAB // wakeup 22 | #define FLASH_ERST 0x66 // enable reset 23 | #define FLASH_RST 0x99 // reset 24 | #define FLASH_ID 0x9f // get ID bytes 25 | 26 | 27 | /* 28 | * wake up SPI Flash 29 | */ 30 | void flash_init(SPI_TypeDef *s) 31 | { 32 | spi_tx_byte(s, FLASH_WKUP); 33 | } 34 | 35 | /* 36 | * send a header to the SPI Flash (for read/erase/write commands) 37 | */ 38 | void flash_header(SPI_TypeDef *s, uint8_t cmd, uint32_t addr) 39 | { 40 | uint8_t txdat[4]; 41 | 42 | /* assemble header */ 43 | txdat[0] = cmd; 44 | txdat[1] = (addr>>16)&0xff; 45 | txdat[2] = (addr>>8)&0xff; 46 | txdat[3] = (addr)&0xff; 47 | 48 | /* send the header */ 49 | spi_transmit(s, txdat, 4); 50 | } 51 | 52 | /* 53 | * read bytes from SPI Flash 54 | */ 55 | void flash_read(SPI_TypeDef *s, uint8_t *dst, uint32_t addr, uint32_t len) 56 | { 57 | uint8_t dummy __attribute ((unused)); 58 | 59 | spi_cs_low(s); 60 | 61 | /* send read header */ 62 | flash_header(s, FLASH_READ, addr); 63 | 64 | /* wait for tx ready */ 65 | spi_tx_wait(s); 66 | 67 | /* dummy reads */ 68 | dummy = s->SPIRXDR; 69 | dummy = s->SPIRXDR; 70 | 71 | /* get the buffer */ 72 | spi_receive(s, dst, len); 73 | 74 | spi_cs_high(s); 75 | } 76 | 77 | /* 78 | * read bytes from SPI Flash 79 | */ 80 | uint8_t flash_rdreg(SPI_TypeDef *s, uint8_t cmd) 81 | { 82 | uint8_t result; 83 | 84 | spi_cs_low(s); 85 | 86 | /* wait for tx ready */ 87 | spi_tx_wait(s); 88 | 89 | /* send command */ 90 | s->SPITXDR = cmd; 91 | 92 | /* wait for rx ready */ 93 | spi_rx_wait(s); 94 | 95 | /* dummy read */ 96 | result = s->SPIRXDR; 97 | 98 | /* send dummy data */ 99 | s->SPITXDR = 0; 100 | 101 | /* wait for rx ready */ 102 | spi_rx_wait(s); 103 | 104 | /* read data */ 105 | result = s->SPIRXDR; 106 | 107 | spi_cs_high(s); 108 | 109 | return result; 110 | } 111 | 112 | /* 113 | * get SPI Flash status byte 114 | */ 115 | uint8_t flash_status(SPI_TypeDef *s) 116 | { 117 | return flash_rdreg(s, FLASH_RSR1); 118 | } 119 | 120 | /* 121 | * wait for SPI Flash not busy 122 | */ 123 | void flash_busy_wait(SPI_TypeDef *s) 124 | { 125 | while(!(flash_status(s)&1)); 126 | } 127 | 128 | /* 129 | * erase 32kB block in SPI Flash 130 | */ 131 | void flash_eraseblk(SPI_TypeDef *s, uint32_t addr) 132 | { 133 | /* write enable */ 134 | spi_tx_byte(s, FLASH_WEN); 135 | 136 | spi_cs_low(s); 137 | 138 | /* send read header */ 139 | flash_header(s, FLASH_EB32, addr); 140 | 141 | /* wait for rx ready */ 142 | spi_rx_wait(s); 143 | 144 | spi_cs_high(s); 145 | } 146 | 147 | /* 148 | * write bytes to SPI Flash 149 | */ 150 | void flash_write(SPI_TypeDef *s, uint8_t *src, uint32_t addr, uint32_t len) 151 | { 152 | /* write enable */ 153 | spi_tx_byte(s, FLASH_WEN); 154 | 155 | spi_cs_low(s); 156 | 157 | /* send read header */ 158 | flash_header(s, FLASH_WRPG, addr); 159 | 160 | /* send data packet */ 161 | spi_transmit(s, src, len); 162 | 163 | spi_cs_high(s); 164 | } 165 | 166 | /* 167 | * get ID from SPI Flash 168 | */ 169 | uint32_t flash_id(SPI_TypeDef *s) 170 | { 171 | uint8_t result[3]; 172 | 173 | spi_cs_low(s); 174 | 175 | /* send command */ 176 | spi_tx_wait(s); 177 | s->SPITXDR = FLASH_ID; 178 | spi_rx_wait(s); 179 | result[0] = s->SPIRXDR; // dummy read 180 | 181 | /* get id bytes */ 182 | spi_receive(s, result, 3); 183 | 184 | spi_cs_high(s); 185 | 186 | return (result[0]<<16) | (result[1]<<8) | result[2]; 187 | } 188 | -------------------------------------------------------------------------------- /src/acia.v: -------------------------------------------------------------------------------- 1 | // acia.v - strippped-down version of MC6850 ACIA with home-made TX/RX 2 | // 03-02-19 E. Brombaugh 3 | 4 | module acia( 5 | input clk, // system clock 6 | input rst, // system reset 7 | input cs, // chip select 8 | input we, // write enable 9 | input rs, // register select 10 | input rx, // serial receive 11 | input [7:0] din, // data bus input 12 | output reg [7:0] dout, // data bus output 13 | output tx, // serial tx_start 14 | output irq // high-true interrupt request 15 | ); 16 | // hard-coded bit-rate 17 | localparam sym_rate = 115200; 18 | localparam clk_freq = 24000000; 19 | localparam sym_cnt = clk_freq / sym_rate; 20 | localparam SCW = $clog2(sym_cnt); 21 | 22 | wire [SCW-1:0] sym_cntr = sym_cnt; 23 | 24 | // generate tx_start signal on write to register 1 25 | wire tx_start = cs & rs & we; 26 | 27 | // load control register 28 | reg [1:0] counter_divide_select, tx_start_control; 29 | reg [2:0] word_select; // dummy 30 | reg receive_interrupt_enable; 31 | always @(posedge clk) 32 | begin 33 | if(rst) 34 | begin 35 | counter_divide_select <= 2'b00; 36 | word_select <= 3'b000; 37 | tx_start_control <= 2'b00; 38 | receive_interrupt_enable <= 1'b0; 39 | end 40 | else if(cs & ~rs & we) 41 | { 42 | receive_interrupt_enable, 43 | tx_start_control, 44 | word_select, 45 | counter_divide_select 46 | } <= din; 47 | end 48 | 49 | // acia reset generation 50 | wire acia_rst = rst | (counter_divide_select == 2'b11); 51 | 52 | // load dout with either status or rx data 53 | wire [7:0] rx_dat, status; 54 | always @(posedge clk) 55 | begin 56 | if(rst) 57 | begin 58 | dout <= 8'h00; 59 | end 60 | else 61 | begin 62 | if(cs & ~we) 63 | begin 64 | if(rs) 65 | dout <= rx_dat; 66 | else 67 | dout <= status; 68 | end 69 | end 70 | end 71 | 72 | // tx empty is cleared when tx_start starts, cleared when tx_busy deasserts 73 | reg txe; 74 | wire tx_busy; 75 | reg prev_tx_busy; 76 | always @(posedge clk) 77 | begin 78 | if(rst) 79 | begin 80 | txe <= 1'b1; 81 | prev_tx_busy <= 1'b0; 82 | end 83 | else 84 | begin 85 | prev_tx_busy <= tx_busy; 86 | 87 | if(tx_start) 88 | txe <= 1'b0; 89 | else if(prev_tx_busy & ~tx_busy) 90 | txe <= 1'b1; 91 | end 92 | end 93 | 94 | // rx full is set when rx_stb pulses, cleared when data reg read 95 | wire rx_stb; 96 | reg rxf; 97 | always @(posedge clk) 98 | begin 99 | if(rst) 100 | rxf <= 1'b0; 101 | else 102 | begin 103 | if(rx_stb) 104 | rxf <= 1'b1; 105 | else if(cs & rs & ~we) 106 | rxf <= 1'b0; 107 | end 108 | end 109 | 110 | // assemble status byte 111 | wire rx_err; 112 | assign status = 113 | { 114 | irq, // bit 7 = irq - forced inactive 115 | 1'b0, // bit 6 = parity error - unused 116 | rx_err, // bit 5 = overrun error - same as all errors 117 | rx_err, // bit 4 = framing error - same as all errors 118 | 1'b0, // bit 3 = /CTS - forced active 119 | 1'b0, // bit 2 = /DCD - forced active 120 | txe, // bit 1 = tx_start empty 121 | rxf // bit 0 = receive full 122 | }; 123 | 124 | // Async Receiver 125 | acia_rx #( 126 | .SCW(SCW), // rate counter width 127 | .sym_cnt(sym_cnt) // rate count value 128 | ) 129 | my_rx( 130 | .clk(clk), // system clock 131 | .rst(acia_rst), // system reset 132 | .rx_serial(rx), // raw serial input 133 | .rx_dat(rx_dat), // received byte 134 | .rx_stb(rx_stb), // received data available 135 | .rx_err(rx_err) // received data error 136 | ); 137 | 138 | // Transmitter 139 | acia_tx #( 140 | .SCW(SCW), // rate counter width 141 | .sym_cnt(sym_cnt) // rate count value 142 | ) 143 | my_tx( 144 | .clk(clk), // system clock 145 | .rst(acia_rst), // system reset 146 | .tx_dat(din), // transmit data byte 147 | .tx_start(tx_start), // trigger transmission 148 | .tx_serial(tx), // tx serial output 149 | .tx_busy(tx_busy) // tx is active (not ready) 150 | ); 151 | 152 | // generate IRQ 153 | assign irq = (rxf & receive_interrupt_enable) | ((tx_start_control==2'b01) & txe); 154 | 155 | endmodule 156 | -------------------------------------------------------------------------------- /c/printf.h: -------------------------------------------------------------------------------- 1 | /* 2 | File: printf.h 3 | 4 | Copyright (C) 2004 Kustaa Nyholm 5 | 6 | This library is free software; you can redistribute it and/or 7 | modify it under the terms of the GNU Lesser General Public 8 | License as published by the Free Software Foundation; either 9 | version 2.1 of the License, or (at your option) any later version. 10 | 11 | This library is distributed in the hope that it will be useful, 12 | but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. 14 | See the GNU Lesser General Public License for more details. 15 | 16 | You should have received a copy of the GNU Lesser General Public 17 | License along with this library; if not, write to the Free Software 18 | Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 19 | 20 | This library is realy just two files: 'printf.h' and 'printf.c'. 21 | 22 | They provide a simple and small (+200 loc) printf functionality to 23 | be used in embedded systems. 24 | 25 | I've found them so usefull in debugging that I do not bother with a 26 | debugger at all. 27 | 28 | They are distributed in source form, so to use them, just compile them 29 | into your project. 30 | 31 | Two printf variants are provided: printf and sprintf. 32 | 33 | The formats supported by this implementation are: 'd' 'u' 'c' 's' 'x' 'X'. 34 | 35 | Zero padding and field width are also supported. 36 | 37 | If the library is compiled with 'PRINTF_SUPPORT_LONG' defined then the 38 | long specifier is also 39 | supported. Note that this will pull in some long math routines (pun intended!) 40 | and thus make your executable noticably longer. 41 | 42 | The memory foot print of course depends on the target cpu, compiler and 43 | compiler options, but a rough guestimate (based on a H8S target) is about 44 | 1.4 kB for code and some twenty 'int's and 'char's, say 60 bytes of stack space. 45 | Not too bad. Your milage may vary. By hacking the source code you can 46 | get rid of some hunred bytes, I'm sure, but personally I feel the balance of 47 | functionality and flexibility versus code size is close to optimal for 48 | many embedded systems. 49 | 50 | To use the printf you need to supply your own character output function, 51 | something like : 52 | 53 | void putc ( void* p, char c) 54 | { 55 | while (!SERIAL_PORT_EMPTY) ; 56 | SERIAL_PORT_TX_REGISTER = c; 57 | } 58 | 59 | Before you can call printf you need to initialize it to use your 60 | character output function with something like: 61 | 62 | init_printf(NULL,putc); 63 | 64 | Notice the 'NULL' in 'init_printf' and the parameter 'void* p' in 'putc', 65 | the NULL (or any pointer) you pass into the 'init_printf' will eventually be 66 | passed to your 'putc' routine. This allows you to pass some storage space (or 67 | anything realy) to the character output function, if necessary. 68 | This is not often needed but it was implemented like that because it made 69 | implementing the sprintf function so neat (look at the source code). 70 | 71 | The code is re-entrant, except for the 'init_printf' function, so it 72 | is safe to call it from interupts too, although this may result in mixed output. 73 | If you rely on re-entrancy, take care that your 'putc' function is re-entrant! 74 | 75 | The printf and sprintf functions are actually macros that translate to 76 | 'tfp_printf' and 'tfp_sprintf'. This makes it possible 77 | to use them along with 'stdio.h' printf's in a single source file. 78 | You just need to undef the names before you include the 'stdio.h'. 79 | Note that these are not function like macros, so if you have variables 80 | or struct members with these names, things will explode in your face. 81 | Without variadic macros this is the best we can do to wrap these 82 | fucnction. If it is a problem just give up the macros and use the 83 | functions directly or rename them. 84 | 85 | For further details see source code. 86 | 87 | regs Kusti, 23.10.2004 88 | */ 89 | 90 | 91 | #ifndef __TFP_PRINTF__ 92 | #define __TFP_PRINTF__ 93 | 94 | #ifdef __cplusplus 95 | extern "C" { 96 | #endif 97 | 98 | #include 99 | 100 | void init_printf(void* putp,void (*putf) (void*,char)); 101 | 102 | void tfp_printf(char *fmt, ...); 103 | void tfp_sprintf(char* s,char *fmt, ...); 104 | 105 | void tfp_format(void* putp,void (*putf) (void*,char),char *fmt, va_list va); 106 | 107 | #define printf tfp_printf 108 | #define sprintf tfp_sprintf 109 | 110 | #ifdef __cplusplus 111 | } 112 | #endif 113 | 114 | #endif 115 | -------------------------------------------------------------------------------- /src/system.v: -------------------------------------------------------------------------------- 1 | /* 2 | * system.v - top-level system for picorv32 3 | * 06-30-19 E. Brombaugh 4 | */ 5 | 6 | `default_nettype none 7 | 8 | module system( 9 | input clk24, // clock, reset 10 | reset, 11 | 12 | input RX, // serial 13 | output TX, 14 | 15 | inout spi0_mosi, // SPI core 0 16 | spi0_miso, 17 | spi0_sclk, 18 | spi0_cs0, 19 | 20 | inout spi1_mosi, // SPI core 1 21 | spi1_miso, 22 | spi1_sclk, 23 | spi1_cs0, 24 | 25 | inout i2c0_sda, // I2C core 0 26 | i2c0_scl, 27 | 28 | output reg [31:0] gp_out 29 | ); 30 | // CPU 31 | wire mem_valid; 32 | wire mem_instr; 33 | wire mem_ready; 34 | wire [31:0] mem_addr; 35 | reg [31:0] mem_rdata; 36 | wire [31:0] mem_wdata; 37 | wire [ 3:0] mem_wstrb; 38 | picorv32 #( 39 | .PROGADDR_RESET(32'h 0000_0000), // start or ROM 40 | .STACKADDR(32'h 1001_0000), // end of SPRAM 41 | .BARREL_SHIFTER(0), 42 | .COMPRESSED_ISA(0), 43 | .ENABLE_COUNTERS(0), 44 | .ENABLE_MUL(0), 45 | .ENABLE_DIV(0), 46 | .ENABLE_IRQ(0), 47 | .ENABLE_IRQ_QREGS(0), 48 | .CATCH_MISALIGN(0), 49 | .CATCH_ILLINSN(0) 50 | ) cpu_I ( 51 | .clk (clk24), 52 | .resetn (~reset), 53 | .mem_valid (mem_valid), 54 | .mem_instr (mem_instr), 55 | .mem_ready (mem_ready), 56 | .mem_addr (mem_addr), 57 | .mem_wdata (mem_wdata), 58 | .mem_wstrb (mem_wstrb), 59 | .mem_rdata (mem_rdata) 60 | ); 61 | 62 | // Address decode 63 | wire rom_sel = (mem_addr[31:28]==4'h0)&mem_valid ? 1'b1 : 1'b0; 64 | wire ram_sel = (mem_addr[31:28]==4'h1)&mem_valid ? 1'b1 : 1'b0; 65 | wire gpo_sel = (mem_addr[31:28]==4'h2)&mem_valid ? 1'b1 : 1'b0; 66 | wire ser_sel = (mem_addr[31:28]==4'h3)&mem_valid ? 1'b1 : 1'b0; 67 | wire wbb_sel = (mem_addr[31:28]==4'h4)&mem_valid ? 1'b1 : 1'b0; 68 | wire cnt_sel = (mem_addr[31:28]==4'h5)&mem_valid ? 1'b1 : 1'b0; 69 | 70 | // 2k x 32 ROM 71 | reg [31:0] rom[2047:0], rom_do; 72 | initial 73 | $readmemh("rom.hex",rom); 74 | always @(posedge clk24) 75 | rom_do <= rom[mem_addr[12:2]]; 76 | 77 | // RAM, byte addressable 78 | wire [31:0] ram_do; 79 | spram_16kx32 uram( 80 | .clk(clk24), 81 | .sel(ram_sel), 82 | .we(mem_wstrb), 83 | .addr(mem_addr[15:0]), 84 | .wdat(mem_wdata), 85 | .rdat(ram_do) 86 | ); 87 | 88 | // GPIO 89 | always @(posedge clk24) 90 | if(gpo_sel) 91 | begin 92 | if(mem_wstrb[0]) 93 | gp_out[7:0] <= mem_wdata[7:0]; 94 | if(mem_wstrb[1]) 95 | gp_out[15:8] <= mem_wdata[15:8]; 96 | if(mem_wstrb[2]) 97 | gp_out[23:16] <= mem_wdata[23:16]; 98 | if(mem_wstrb[3]) 99 | gp_out[31:24] <= mem_wdata[31:24]; 100 | end 101 | 102 | // Serial 103 | wire [7:0] ser_do; 104 | acia uacia( 105 | .clk(clk24), // system clock 106 | .rst(reset), // system reset 107 | .cs(ser_sel), // chip select 108 | .we(mem_wstrb[0]), // write enable 109 | .rs(mem_addr[2]), // address 110 | .rx(RX), // serial receive 111 | .din(mem_wdata[7:0]), // data bus input 112 | .dout(ser_do), // data bus output 113 | .tx(TX), // serial transmit 114 | .irq() // interrupt request 115 | ); 116 | 117 | // 256B Wishbone bus master and SB IP cores @ F100-F1FF 118 | wire [7:0] wbb_do; 119 | wire wbb_rdy; 120 | wb_bus uwbb( 121 | .clk(clk24), // system clock 122 | .rst(reset), // system reset 123 | .cs(wbb_sel), // chip select 124 | .we(mem_wstrb[0]), // write enable 125 | .addr(mem_addr[9:2]), // address 126 | .din(mem_wdata[7:0]), // data bus input 127 | .dout(wbb_do), // data bus output 128 | .rdy(wbb_rdy), // bus ready 129 | .spi0_mosi(spi0_mosi), // spi core 0 mosi 130 | .spi0_miso(spi0_miso), // spi core 0 miso 131 | .spi0_sclk(spi0_sclk), // spi core 0 sclk 132 | .spi0_cs0(spi0_cs0), // spi core 0 cs 133 | .spi1_mosi(spi1_mosi), // spi core 1 mosi 134 | .spi1_miso(spi1_miso), // spi core 1 miso 135 | .spi1_sclk(spi1_sclk), // spi core 1 sclk 136 | .spi1_cs0(spi1_cs0), // spi core 1 cs 137 | .i2c0_sda(i2c0_sda), // i2c core 0 data 138 | .i2c0_scl(i2c0_scl) // i2c core 0 clk 139 | ); 140 | 141 | // Resettable clock counter 142 | reg [31:0] cnt; 143 | always @(posedge clk24) 144 | if(cnt_sel & |mem_wstrb) 145 | begin 146 | if(mem_wstrb[0]) 147 | cnt[7:0] <= mem_wdata[7:0]; 148 | if(mem_wstrb[1]) 149 | cnt[15:8] <= mem_wdata[15:8]; 150 | if(mem_wstrb[2]) 151 | cnt[23:16] <= mem_wdata[23:16]; 152 | if(mem_wstrb[3]) 153 | cnt[31:24] <= mem_wdata[31:24]; 154 | end 155 | else 156 | cnt <= cnt + 32'd1; 157 | 158 | // Read Mux 159 | always @(*) 160 | casex({cnt_sel,wbb_sel,ser_sel,gpo_sel,ram_sel,rom_sel}) 161 | 6'b000001: mem_rdata = rom_do; 162 | 6'b00001x: mem_rdata = ram_do; 163 | 6'b0001xx: mem_rdata = gp_out; 164 | 6'b001xxx: mem_rdata = {{24{1'b0}},ser_do}; 165 | 6'b01xxxx: mem_rdata = {{24{1'b0}},wbb_do}; 166 | 6'b1xxxxx: mem_rdata = cnt; 167 | default: mem_rdata = 32'd0; 168 | endcase 169 | 170 | // ready flag 171 | reg mem_rdy; 172 | always @(posedge clk24) 173 | if(reset) 174 | mem_rdy <= 1'b0; 175 | else 176 | mem_rdy <= (cnt_sel|ser_sel|gpo_sel|ram_sel|rom_sel) & ~mem_rdy; 177 | assign mem_ready = wbb_rdy | mem_rdy; 178 | 179 | endmodule 180 | 181 | -------------------------------------------------------------------------------- /c/printf.c: -------------------------------------------------------------------------------- 1 | /* 2 | File: printf.c 3 | 4 | Copyright (C) 2004 Kustaa Nyholm 5 | 6 | This library is free software; you can redistribute it and/or 7 | modify it under the terms of the GNU Lesser General Public 8 | License as published by the Free Software Foundation; either 9 | version 2.1 of the License, or (at your option) any later version. 10 | 11 | This library is distributed in the hope that it will be useful, 12 | but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 14 | Lesser General Public License for more details. 15 | 16 | You should have received a copy of the GNU Lesser General Public 17 | License along with this library; if not, write to the Free Software 18 | Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 19 | 20 | */ 21 | 22 | #include "printf.h" 23 | 24 | typedef void (*putcf) (void*,char); 25 | static putcf stdout_putf; 26 | static void* stdout_putp; 27 | 28 | #define PRINTF_LONG_SUPPORT 29 | 30 | #ifdef PRINTF_LONG_SUPPORT 31 | 32 | static void uli2a(unsigned long int num, unsigned int base, int uc,char * bf) 33 | { 34 | int n=0; 35 | unsigned int d=1; 36 | while (num/d >= base) 37 | d*=base; 38 | while (d!=0) { 39 | int dgt = num / d; 40 | num%=d; 41 | d/=base; 42 | if (n || dgt>0|| d==0) { 43 | *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); 44 | ++n; 45 | } 46 | } 47 | *bf=0; 48 | } 49 | 50 | static void li2a (long num, char * bf) 51 | { 52 | if (num<0) { 53 | num=-num; 54 | *bf++ = '-'; 55 | } 56 | uli2a(num,10,0,bf); 57 | } 58 | 59 | #endif 60 | 61 | static void ui2a(unsigned int num, unsigned int base, int uc,char * bf) 62 | { 63 | int n=0; 64 | unsigned int d=1; 65 | while (num/d >= base) 66 | d*=base; 67 | while (d!=0) { 68 | int dgt = num / d; 69 | num%= d; 70 | d/=base; 71 | if (n || dgt>0 || d==0) { 72 | *bf++ = dgt+(dgt<10 ? '0' : (uc ? 'A' : 'a')-10); 73 | ++n; 74 | } 75 | } 76 | *bf=0; 77 | } 78 | 79 | static void i2a (int num, char * bf) 80 | { 81 | if (num<0) { 82 | num=-num; 83 | *bf++ = '-'; 84 | } 85 | ui2a(num,10,0,bf); 86 | } 87 | 88 | static int a2d(char ch) 89 | { 90 | if (ch>='0' && ch<='9') 91 | return ch-'0'; 92 | else if (ch>='a' && ch<='f') 93 | return ch-'a'+10; 94 | else if (ch>='A' && ch<='F') 95 | return ch-'A'+10; 96 | else return -1; 97 | } 98 | 99 | static char a2i(char ch, char** src,int base,int* nump) 100 | { 101 | char* p= *src; 102 | int num=0; 103 | int digit; 104 | while ((digit=a2d(ch))>=0) { 105 | if (digit>base) break; 106 | num=num*base+digit; 107 | ch=*p++; 108 | } 109 | *src=p; 110 | *nump=num; 111 | return ch; 112 | } 113 | 114 | static void putchw(void* putp,putcf putf,int n, char z, char* bf) 115 | { 116 | char fc=z? '0' : ' '; 117 | char ch; 118 | char* p=bf; 119 | while (*p++ && n > 0) 120 | n--; 121 | while (n-- > 0) 122 | putf(putp,fc); 123 | while ((ch= *bf++)) 124 | putf(putp,ch); 125 | } 126 | 127 | void tfp_format(void* putp,putcf putf,char *fmt, va_list va) 128 | { 129 | char bf[12]; 130 | 131 | char ch; 132 | 133 | 134 | while ((ch=*(fmt++))) { 135 | if (ch!='%') 136 | putf(putp,ch); 137 | else { 138 | char lz=0; 139 | #ifdef PRINTF_LONG_SUPPORT 140 | char lng=0; 141 | #endif 142 | int w=0; 143 | ch=*(fmt++); 144 | if (ch=='0') { 145 | ch=*(fmt++); 146 | lz=1; 147 | } 148 | if (ch>='0' && ch<='9') { 149 | ch=a2i(ch,&fmt,10,&w); 150 | } 151 | #ifdef PRINTF_LONG_SUPPORT 152 | if (ch=='l') { 153 | ch=*(fmt++); 154 | lng=1; 155 | } 156 | #endif 157 | switch (ch) { 158 | case 0: 159 | goto abort; 160 | case 'u' : { 161 | #ifdef PRINTF_LONG_SUPPORT 162 | if (lng) 163 | uli2a(va_arg(va, unsigned long int),10,0,bf); 164 | else 165 | #endif 166 | ui2a(va_arg(va, unsigned int),10,0,bf); 167 | putchw(putp,putf,w,lz,bf); 168 | break; 169 | } 170 | case 'd' : { 171 | #ifdef PRINTF_LONG_SUPPORT 172 | if (lng) 173 | li2a(va_arg(va, unsigned long int),bf); 174 | else 175 | #endif 176 | i2a(va_arg(va, int),bf); 177 | putchw(putp,putf,w,lz,bf); 178 | break; 179 | } 180 | case 'x': case 'X' : 181 | #ifdef PRINTF_LONG_SUPPORT 182 | if (lng) 183 | uli2a(va_arg(va, unsigned long int),16,(ch=='X'),bf); 184 | else 185 | #endif 186 | ui2a(va_arg(va, unsigned int),16,(ch=='X'),bf); 187 | putchw(putp,putf,w,lz,bf); 188 | break; 189 | case 'c' : 190 | putf(putp,(char)(va_arg(va, int))); 191 | break; 192 | case 's' : 193 | putchw(putp,putf,w,0,va_arg(va, char*)); 194 | break; 195 | case '%' : 196 | putf(putp,ch); 197 | default: 198 | break; 199 | } 200 | } 201 | } 202 | abort:; 203 | } 204 | 205 | 206 | void init_printf(void* putp,void (*putf) (void*,char)) 207 | { 208 | stdout_putf=putf; 209 | stdout_putp=putp; 210 | } 211 | 212 | void tfp_printf(char *fmt, ...) 213 | { 214 | va_list va; 215 | va_start(va,fmt); 216 | tfp_format(stdout_putp,stdout_putf,fmt,va); 217 | va_end(va); 218 | } 219 | 220 | static void putcp(void* p,char c) 221 | { 222 | *(*((char**)p))++ = c; 223 | } 224 | 225 | 226 | 227 | void tfp_sprintf(char* s,char *fmt, ...) 228 | { 229 | va_list va; 230 | va_start(va,fmt); 231 | tfp_format(&s,putcp,fmt,va); 232 | putcp(&s,0); 233 | va_end(va); 234 | } -------------------------------------------------------------------------------- /src/save/wb_bus.v: -------------------------------------------------------------------------------- 1 | // wb_bus.v - wrapper for wishbone master and IP cores 2 | // 07-01-19 E. Brombaugh 3 | 4 | `default_nettype none 5 | 6 | module wb_bus( 7 | input clk, // system clock 8 | input rst, // system reset 9 | input cs, // chip select 10 | input we, // write enable 11 | input [7:0] addr, // register select 12 | input [7:0] din, // data bus input 13 | output [7:0] dout, // data bus output 14 | output rdy, // high-true ready flag 15 | inout spi0_mosi, // spi core 0 mosi 16 | inout spi0_miso, // spi core 0 miso 17 | inout spi0_sclk, // spi core 0 sclk 18 | inout spi0_cs0, // spi core 0 cs 19 | inout spi1_mosi, // spi core 1 mosi 20 | inout spi1_miso, // spi core 1 miso 21 | inout spi1_sclk, // spi core 1 sclk 22 | inout spi1_cs0 // spi core 1 cs 23 | ); 24 | 25 | // the wishbone master 26 | wire sbstbi, sbrwi, sbacko; 27 | wire [7:0] sbadri, sbdato, sbdati; 28 | wb_master uwbm( 29 | .clk(clk), 30 | .rst(rst), 31 | .cs(cs), 32 | .we(we), 33 | .addr(addr), 34 | .din(din), 35 | .dout(dout), 36 | .rdy(rdy), 37 | .wb_stbo(sbstbi), 38 | .wb_adro(sbadri), 39 | .wb_rwo(sbrwi), 40 | .wb_dato(sbdati), 41 | .wb_acki(sbacko), 42 | .wb_dati(sbdato) 43 | ); 44 | 45 | // SPI IP Core 0 46 | wire moe_0, mo_0, si_0; // MOSI components 47 | wire soe_0, mi_0, so_0; // MISO components 48 | wire sckoe_0, scko_0, scki_0; // SCLK components 49 | wire mcsnoe_00, mcsno_00, scsni_0; // CS0 components 50 | wire [7:0] sbdato_0; 51 | wire sbacko_0; 52 | SB_SPI #( 53 | .BUS_ADDR74("0b0000") 54 | ) 55 | spiInst0 ( 56 | .SBCLKI(clk), 57 | .SBRWI(sbrwi), 58 | .SBSTBI(sbstbi), 59 | .SBADRI7(sbadri[7]), 60 | .SBADRI6(sbadri[6]), 61 | .SBADRI5(sbadri[5]), 62 | .SBADRI4(sbadri[4]), 63 | .SBADRI3(sbadri[3]), 64 | .SBADRI2(sbadri[2]), 65 | .SBADRI1(sbadri[1]), 66 | .SBADRI0(sbadri[0]), 67 | .SBDATI7(sbdati[7]), 68 | .SBDATI6(sbdati[6]), 69 | .SBDATI5(sbdati[5]), 70 | .SBDATI4(sbdati[4]), 71 | .SBDATI3(sbdati[3]), 72 | .SBDATI2(sbdati[2]), 73 | .SBDATI1(sbdati[1]), 74 | .SBDATI0(sbdati[0]), 75 | .MI(mi_0), 76 | .SI(si_0), 77 | .SCKI(scki_0), 78 | .SCSNI(scsni_0), // must be pulled high to prevent SOE 79 | .SBDATO7(sbdato_0[7]), 80 | .SBDATO6(sbdato_0[6]), 81 | .SBDATO5(sbdato_0[5]), 82 | .SBDATO4(sbdato_0[4]), 83 | .SBDATO3(sbdato_0[3]), 84 | .SBDATO2(sbdato_0[2]), 85 | .SBDATO1(sbdato_0[1]), 86 | .SBDATO0(sbdato_0[0]), 87 | .SBACKO(sbacko_0), 88 | .SPIIRQ(), 89 | .SPIWKUP(), 90 | .SO(so_0), 91 | .SOE(soe_0), 92 | .MO(mo_0), 93 | .MOE(moe_0), 94 | .SCKO(scko_0), 95 | .SCKOE(sckoe_0), 96 | .MCSNO3(), 97 | .MCSNO2(), 98 | .MCSNO1(), 99 | .MCSNO0(mcsno_00), 100 | .MCSNOE3(), 101 | .MCSNOE2(), 102 | .MCSNOE1(), 103 | .MCSNOE0(mcsnoe_00) 104 | ); 105 | 106 | // I/O drivers are tri-state output w/ simple input 107 | // MOSI driver 108 | SB_IO #( 109 | .PIN_TYPE(6'b101001), 110 | .PULLUP(1'b1), 111 | .NEG_TRIGGER(1'b0), 112 | .IO_STANDARD("SB_LVCMOS") 113 | ) umosi_0 ( 114 | .PACKAGE_PIN(spi0_mosi), 115 | .LATCH_INPUT_VALUE(1'b0), 116 | .CLOCK_ENABLE(1'b0), 117 | .INPUT_CLK(1'b0), 118 | .OUTPUT_CLK(1'b0), 119 | .OUTPUT_ENABLE(moe_0), 120 | .D_OUT_0(mo_0), 121 | .D_OUT_1(1'b0), 122 | .D_IN_0(si_0), 123 | .D_IN_1() 124 | ); 125 | 126 | // MISO driver 127 | SB_IO #( 128 | .PIN_TYPE(6'b101001), 129 | .PULLUP(1'b1), 130 | .NEG_TRIGGER(1'b0), 131 | .IO_STANDARD("SB_LVCMOS") 132 | ) umiso_0 ( 133 | .PACKAGE_PIN(spi0_miso), 134 | .LATCH_INPUT_VALUE(1'b0), 135 | .CLOCK_ENABLE(1'b0), 136 | .INPUT_CLK(1'b0), 137 | .OUTPUT_CLK(1'b0), 138 | .OUTPUT_ENABLE(soe_0), 139 | .D_OUT_0(so_0), 140 | .D_OUT_1(1'b0), 141 | .D_IN_0(mi_0), 142 | .D_IN_1() 143 | ); 144 | 145 | // SCK driver 146 | SB_IO #( 147 | .PIN_TYPE(6'b101001), 148 | .PULLUP(1'b1), 149 | .NEG_TRIGGER(1'b0), 150 | .IO_STANDARD("SB_LVCMOS") 151 | ) usclk_0 ( 152 | .PACKAGE_PIN(spi0_sclk), 153 | .LATCH_INPUT_VALUE(1'b0), 154 | .CLOCK_ENABLE(1'b0), 155 | .INPUT_CLK(1'b0), 156 | .OUTPUT_CLK(1'b0), 157 | .OUTPUT_ENABLE(sckoe_0), 158 | .D_OUT_0(scko_0), 159 | .D_OUT_1(1'b0), 160 | .D_IN_0(scki_0), 161 | .D_IN_1() 162 | ); 163 | 164 | // CS0 driver 165 | SB_IO #( 166 | .PIN_TYPE(6'b101001), 167 | .PULLUP(1'b1), 168 | .NEG_TRIGGER(1'b0), 169 | .IO_STANDARD("SB_LVCMOS") 170 | ) ucs0_0 ( 171 | .PACKAGE_PIN(spi0_cs0), 172 | .LATCH_INPUT_VALUE(1'b0), 173 | .CLOCK_ENABLE(1'b0), 174 | .INPUT_CLK(1'b0), 175 | .OUTPUT_CLK(1'b0), 176 | .OUTPUT_ENABLE(1'b1), // or mcsnoe_00 for hi-z when inactive 177 | .D_OUT_0(mcsno_00), 178 | .D_OUT_1(1'b0), 179 | .D_IN_0(scsni_0), // unused to prevent accidental slave mode 180 | .D_IN_1() 181 | ); 182 | 183 | // SPI IP Core 1 184 | wire moe_1, mo_1, si_1; // MOSI components 185 | wire soe_1, mi_1, so_1; // MISO components 186 | wire sckoe_1, scko_1, scki_1; // SCLK components 187 | wire mcsnoe_01, mcsno_01, scsni_1; // CS0 components 188 | wire [7:0] sbdato_1; 189 | wire sbacko_1; 190 | SB_SPI #( 191 | .BUS_ADDR74("0b0001") 192 | ) 193 | spiInst1 ( 194 | .SBCLKI(clk), 195 | .SBRWI(sbrwi), 196 | .SBSTBI(sbstbi), 197 | .SBADRI7(sbadri[7]), 198 | .SBADRI6(sbadri[6]), 199 | .SBADRI5(sbadri[5]), 200 | .SBADRI4(sbadri[4]), 201 | .SBADRI3(sbadri[3]), 202 | .SBADRI2(sbadri[2]), 203 | .SBADRI1(sbadri[1]), 204 | .SBADRI0(sbadri[0]), 205 | .SBDATI7(sbdati[7]), 206 | .SBDATI6(sbdati[6]), 207 | .SBDATI5(sbdati[5]), 208 | .SBDATI4(sbdati[4]), 209 | .SBDATI3(sbdati[3]), 210 | .SBDATI2(sbdati[2]), 211 | .SBDATI1(sbdati[1]), 212 | .SBDATI0(sbdati[0]), 213 | .MI(mi_1), 214 | .SI(si_1), 215 | .SCKI(scki_1), 216 | .SCSNI(scsni_1), // must be pulled high to prevent SOE 217 | .SBDATO7(sbdato_1[7]), 218 | .SBDATO6(sbdato_1[6]), 219 | .SBDATO5(sbdato_1[5]), 220 | .SBDATO4(sbdato_1[4]), 221 | .SBDATO3(sbdato_1[3]), 222 | .SBDATO2(sbdato_1[2]), 223 | .SBDATO1(sbdato_1[1]), 224 | .SBDATO0(sbdato_1[0]), 225 | .SBACKO(sbacko_1), 226 | .SPIIRQ(), 227 | .SPIWKUP(), 228 | .SO(so_1), 229 | .SOE(soe_1), 230 | .MO(mo_1), 231 | .MOE(moe_1), 232 | .SCKO(scko_1), 233 | .SCKOE(sckoe_1), 234 | .MCSNO3(), 235 | .MCSNO2(), 236 | .MCSNO1(), 237 | .MCSNO0(mcsno_01), 238 | .MCSNOE3(), 239 | .MCSNOE2(), 240 | .MCSNOE1(), 241 | .MCSNOE0(mcsnoe_01) 242 | ); 243 | 244 | // I/O drivers are tri-state output w/ simple input 245 | // MOSI driver 246 | SB_IO #( 247 | .PIN_TYPE(6'b101001), 248 | .PULLUP(1'b1), 249 | .NEG_TRIGGER(1'b0), 250 | .IO_STANDARD("SB_LVCMOS") 251 | ) umosi_1 ( 252 | .PACKAGE_PIN(spi1_mosi), 253 | .LATCH_INPUT_VALUE(1'b0), 254 | .CLOCK_ENABLE(1'b0), 255 | .INPUT_CLK(1'b0), 256 | .OUTPUT_CLK(1'b0), 257 | .OUTPUT_ENABLE(moe_1), 258 | .D_OUT_0(mo_1), 259 | .D_OUT_1(1'b0), 260 | .D_IN_0(si_1), 261 | .D_IN_1() 262 | ); 263 | 264 | // MISO driver 265 | SB_IO #( 266 | .PIN_TYPE(6'b101001), 267 | .PULLUP(1'b1), 268 | .NEG_TRIGGER(1'b0), 269 | .IO_STANDARD("SB_LVCMOS") 270 | ) umiso_1 ( 271 | .PACKAGE_PIN(spi1_miso), 272 | .LATCH_INPUT_VALUE(1'b0), 273 | .CLOCK_ENABLE(1'b0), 274 | .INPUT_CLK(1'b0), 275 | .OUTPUT_CLK(1'b0), 276 | .OUTPUT_ENABLE(soe_1), 277 | .D_OUT_0(so_1), 278 | .D_OUT_1(1'b0), 279 | .D_IN_0(mi_1), 280 | .D_IN_1() 281 | ); 282 | 283 | // SCK driver 284 | SB_IO #( 285 | .PIN_TYPE(6'b101001), 286 | .PULLUP(1'b1), 287 | .NEG_TRIGGER(1'b0), 288 | .IO_STANDARD("SB_LVCMOS") 289 | ) usclk_1 ( 290 | .PACKAGE_PIN(spi1_sclk), 291 | .LATCH_INPUT_VALUE(1'b0), 292 | .CLOCK_ENABLE(1'b0), 293 | .INPUT_CLK(1'b0), 294 | .OUTPUT_CLK(1'b0), 295 | .OUTPUT_ENABLE(sckoe_1), 296 | .D_OUT_0(scko_1), 297 | .D_OUT_1(1'b0), 298 | .D_IN_0(scki_1), 299 | .D_IN_1() 300 | ); 301 | 302 | // CS0 driver 303 | SB_IO #( 304 | .PIN_TYPE(6'b101001), 305 | .PULLUP(1'b1), 306 | .NEG_TRIGGER(1'b0), 307 | .IO_STANDARD("SB_LVCMOS") 308 | ) ucs0_1 ( 309 | .PACKAGE_PIN(spi1_cs0), 310 | .LATCH_INPUT_VALUE(1'b0), 311 | .CLOCK_ENABLE(1'b0), 312 | .INPUT_CLK(1'b0), 313 | .OUTPUT_CLK(1'b0), 314 | .OUTPUT_ENABLE(1'b1), // or mcsnoe_00 for hi-z when inactive 315 | .D_OUT_0(mcsno_01), 316 | .D_OUT_1(1'b0), 317 | .D_IN_0(scsni_1), // unused to prevent accidental slave mode 318 | .D_IN_1() 319 | ); 320 | 321 | // mux the DAT and ACK lines into the WB master 322 | always @(*) 323 | casex(sbadri[7:4]) 324 | 4'h0: 325 | begin 326 | sbdato = sbdato_0; 327 | sbacko = sbacko_0; 328 | end 329 | 330 | 4'h1: 331 | begin 332 | sbdato = sbdato_1; 333 | sbacko = sbacko_1; 334 | end 335 | endcase 336 | 337 | endmodule 338 | -------------------------------------------------------------------------------- /src/wb_bus.v: -------------------------------------------------------------------------------- 1 | // wb_bus.v - wrapper for wishbone master and IP cores 2 | // 07-01-19 E. Brombaugh 3 | 4 | `default_nettype none 5 | 6 | module wb_bus( 7 | input clk, // system clock 8 | input rst, // system reset 9 | input cs, // chip select 10 | input we, // write enable 11 | input [7:0] addr, // register select 12 | input [7:0] din, // data bus input 13 | output [7:0] dout, // data bus output 14 | output rdy, // high-true ready flag 15 | inout spi0_mosi, // spi core 0 mosi 16 | inout spi0_miso, // spi core 0 miso 17 | inout spi0_sclk, // spi core 0 sclk 18 | inout spi0_cs0, // spi core 0 cs 19 | inout spi1_mosi, // spi core 1 mosi 20 | inout spi1_miso, // spi core 1 miso 21 | inout spi1_sclk, // spi core 1 sclk 22 | inout spi1_cs0, // spi core 1 cs 23 | inout i2c0_sda, // i2c core 0 data 24 | inout i2c0_scl // i2c core 0 clock 25 | ); 26 | 27 | // the wishbone master 28 | wire sbstbi, sbrwi, sbacko; 29 | wire [7:0] sbadri, sbdato, sbdati; 30 | wb_master uwbm( 31 | .clk(clk), 32 | .rst(rst), 33 | .cs(cs), 34 | .we(we), 35 | .addr(addr), 36 | .din(din), 37 | .dout(dout), 38 | .rdy(rdy), 39 | .wb_stbo(sbstbi), 40 | .wb_adro(sbadri), 41 | .wb_rwo(sbrwi), 42 | .wb_dato(sbdati), 43 | .wb_acki(sbacko), 44 | .wb_dati(sbdato) 45 | ); 46 | 47 | // SPI IP Core 0 48 | wire moe_0, mo_0, si_0; // MOSI components 49 | wire soe_0, mi_0, so_0; // MISO components 50 | wire sckoe_0, scko_0, scki_0; // SCLK components 51 | wire mcsnoe_00, mcsno_00, scsni_0; // CS0 components 52 | wire [7:0] sbdato_0; 53 | wire sbacko_0; 54 | SB_SPI #( 55 | .BUS_ADDR74("0b0000") 56 | ) 57 | spiInst0 ( 58 | .SBCLKI(clk), 59 | .SBRWI(sbrwi), 60 | .SBSTBI(sbstbi), 61 | .SBADRI7(sbadri[7]), 62 | .SBADRI6(sbadri[6]), 63 | .SBADRI5(sbadri[5]), 64 | .SBADRI4(sbadri[4]), 65 | .SBADRI3(sbadri[3]), 66 | .SBADRI2(sbadri[2]), 67 | .SBADRI1(sbadri[1]), 68 | .SBADRI0(sbadri[0]), 69 | .SBDATI7(sbdati[7]), 70 | .SBDATI6(sbdati[6]), 71 | .SBDATI5(sbdati[5]), 72 | .SBDATI4(sbdati[4]), 73 | .SBDATI3(sbdati[3]), 74 | .SBDATI2(sbdati[2]), 75 | .SBDATI1(sbdati[1]), 76 | .SBDATI0(sbdati[0]), 77 | .MI(mi_0), 78 | .SI(si_0), 79 | .SCKI(scki_0), 80 | .SCSNI(scsni_0), // must be pulled high to prevent SOE 81 | .SBDATO7(sbdato_0[7]), 82 | .SBDATO6(sbdato_0[6]), 83 | .SBDATO5(sbdato_0[5]), 84 | .SBDATO4(sbdato_0[4]), 85 | .SBDATO3(sbdato_0[3]), 86 | .SBDATO2(sbdato_0[2]), 87 | .SBDATO1(sbdato_0[1]), 88 | .SBDATO0(sbdato_0[0]), 89 | .SBACKO(sbacko_0), 90 | .SPIIRQ(), 91 | .SPIWKUP(), 92 | .SO(so_0), 93 | .SOE(soe_0), 94 | .MO(mo_0), 95 | .MOE(moe_0), 96 | .SCKO(scko_0), 97 | .SCKOE(sckoe_0), 98 | .MCSNO3(), 99 | .MCSNO2(), 100 | .MCSNO1(), 101 | .MCSNO0(mcsno_00), 102 | .MCSNOE3(), 103 | .MCSNOE2(), 104 | .MCSNOE1(), 105 | .MCSNOE0(mcsnoe_00) 106 | ); 107 | 108 | // I/O drivers are tri-state output w/ simple input 109 | // MOSI driver 110 | SB_IO #( 111 | .PIN_TYPE(6'b101001), 112 | .PULLUP(1'b1), 113 | .NEG_TRIGGER(1'b0), 114 | .IO_STANDARD("SB_LVCMOS") 115 | ) umosi_0 ( 116 | .PACKAGE_PIN(spi0_mosi), 117 | .LATCH_INPUT_VALUE(1'b0), 118 | .CLOCK_ENABLE(1'b0), 119 | .INPUT_CLK(1'b0), 120 | .OUTPUT_CLK(1'b0), 121 | .OUTPUT_ENABLE(moe_0), 122 | .D_OUT_0(mo_0), 123 | .D_OUT_1(1'b0), 124 | .D_IN_0(si_0), 125 | .D_IN_1() 126 | ); 127 | 128 | // MISO driver 129 | SB_IO #( 130 | .PIN_TYPE(6'b101001), 131 | .PULLUP(1'b1), 132 | .NEG_TRIGGER(1'b0), 133 | .IO_STANDARD("SB_LVCMOS") 134 | ) umiso_0 ( 135 | .PACKAGE_PIN(spi0_miso), 136 | .LATCH_INPUT_VALUE(1'b0), 137 | .CLOCK_ENABLE(1'b0), 138 | .INPUT_CLK(1'b0), 139 | .OUTPUT_CLK(1'b0), 140 | .OUTPUT_ENABLE(soe_0), 141 | .D_OUT_0(so_0), 142 | .D_OUT_1(1'b0), 143 | .D_IN_0(mi_0), 144 | .D_IN_1() 145 | ); 146 | 147 | // SCK driver 148 | SB_IO #( 149 | .PIN_TYPE(6'b101001), 150 | .PULLUP(1'b1), 151 | .NEG_TRIGGER(1'b0), 152 | .IO_STANDARD("SB_LVCMOS") 153 | ) usclk_0 ( 154 | .PACKAGE_PIN(spi0_sclk), 155 | .LATCH_INPUT_VALUE(1'b0), 156 | .CLOCK_ENABLE(1'b0), 157 | .INPUT_CLK(1'b0), 158 | .OUTPUT_CLK(1'b0), 159 | .OUTPUT_ENABLE(sckoe_0), 160 | .D_OUT_0(scko_0), 161 | .D_OUT_1(1'b0), 162 | .D_IN_0(scki_0), 163 | .D_IN_1() 164 | ); 165 | 166 | // CS0 driver 167 | SB_IO #( 168 | .PIN_TYPE(6'b101001), 169 | .PULLUP(1'b1), 170 | .NEG_TRIGGER(1'b0), 171 | .IO_STANDARD("SB_LVCMOS") 172 | ) ucs0_0 ( 173 | .PACKAGE_PIN(spi0_cs0), 174 | .LATCH_INPUT_VALUE(1'b0), 175 | .CLOCK_ENABLE(1'b0), 176 | .INPUT_CLK(1'b0), 177 | .OUTPUT_CLK(1'b0), 178 | .OUTPUT_ENABLE(1'b1), // or mcsnoe_00 for hi-z when inactive 179 | .D_OUT_0(mcsno_00), 180 | .D_OUT_1(1'b0), 181 | .D_IN_0(scsni_0), // unused to prevent accidental slave mode 182 | .D_IN_1() 183 | ); 184 | 185 | // SPI IP Core 1 186 | wire moe_1, mo_1, si_1; // MOSI components 187 | wire soe_1, mi_1, so_1; // MISO components 188 | wire sckoe_1, scko_1, scki_1; // SCLK components 189 | wire mcsnoe_01, mcsno_01, scsni_1; // CS0 components 190 | wire [7:0] sbdato_1; 191 | wire sbacko_1; 192 | SB_SPI #( 193 | .BUS_ADDR74("0b0010") // 2nd SPI instance (despite Lattice docs) 194 | ) 195 | spiInst1 ( 196 | .SBCLKI(clk), 197 | .SBRWI(sbrwi), 198 | .SBSTBI(sbstbi), 199 | .SBADRI7(sbadri[7]), 200 | .SBADRI6(sbadri[6]), 201 | .SBADRI5(sbadri[5]), 202 | .SBADRI4(sbadri[4]), 203 | .SBADRI3(sbadri[3]), 204 | .SBADRI2(sbadri[2]), 205 | .SBADRI1(sbadri[1]), 206 | .SBADRI0(sbadri[0]), 207 | .SBDATI7(sbdati[7]), 208 | .SBDATI6(sbdati[6]), 209 | .SBDATI5(sbdati[5]), 210 | .SBDATI4(sbdati[4]), 211 | .SBDATI3(sbdati[3]), 212 | .SBDATI2(sbdati[2]), 213 | .SBDATI1(sbdati[1]), 214 | .SBDATI0(sbdati[0]), 215 | .MI(mi_1), 216 | .SI(si_1), 217 | .SCKI(scki_1), 218 | .SCSNI(scsni_1), // must be pulled high to prevent SOE 219 | .SBDATO7(sbdato_1[7]), 220 | .SBDATO6(sbdato_1[6]), 221 | .SBDATO5(sbdato_1[5]), 222 | .SBDATO4(sbdato_1[4]), 223 | .SBDATO3(sbdato_1[3]), 224 | .SBDATO2(sbdato_1[2]), 225 | .SBDATO1(sbdato_1[1]), 226 | .SBDATO0(sbdato_1[0]), 227 | .SBACKO(sbacko_1), 228 | .SPIIRQ(), 229 | .SPIWKUP(), 230 | .SO(so_1), 231 | .SOE(soe_1), 232 | .MO(mo_1), 233 | .MOE(moe_1), 234 | .SCKO(scko_1), 235 | .SCKOE(sckoe_1), 236 | .MCSNO3(), 237 | .MCSNO2(), 238 | .MCSNO1(), 239 | .MCSNO0(mcsno_01), 240 | .MCSNOE3(), 241 | .MCSNOE2(), 242 | .MCSNOE1(), 243 | .MCSNOE0(mcsnoe_01) 244 | ); 245 | 246 | // I/O drivers are tri-state output w/ simple input 247 | // MOSI driver 248 | SB_IO #( 249 | .PIN_TYPE(6'b101001), 250 | .PULLUP(1'b1), 251 | .NEG_TRIGGER(1'b0), 252 | .IO_STANDARD("SB_LVCMOS") 253 | ) umosi_1 ( 254 | .PACKAGE_PIN(spi1_mosi), 255 | .LATCH_INPUT_VALUE(1'b0), 256 | .CLOCK_ENABLE(1'b0), 257 | .INPUT_CLK(1'b0), 258 | .OUTPUT_CLK(1'b0), 259 | .OUTPUT_ENABLE(moe_1), 260 | .D_OUT_0(mo_1), 261 | .D_OUT_1(1'b0), 262 | .D_IN_0(si_1), 263 | .D_IN_1() 264 | ); 265 | 266 | // MISO driver 267 | SB_IO #( 268 | .PIN_TYPE(6'b101001), 269 | .PULLUP(1'b1), 270 | .NEG_TRIGGER(1'b0), 271 | .IO_STANDARD("SB_LVCMOS") 272 | ) umiso_1 ( 273 | .PACKAGE_PIN(spi1_miso), 274 | .LATCH_INPUT_VALUE(1'b0), 275 | .CLOCK_ENABLE(1'b0), 276 | .INPUT_CLK(1'b0), 277 | .OUTPUT_CLK(1'b0), 278 | .OUTPUT_ENABLE(soe_1), 279 | .D_OUT_0(so_1), 280 | .D_OUT_1(1'b0), 281 | .D_IN_0(mi_1), 282 | .D_IN_1() 283 | ); 284 | 285 | // SCK driver 286 | SB_IO #( 287 | .PIN_TYPE(6'b101001), 288 | .PULLUP(1'b1), 289 | .NEG_TRIGGER(1'b0), 290 | .IO_STANDARD("SB_LVCMOS") 291 | ) usclk_1 ( 292 | .PACKAGE_PIN(spi1_sclk), 293 | .LATCH_INPUT_VALUE(1'b0), 294 | .CLOCK_ENABLE(1'b0), 295 | .INPUT_CLK(1'b0), 296 | .OUTPUT_CLK(1'b0), 297 | .OUTPUT_ENABLE(sckoe_1), 298 | .D_OUT_0(scko_1), 299 | .D_OUT_1(1'b0), 300 | .D_IN_0(scki_1), 301 | .D_IN_1() 302 | ); 303 | 304 | // CS0 driver 305 | SB_IO #( 306 | .PIN_TYPE(6'b101001), 307 | .PULLUP(1'b1), 308 | .NEG_TRIGGER(1'b0), 309 | .IO_STANDARD("SB_LVCMOS") 310 | ) ucs0_1 ( 311 | .PACKAGE_PIN(spi1_cs0), 312 | .LATCH_INPUT_VALUE(1'b0), 313 | .CLOCK_ENABLE(1'b0), 314 | .INPUT_CLK(1'b0), 315 | .OUTPUT_CLK(1'b0), 316 | .OUTPUT_ENABLE(1'b1), // or mcsnoe_00 for hi-z when inactive 317 | .D_OUT_0(mcsno_01), 318 | .D_OUT_1(1'b0), 319 | .D_IN_0(scsni_1), // unused to prevent accidental slave mode 320 | .D_IN_1() 321 | ); 322 | 323 | // I2C IP Core 324 | wire sda_oe_0, sda_i_0, sda_o_0; // sda components 325 | wire scl_oe_0, scl_i_0, scl_o_0; // scl components 326 | wire [7:0] sbdato_2; 327 | wire sbacko_2; 328 | SB_I2C #( 329 | .BUS_ADDR74("0b0001") 330 | ) 331 | i2cInst0 ( 332 | .SBCLKI(clk), 333 | .SBRWI(sbrwi), 334 | .SBSTBI(sbstbi), 335 | .SBADRI7(sbadri[7]), 336 | .SBADRI6(sbadri[6]), 337 | .SBADRI5(sbadri[5]), 338 | .SBADRI4(sbadri[4]), 339 | .SBADRI3(sbadri[3]), 340 | .SBADRI2(sbadri[2]), 341 | .SBADRI1(sbadri[1]), 342 | .SBADRI0(sbadri[0]), 343 | .SBDATI7(sbdati[7]), 344 | .SBDATI6(sbdati[6]), 345 | .SBDATI5(sbdati[5]), 346 | .SBDATI4(sbdati[4]), 347 | .SBDATI3(sbdati[3]), 348 | .SBDATI2(sbdati[2]), 349 | .SBDATI1(sbdati[1]), 350 | .SBDATI0(sbdati[0]), 351 | .SCLI(scl_i_0), 352 | .SDAI(sda_i_0), 353 | .SBDATO7(sbdato_2[7]), 354 | .SBDATO6(sbdato_2[6]), 355 | .SBDATO5(sbdato_2[5]), 356 | .SBDATO4(sbdato_2[4]), 357 | .SBDATO3(sbdato_2[3]), 358 | .SBDATO2(sbdato_2[2]), 359 | .SBDATO1(sbdato_2[1]), 360 | .SBDATO0(sbdato_2[0]), 361 | .SBACKO(sbacko_2), 362 | .I2CIRQ(), 363 | .I2CWKUP(), 364 | .SCLO(scl_o_0), 365 | .SCLOE(scl_oe_0), 366 | .SDAO(sda_o_0), 367 | .SDAOE(sda_oe_0) 368 | ); 369 | 370 | // I/O drivers are tri-state output w/ simple input 371 | // SDA driver 372 | SB_IO #( 373 | .PIN_TYPE(6'b101001), 374 | .PULLUP(1'b1), 375 | .NEG_TRIGGER(1'b0), 376 | .IO_STANDARD("SB_LVCMOS") 377 | ) usda ( 378 | .PACKAGE_PIN(i2c0_sda), 379 | .LATCH_INPUT_VALUE(1'b0), 380 | .CLOCK_ENABLE(1'b0), 381 | .INPUT_CLK(1'b0), 382 | .OUTPUT_CLK(1'b0), 383 | .OUTPUT_ENABLE(sda_oe_0), 384 | .D_OUT_0(sda_o_0), 385 | .D_OUT_1(1'b0), 386 | .D_IN_0(sda_i_0), 387 | .D_IN_1() 388 | ); 389 | 390 | // SCL driver 391 | SB_IO #( 392 | .PIN_TYPE(6'b101001), 393 | .PULLUP(1'b1), 394 | .NEG_TRIGGER(1'b0), 395 | .IO_STANDARD("SB_LVCMOS") 396 | ) uscl ( 397 | .PACKAGE_PIN(i2c0_scl), 398 | .LATCH_INPUT_VALUE(1'b0), 399 | .CLOCK_ENABLE(1'b0), 400 | .INPUT_CLK(1'b0), 401 | .OUTPUT_CLK(1'b0), 402 | .OUTPUT_ENABLE(scl_oe_0), 403 | .D_OUT_0(scl_o_0), 404 | .D_OUT_1(1'b0), 405 | .D_IN_0(scl_i_0), 406 | .D_IN_1() 407 | ); 408 | 409 | // OR muxing of output data & ack 410 | assign sbdato = sbdato_0 | sbdato_1 | sbdato_2; 411 | assign sbacko = sbacko_0 | sbacko_1 | sbacko_2; 412 | endmodule 413 | -------------------------------------------------------------------------------- /c/ili9341.c: -------------------------------------------------------------------------------- 1 | /* 2 | * ili9341.h - ILI9341 LCD driver 3 | * 07-03-19 E. Brombaugh 4 | * portions based on Adafruit ILI9341 driver for Arduino 5 | */ 6 | 7 | #include "ili9341.h" 8 | #include "spi.h" 9 | #include "clkcnt.h" 10 | #include "font_8x8.h" 11 | 12 | #define ILI9341_DC_CMD() (gp_out&=~(1<<30)) 13 | #define ILI9341_DC_DATA() (gp_out|=(1<<30)) 14 | #define ILI9341_RST_LOW() (gp_out&=~(1<<31)) 15 | #define ILI9341_RST_HIGH() (gp_out|=(1<<31)) 16 | 17 | #define ILI9341_CMD 0x100 18 | #define ILI9341_DLY 0x200 19 | #define ILI9341_END 0x400 20 | 21 | /* some flags for init */ 22 | #define INITR_GREENTAB 0x0 23 | #define INITR_REDTAB 0x1 24 | 25 | #define ILI9341_NOP 0x00 26 | #define ILI9341_SWRESET 0x01 27 | #define ILI9341_RDDID 0x04 28 | #define ILI9341_RDDST 0x09 29 | 30 | #define ILI9341_SLPIN 0x10 31 | #define ILI9341_SLPOUT 0x11 32 | #define ILI9341_PTLON 0x12 33 | #define ILI9341_NORON 0x13 34 | 35 | #define ILI9341_INVOFF 0x20 36 | #define ILI9341_INVON 0x21 37 | #define ILI9341_GAMMASET 0x26 38 | #define ILI9341_DISPOFF 0x28 39 | #define ILI9341_DISPON 0x29 40 | #define ILI9341_CASET 0x2A 41 | #define ILI9341_RASET 0x2B 42 | #define ILI9341_RAMWR 0x2C 43 | #define ILI9341_RAMRD 0x2E 44 | 45 | #define ILI9341_PTLAR 0x30 46 | #define ILI9341_PIXFMT 0x3A 47 | #define ILI9341_MADCTL 0x36 48 | 49 | #define ILI9341_FRMCTR1 0xB1 50 | #define ILI9341_FRMCTR2 0xB2 51 | #define ILI9341_FRMCTR3 0xB3 52 | #define ILI9341_INVCTR 0xB4 53 | #define ILI9341_DFUNCTR 0xB6 54 | 55 | #define ILI9341_PWCTR1 0xC0 56 | #define ILI9341_PWCTR2 0xC1 57 | #define ILI9341_PWCTR3 0xC2 58 | #define ILI9341_PWCTR4 0xC3 59 | #define ILI9341_PWCTR5 0xC4 60 | #define ILI9341_VMCTR1 0xC5 61 | #define ILI9341_VMCTR2 0xC7 62 | 63 | #define ILI9341_RDID1 0xDA 64 | #define ILI9341_RDID2 0xDB 65 | #define ILI9341_RDID3 0xDC 66 | #define ILI9341_RDID4 0xDD 67 | 68 | #define ILI9341_PWCTR6 0xFC 69 | 70 | #define ILI9341_GMCTRP1 0xE0 71 | #define ILI9341_GMCTRN1 0xE1 72 | 73 | /* these values look better - more saturated, less flicker */ 74 | const static uint16_t initlst[] = { 75 | 0x11 | ILI9341_CMD, // Exit Sleep 76 | 120 | ILI9341_DLY, // 120 ms delay 77 | 0xCF | ILI9341_CMD, // Power control B 78 | 0x00, 0xC3, 0x30, 79 | 0xED | ILI9341_CMD, // Power on sequence control 80 | 0x64, 0x03, 0x12, 0x81, 81 | 0xE8 | ILI9341_CMD, // Driver timing control A 82 | 0x85, 0x10, 0x79, 83 | 0xCB | ILI9341_CMD, // Power control B 84 | 0x39, 0x2C, 0x00, 0x34, 0x02, 85 | 0xF7 | ILI9341_CMD, // Pump ratio control 86 | 0x20, 87 | 0xEA | ILI9341_CMD, // Driver timing control B 88 | 0x00, 0x00, 89 | ILI9341_PWCTR1 | ILI9341_CMD, // Power control 1 90 | 0x22, 91 | ILI9341_PWCTR2 | ILI9341_CMD, // Power control 2 92 | 0x11, 93 | ILI9341_VMCTR1 | ILI9341_CMD, // VCOM Control 1 94 | 0x3d, 0x20, 95 | ILI9341_VMCTR2 | ILI9341_CMD, // VCOM Control 2 96 | 0xAA, 97 | ILI9341_MADCTL | ILI9341_CMD, // Memory Access Control 98 | 0x08, 99 | ILI9341_PIXFMT | ILI9341_CMD, // 100 | 0x55, 101 | ILI9341_FRMCTR1| ILI9341_CMD, // 102 | 0x00, 0x13, 103 | ILI9341_DFUNCTR| ILI9341_CMD, // 104 | 0x0A, 0xA2, 105 | 0xF6| ILI9341_CMD, 106 | 0x01, 0x30, 107 | 0xF2| ILI9341_CMD, // 3Gamma Function Disable 108 | 0x00, 109 | ILI9341_GAMMASET| ILI9341_CMD, // Set Gamma 110 | 0x01, 111 | ILI9341_GMCTRP1| ILI9341_CMD, // Gamma 112 | 0x0F, 0x3f, 0x2f, 0x0c, 113 | 0x10, 0x0A, 0x53, 0xD5, 114 | 0x40, 0x0A, 0x13, 0x03, 115 | 0x08, 0x03, 0x00, 116 | ILI9341_GMCTRN1 | ILI9341_CMD, // Gamma 117 | 0x00, 0x00, 0x10, 0x03, 118 | 0x0f, 0x05, 0x2c, 0xa2, 119 | 0x3f, 0x05, 0x0e, 0x0c, 120 | 0x37, 0x3c, 0x0F, 121 | ILI9341_SLPOUT | ILI9341_CMD, // Exit Sleep 122 | 120 | ILI9341_DLY, // 120 ms delay 123 | ILI9341_DISPON | ILI9341_CMD, // display on 124 | 50 | ILI9341_DLY, // 50 ms delay 125 | ILI9341_END // END 126 | }; 127 | 128 | /* pointer to SPI port */ 129 | SPI_TypeDef *ili9341_spi; 130 | 131 | /* 132 | * send single byte via SPI - cmd or data depends on bit 8 133 | */ 134 | void ili9341_write(uint16_t dat) 135 | { 136 | if((dat&ILI9341_CMD) == ILI9341_CMD) 137 | ILI9341_DC_CMD(); 138 | else 139 | ILI9341_DC_DATA(); 140 | 141 | spi_tx_byte(ili9341_spi, dat&0xff); 142 | } 143 | 144 | /* 145 | * initialize the LCD 146 | */ 147 | void ili9341_init(SPI_TypeDef *s) 148 | { 149 | // save SPI port 150 | ili9341_spi = s; 151 | 152 | // Reset it 153 | ILI9341_RST_LOW(); 154 | clkcnt_delayms(50); 155 | ILI9341_RST_HIGH(); 156 | clkcnt_delayms(50); 157 | 158 | // Send init command list 159 | uint16_t *addr = (uint16_t *)initlst, ms; 160 | while(*addr != ILI9341_END) 161 | { 162 | if((*addr & ILI9341_DLY) != ILI9341_DLY) 163 | ili9341_write(*addr++); 164 | else 165 | { 166 | ms = (*addr++)&0x1ff; // strip delay time (ms) 167 | clkcnt_delayms(ms); 168 | } 169 | } 170 | } 171 | 172 | /* 173 | * opens a window into display mem for bitblt 174 | */ 175 | void ili9341_setAddrWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1) 176 | { 177 | ili9341_write(ILI9341_CASET | ILI9341_CMD); // Column addr set 178 | ili9341_write(x0>>8); 179 | ili9341_write(x0&0xff); // XSTART 180 | ili9341_write(x1>>8); 181 | ili9341_write(x1&0xff); // XEND 182 | 183 | ili9341_write(ILI9341_RASET | ILI9341_CMD); // Row addr set 184 | ili9341_write(y0>>8); 185 | ili9341_write(y0&0xff); // YSTART 186 | ili9341_write(y1>>8); 187 | ili9341_write(y1&0xff); // YEND 188 | 189 | ili9341_write(ILI9341_RAMWR | ILI9341_CMD); // write to RAM 190 | } 191 | 192 | /* 193 | * Convert HSV triple to RGB triple 194 | * use algorithm from 195 | * http://en.wikipedia.org/wiki/HSL_and_HSV#Converting_to_RGB 196 | */ 197 | void ili9341_hsv2rgb(uint8_t rgb[], uint8_t hsv[]) 198 | { 199 | uint16_t C; 200 | int16_t Hprime, Cscl; 201 | uint8_t hs, X, m; 202 | 203 | /* default */ 204 | rgb[0] = 0; 205 | rgb[1] = 0; 206 | rgb[2] = 0; 207 | 208 | /* calcs are easy if v = 0 */ 209 | if(hsv[2] == 0) 210 | return; 211 | 212 | /* C is the chroma component */ 213 | C = ((uint16_t)hsv[1] * (uint16_t)hsv[2])>>8; 214 | 215 | /* Hprime is fixed point with range 0-5.99 representing hue sector */ 216 | Hprime = (int16_t)hsv[0] * 6; 217 | 218 | /* get intermediate value X */ 219 | Cscl = (Hprime%512)-256; 220 | Cscl = Cscl < 0 ? -Cscl : Cscl; 221 | Cscl = 256 - Cscl; 222 | X = ((uint16_t)C * Cscl)>>8; 223 | 224 | /* m is value offset */ 225 | m = hsv[2] - C; 226 | 227 | /* get the hue sector (1 of 6) */ 228 | hs = (Hprime)>>8; 229 | 230 | /* map by sector */ 231 | switch(hs) 232 | { 233 | case 0: 234 | /* Red -> Yellow sector */ 235 | rgb[0] = C + m; 236 | rgb[1] = X + m; 237 | rgb[2] = m; 238 | break; 239 | 240 | case 1: 241 | /* Yellow -> Green sector */ 242 | rgb[0] = X + m; 243 | rgb[1] = C + m; 244 | rgb[2] = m; 245 | break; 246 | 247 | case 2: 248 | /* Green -> Cyan sector */ 249 | rgb[0] = m; 250 | rgb[1] = C + m; 251 | rgb[2] = X + m; 252 | break; 253 | 254 | case 3: 255 | /* Cyan -> Blue sector */ 256 | rgb[0] = m; 257 | rgb[1] = X + m; 258 | rgb[2] = C + m; 259 | break; 260 | 261 | case 4: 262 | /* Blue -> Magenta sector */ 263 | rgb[0] = X + m; 264 | rgb[1] = m; 265 | rgb[2] = C + m; 266 | break; 267 | 268 | case 5: 269 | /* Magenta -> Red sector */ 270 | rgb[0] = C + m; 271 | rgb[1] = m; 272 | rgb[2] = X + m; 273 | break; 274 | } 275 | } 276 | 277 | /* 278 | * Convert 8-bit (each) R,G,B to 16-bit rgb565 packed color 279 | */ 280 | uint16_t ili9342_Color565(uint8_t r, uint8_t g, uint8_t b) 281 | { 282 | return ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3); 283 | } 284 | 285 | /* 286 | * fast color fill 287 | */ 288 | void ili9342_fillcolor(uint16_t color, uint32_t sz) 289 | { 290 | uint8_t lo = color&0xff, hi = color>>8; 291 | 292 | while(sz--) 293 | { 294 | /* wait for tx ready */ 295 | spi_tx_wait(ili9341_spi); 296 | 297 | /* transmit hi byte */ 298 | ili9341_spi->SPITXDR = hi; 299 | 300 | /* wait for tx ready */ 301 | spi_tx_wait(ili9341_spi); 302 | 303 | /* transmit hi byte */ 304 | ili9341_spi->SPITXDR = lo; 305 | } 306 | } 307 | 308 | /* 309 | * draw single pixel 310 | */ 311 | void ili9341_drawPixel(int16_t x, int16_t y, uint16_t color) 312 | { 313 | 314 | if((x < 0) ||(x >= ILI9341_TFTWIDTH) || (y < 0) || (y >= ILI9341_TFTHEIGHT)) return; 315 | 316 | ili9341_setAddrWindow(x,y,x+1,y+1); 317 | 318 | ILI9341_DC_DATA(); 319 | spi_cs_low(ili9341_spi); 320 | ili9342_fillcolor(color, 1); 321 | spi_cs_high(ili9341_spi); 322 | } 323 | 324 | /* 325 | * abs() helper function for line drawing 326 | */ 327 | int16_t ili9341_abs(int16_t x) 328 | { 329 | return (x<0) ? -x : x; 330 | } 331 | 332 | /* 333 | * swap() helper function for line drawing 334 | */ 335 | void ili9341_swap(int16_t *z0, int16_t *z1) 336 | { 337 | int16_t temp = *z0; 338 | *z0 = *z1; 339 | *z1 = temp; 340 | } 341 | 342 | /* 343 | * Bresenham line draw routine swiped from Wikipedia 344 | */ 345 | void ili9341_drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, 346 | uint16_t color) 347 | { 348 | int8_t steep; 349 | int16_t deltax, deltay, error, ystep, x, y; 350 | 351 | /* flip sense 45deg to keep error calc in range */ 352 | steep = (ili9341_abs(y1 - y0) > ili9341_abs(x1 - x0)); 353 | 354 | if(steep) 355 | { 356 | ili9341_swap(&x0, &y0); 357 | ili9341_swap(&x1, &y1); 358 | } 359 | 360 | /* run low->high */ 361 | if(x0 > x1) 362 | { 363 | ili9341_swap(&x0, &x1); 364 | ili9341_swap(&y0, &y1); 365 | } 366 | 367 | /* set up loop initial conditions */ 368 | deltax = x1 - x0; 369 | deltay = ili9341_abs(y1 - y0); 370 | error = deltax/2; 371 | y = y0; 372 | if(y0 < y1) 373 | ystep = 1; 374 | else 375 | ystep = -1; 376 | 377 | /* loop x */ 378 | for(x=x0;x<=x1;x++) 379 | { 380 | /* plot point */ 381 | if(steep) 382 | /* flip point & plot */ 383 | ili9341_drawPixel(y, x, color); 384 | else 385 | /* just plot */ 386 | ili9341_drawPixel(x, y, color); 387 | 388 | /* update error */ 389 | error = error - deltay; 390 | 391 | /* update y */ 392 | if(error < 0) 393 | { 394 | y = y + ystep; 395 | error = error + deltax; 396 | } 397 | } 398 | } 399 | 400 | /* 401 | * fast vert line 402 | */ 403 | void ili9341_drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color) 404 | { 405 | // clipping 406 | if((x >= ILI9341_TFTWIDTH) || (y >= ILI9341_TFTHEIGHT)) return; 407 | if((y+h-1) >= ILI9341_TFTHEIGHT) h = ILI9341_TFTHEIGHT-y; 408 | ili9341_setAddrWindow(x, y, x, y+h-1); 409 | 410 | ILI9341_DC_DATA(); 411 | spi_cs_low(ili9341_spi); 412 | ili9342_fillcolor(color, h); 413 | spi_cs_high(ili9341_spi); 414 | } 415 | 416 | /* 417 | * fast horiz line 418 | */ 419 | void ili9341_drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color) 420 | { 421 | // clipping 422 | if((x >= ILI9341_TFTWIDTH) || (y >= ILI9341_TFTHEIGHT)) return; 423 | if((x+w-1) >= ILI9341_TFTWIDTH) w = ILI9341_TFTWIDTH-x; 424 | ili9341_setAddrWindow(x, y, x+w-1, y); 425 | 426 | ILI9341_DC_DATA(); 427 | spi_cs_low(ili9341_spi); 428 | ili9342_fillcolor(color, w); 429 | spi_cs_high(ili9341_spi); 430 | } 431 | 432 | /* 433 | * empty rect 434 | */ 435 | void ili9341_emptyRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) 436 | { 437 | /* top & bottom */ 438 | ili9341_drawFastHLine(x, y, w, color); 439 | ili9341_drawFastHLine(x, y+h-1, w, color); 440 | 441 | /* left & right - don't redraw corners */ 442 | ili9341_drawFastVLine(x, y+1, h-2, color); 443 | ili9341_drawFastVLine(x+w-1, y+1, h-2, color); 444 | } 445 | 446 | /* 447 | * fill a rectangle 448 | */ 449 | void ili9341_fillRect(int16_t x, int16_t y, int16_t w, int16_t h, 450 | uint16_t color) 451 | { 452 | // clipping 453 | if((x >= ILI9341_TFTWIDTH) || (y >= ILI9341_TFTHEIGHT)) return; 454 | if((x + w - 1) >= ILI9341_TFTWIDTH) w = ILI9341_TFTWIDTH - x; 455 | if((y + h - 1) >= ILI9341_TFTHEIGHT) h = ILI9341_TFTHEIGHT - y; 456 | 457 | ili9341_setAddrWindow(x, y, x+w-1, y+h-1); 458 | 459 | ILI9341_DC_DATA(); 460 | spi_cs_low(ili9341_spi); 461 | ili9342_fillcolor(color, h*w); 462 | spi_cs_high(ili9341_spi); 463 | } 464 | 465 | /* 466 | * fill screen w/ single color 467 | */ 468 | void ili9341_fillScreen(uint16_t color) 469 | { 470 | ili9341_fillRect(0, 0, 240, 320, color); 471 | } 472 | 473 | /* 474 | * Draw character direct to the display 475 | */ 476 | void ili9341_drawchar(int16_t x, int16_t y, uint8_t chr, 477 | uint16_t fg, uint16_t bg) 478 | { 479 | uint16_t i, j, col; 480 | uint8_t d; 481 | 482 | ili9341_setAddrWindow(x, y, x+7, y+7); 483 | 484 | ILI9341_DC_DATA(); 485 | spi_cs_low(ili9341_spi); 486 | for(i=0;i<8;i++) 487 | { 488 | d = fontdata[(chr<<3)+i]; 489 | for(j=0;j<8;j++) 490 | { 491 | if(d&0x80) 492 | col = fg; 493 | else 494 | col = bg; 495 | 496 | ili9342_fillcolor(col, 1); 497 | 498 | // next bit 499 | d <<= 1; 500 | } 501 | } 502 | spi_cs_high(ili9341_spi); 503 | } 504 | 505 | // draw a string to the display 506 | void ili9341_drawstr(int16_t x, int16_t y, char *str, 507 | uint16_t fg, uint16_t bg) 508 | { 509 | uint8_t c; 510 | 511 | while((c=*str++)) 512 | { 513 | ili9341_drawchar(x, y, c, fg, bg); 514 | x += 8; 515 | if(x>ILI9341_TFTWIDTH) 516 | break; 517 | } 518 | } 519 | 520 | /* 521 | * send a buffer to the LCD 522 | */ 523 | void ili9341_blit(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t *src) 524 | { 525 | // clipping 526 | if((x >= ILI9341_TFTWIDTH) || (y >= ILI9341_TFTHEIGHT)) return; 527 | if((x + w - 1) >= ILI9341_TFTWIDTH) w = ILI9341_TFTWIDTH - x; 528 | if((y + h - 1) >= ILI9341_TFTHEIGHT) h = ILI9341_TFTHEIGHT - y; 529 | 530 | ili9341_setAddrWindow(x, y, x+w-1, y+h-1); 531 | 532 | ILI9341_DC_DATA(); 533 | spi_cs_low(ili9341_spi); 534 | spi_transmit(ili9341_spi, (uint8_t *)src, h*w*sizeof(uint16_t)); 535 | spi_cs_high(ili9341_spi); 536 | } 537 | 538 | --------------------------------------------------------------------------------