aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAlexis Hovorka <[email protected]>2022-12-01 20:19:53 -0700
committerAlexis Hovorka <[email protected]>2022-12-01 20:19:53 -0700
commit110204d48f34aa8a034dd182aa62503ed2a93f30 (patch)
tree4032b80e989464e413fd6151b2062ba5f03965c7
parent07a0b6ab99a389d7d5abb73c903d99813df8e1d1 (diff)
[feat] Solidify IO address map, implement SPI
-rw-r--r--io.notes92
-rw-r--r--rtl/boot.mem2
-rw-r--r--rtl/southbridge.v119
-rw-r--r--rtl/spi_controller.v61
-rw-r--r--rtl/top.v89
-rw-r--r--src/echo.prog4
-rw-r--r--src/f1.f16
-rw-r--r--src/f1.prog6
-rw-r--r--src/flash.f1137
-rw-r--r--src/print.prog8
10 files changed, 431 insertions, 93 deletions
diff --git a/io.notes b/io.notes
index 49b54c8..1887bf5 100644
--- a/io.notes
+++ b/io.notes
@@ -1,39 +1,42 @@
-GPIO (TODO separate IO?)
-- i 4 switches
-- i 7 buttons
-- o8 leds
-- o1 esp enable
-- o1 piezo (TODO ADC?)
-- o1 tft reset
-- o1 inky reset
-- o1 uart0 select
-- o1 uart1 select
-SPI ctl
-- flash
-- sd
-- adc
-- tft
-- inky cmd
-- inky data
-SPI dat
-- also busy/wait signal from tft/inky
-I2C0 internal
-I2C1 external (or can they be wired together?)
-UART0 cmd (ftdi/ext)
-UART0 dat
-UART1 cmd (esp)
-UART1 dat
-PS/2
-Neopixels
-
-Clocks
-Watchdog
-- Reset "password"?
-- Action (interrupt/reset)
-
-TRNG?
-
-DMA
+TODO:
+- TRNG?
+- PS/2
+- Neopixels
+- DMA
+- Clocks
+- Watchdog
+ - Reset "password"?
+ - Action (interrupt/reset)
+- Interrupt enable/config
+
+Assigned addresses:
+
+6 I2C0 internal
+7 I2C1 external (or can they be wired together?)
+8 UART0 cmd (ftdi/ext)
+9 UART0 dat
+A UART1 cmd (esp)
+B UART1 dat
+C SPI ctl
+ - 1 flash
+ - 2 sd
+ - 3 tft
+ - 4 inky cmd
+ - 5 inky data
+ - 6 adc
+D SPI dat
+ - also incorporate busy/wait signal from tft/inky
+E GPIO0
+ - o1 esp enable
+ - o1 piezo (TODO ADC?)
+ - o1 tft reset
+ - o1 inky reset
+ - o1 uart0 select
+ - o1 uart1 select
+F GPIO1
+ - i4 switches
+ - i7 buttons
+ - o8 leds
-----------------------
@@ -46,10 +49,25 @@ UART has
- two interrupts (rx, tx)
- two registers (ctl, data)
-https://stnolting.github.io/neorv32/#_primary_universal_asynchronous_receiver_and_transmitter_uart0
+ - baud counter / clock prescaler
+ - fifo status (half/full)
+ - enable rts/cts
+ - cts state
+ - parity (none/odd/even/space)
+ - stop bits (1/2)
+ - interrupt config (tx/rx half/full)
+ - tx busy
+ - enable?
- fifo?
+NEORV32 baud config:
+
+Prescaler 0b000 0b001 0b010 0b011 0b100 0b101 0b110 0b111
+ 2 4 8 64 128 1024 2048 4096
+
+Baud rate = (fmain[Hz] / clock_prescaler) / (baud_prsc + 1)
+
-----------------------
SPI has
diff --git a/rtl/boot.mem b/rtl/boot.mem
index 97bb41c..d7b0702 100644
--- a/rtl/boot.mem
+++ b/rtl/boot.mem
@@ -20,7 +20,7 @@
3C00 // 17000 \ addi 7,0,00
// Read byte from serial
-647E // 3107E \ lw 1,0,@uart ; read
+6479 // 31079 \ lw 1,0,@uart ; read
C4FE // 6117E \ blz 1,-2 ; if busy, loop
0CA2 // 03122 \ xor 3,1,2 ; get diff
0D83 // 03303 \ msbl 3,3 ; get upper diff
diff --git a/rtl/southbridge.v b/rtl/southbridge.v
index 2d3544a..49f22ad 100644
--- a/rtl/southbridge.v
+++ b/rtl/southbridge.v
@@ -9,24 +9,59 @@ module SouthBridge
input wire [15:0] from_nb,
output reg [15:0] to_nb,
+ input wire from_ftdi_uart,
+ output wire to_ftdi_uart,
+
+ output wire oled_csn,
+ output wire oled_clk,
+ output wire oled_mosi,
+ output wire oled_dc,
+ output wire oled_resn, // TODO GPIO0
+
+ output wire flash_csn,
+ output wire flash_clk,
+ output wire flash_mosi,
+ input wire flash_miso,
+
+ output wire sd_csn,
+ output wire sd_clk,
+ output wire sd_di,
+ input wire sd_do,
+
+ output wire adc_csn,
+ output wire adc_sclk,
+ output wire adc_mosi,
+ input wire adc_miso,
+
input wire [3:0] sw,
input wire [6:0] btn,
- output reg [7:0] led,
-
- input wire from_ftdi_uart,
- output wire to_ftdi_uart);
+ output reg [7:0] led);
localparam CLOCK_RATE_HZ = 25_000_000;
localparam RST_SEC = 1;
- localparam ADDR_BLINKEN = 16'hXXXF;
- localparam ADDR_FTDI_UART = 16'hXXXE;
+ localparam ADDR_GPIO1 = 16'hXXXF;
+ localparam ADDR_GPIO0 = 16'hXXXE;
+ localparam ADDR_SPI_DAT = 16'hXXXD;
+ localparam ADDR_SPI_CTL = 16'hXXXC;
+ localparam ADDR_UART1_DAT = 16'hXXXB;
+ localparam ADDR_UART1_CTL = 16'hXXXA;
+ localparam ADDR_UART0_DAT = 16'hXXX9;
+ localparam ADDR_UART0_CTL = 16'hXXX8;
+ localparam ADDR_I2C1 = 16'hXXX7; // TODO Necessary?
+ localparam ADDR_I2C0 = 16'hXXX6;
+
+ localparam SPI_FLASH_CS = 8'd1;
+ localparam SPI_SD_CS = 8'd2;
+ localparam SPI_TFT_CS = 8'd3;
+ localparam SPI_OLED_CS = 8'b0000_010X;
+ localparam SPI_ADC_CS = 8'd6;
reg just_wrote = 0;
reg [15:0] just_wrote_to = 0;
// ---------------------------------------------------------------------------
- // Blinkenlights
+ // GPIO1 - Blinkenlights
wire [6:0] btn_db;
debouncer dbO(clk, btn[1], btn_db[0]);
@@ -50,12 +85,62 @@ module SouthBridge
always @(posedge clk) if (rst_out) led <= 0;
else if (rst_cnt >= RST_BLINK_CLK) led <= 8'hFF;
- else if (nb_we && nb_addr == ADDR_BLINKEN) led <= from_nb[7:0];
+ else if (nb_we && nb_addr == ADDR_GPIO1) led <= from_nb[7:0];
+
+ wire [15:0] gpio1_read = {sw, 5'd0, btn_db};
+
+ // ---------------------------------------------------------------------------
+ // SPI
+
+ reg [7:0] spi_cs = 0;
+ reg [7:0] spi_send = 0;
+ wire [7:0] spi_recv;
+ wire spi_go, spi_clk, spi_mosi, spi_busy;
+
+ assign flash_csn = spi_cs != SPI_FLASH_CS;
+ assign flash_clk = spi_clk;
+ assign flash_mosi = spi_mosi;
+
+ assign sd_csn = spi_cs != SPI_SD_CS;
+ assign sd_clk = spi_clk;
+ assign sd_di = spi_mosi;
+
+ assign oled_csn = spi_cs != SPI_OLED_CS;
+ assign oled_dc = spi_cs[0];
+ assign oled_clk = spi_clk;
+ assign oled_mosi = spi_mosi;
+
+ assign adc_csn = spi_cs != SPI_ADC_CS;
+ assign adc_sclk = spi_clk;
+ assign adc_mosi = spi_mosi;
+
+ reg spi_miso;
+ always @* casex (spi_cs)
+ SPI_FLASH_CS: spi_miso = flash_miso;
+ SPI_SD_CS: spi_miso = sd_do;
+ SPI_ADC_CS: spi_miso = adc_miso;
+ default: spi_miso = 0;
+ endcase
+
+ // TODO Extra runtime configurability
+ wire spi_clk, spi_mosi, spi_busy;
+ spi_controller spi(.clk(clk), .rst(rst_out), .go(spi_go),
+ .i_data(spi_send), .o_data(spi_recv), .busy(spi_busy),
+ .spi_clk(spi_clk), .spi_mosi(spi_mosi), .spi_miso(spi_miso));
+
+ always @(posedge clk) begin
+ if (nb_we && nb_addr == ADDR_SPI_CTL) spi_cs <= from_nb[7:0];
+ if (nb_we && nb_addr == ADDR_SPI_DAT) spi_send <= from_nb[7:0];
+ if (rst_out) spi_cs <= 0;
+ end
+
+ assign spi_go = just_wrote && (just_wrote_to == ADDR_SPI_DAT);
- wire [15:0] blinken_read = {sw, 5'd0, btn_db};
+ wire [15:0] spi_dat_read = {spi_busy, 7'd0, spi_recv};
+ wire [15:0] spi_ctl_read = {8'd0, spi_cs};
// ---------------------------------------------------------------------------
- // FTDI UART
+ // UART0 - FTDI
wire frx_avail; // RX data available (strobe, TODO use for interrupt)
wire [7:0] frx_data; // Data received
@@ -63,14 +148,14 @@ module SouthBridge
wire ftx_stb; // Strobe to send data
wire ftx_busy; // Sending
- localparam FTDI_BAUD_RATE = 115_200;
+ localparam FTDI_BAUD_RATE = 115_200; // TODO make runtime configurable
localparam FTDI_CLK_PER_BAUD = CLOCK_RATE_HZ / FTDI_BAUD_RATE;
UartTX #(FTDI_CLK_PER_BAUD[23:0]) ftx(clk, ftx_stb, ftx_data, to_ftdi_uart, ftx_busy);
UartRX #(FTDI_CLK_PER_BAUD[23:0]) frx(clk, rst_out, from_ftdi_uart, frx_avail, frx_data);
- always @(posedge clk) if (nb_we && nb_addr == ADDR_FTDI_UART) ftx_data <= from_nb[7:0];
- assign ftx_stb = just_wrote && (just_wrote_to == ADDR_FTDI_UART);
+ always @(posedge clk) if (nb_we && nb_addr == ADDR_UART0_DAT) ftx_data <= from_nb[7:0];
+ assign ftx_stb = just_wrote && (just_wrote_to == ADDR_UART0_DAT);
reg [6:0] frx_cnt = 0;
always @(posedge clk) begin
@@ -78,13 +163,15 @@ module SouthBridge
if (frx_avail) frx_cnt <= frx_cnt + 1;
end
- wire [15:0] ftdi_uart_read = {ftx_busy, frx_cnt, frx_data};
+ wire [15:0] uart0_dat_read = {ftx_busy, frx_cnt, frx_data};
// ---------------------------------------------------------------------------
always @(posedge clk) casex (nb_addr)
- ADDR_BLINKEN: to_nb <= blinken_read;
- ADDR_FTDI_UART: to_nb <= ftdi_uart_read;
+ ADDR_GPIO1: to_nb <= gpio1_read;
+ ADDR_SPI_DAT: to_nb <= spi_dat_read;
+ ADDR_SPI_CTL: to_nb <= spi_ctl_read;
+ ADDR_UART0_DAT: to_nb <= uart0_dat_read;
default: to_nb <= 0;
endcase
diff --git a/rtl/spi_controller.v b/rtl/spi_controller.v
new file mode 100644
index 0000000..09ddb86
--- /dev/null
+++ b/rtl/spi_controller.v
@@ -0,0 +1,61 @@
+`default_nettype none
+
+module spi_controller
+#(parameter CPOL = 0,
+ parameter CPHA = 0)
+ (input wire clk,
+ input wire rst,
+ input wire go,
+ input wire [7:0] i_data,
+ output reg [7:0] o_data = 8'h00,
+ output wire busy,
+
+ output wire spi_clk,
+ output wire spi_mosi,
+ input wire spi_miso);
+
+ reg [3:0] state = 4'h0;
+ reg [7:0] shift_o = 8'h00;
+ reg [7:0] shift_i = 8'h00;
+
+ wire [7:0] shifted_o = {shift_o[6:0], 1'b0};
+ wire [7:0] shifted_i = {shift_i[6:0], spi_miso};
+
+ assign busy = |state;
+ assign spi_mosi = shift_o[7];
+
+ wire spi_clk_v;
+ generate
+ if (CPOL) assign spi_clk_v = ~(busy && state[0]);
+ else assign spi_clk_v = (busy && state[0]);
+ endgenerate
+
+ generate
+ if (CPHA) assign spi_clk = spi_clk_v;
+ else begin
+ reg spi_clk_d = CPOL;
+ assign spi_clk = spi_clk_d;
+ always @(posedge clk)
+ spi_clk_d <= rst? CPOL : spi_clk_v;
+ end
+ endgenerate
+
+ always @(posedge clk) begin
+ if (rst) begin
+ shift_i <= 8'h00;
+ shift_o <= 8'h00;
+ o_data <= 8'h00;
+ state <= 4'h0;
+
+ end else if (busy) begin
+ state <= state - 4'h1;
+ if (~state[0]) shift_o <= shifted_o;
+ if ( state[0]) shift_i <= shifted_i;
+ if (state == 4'h1) o_data <= shifted_i;
+
+ end else if (go) begin
+ state <= 4'hF;
+ shift_o <= i_data;
+ end
+ end
+endmodule
diff --git a/rtl/top.v b/rtl/top.v
index cf174e7..0fd0348 100644
--- a/rtl/top.v
+++ b/rtl/top.v
@@ -8,8 +8,8 @@
`include "debouncer.v"
`include "uart_rx.v"
`include "uart_tx.v"
+`include "spi_controller.v"
//`include "i2c_controller.v"
-//`include "spi_controller.v"
//`include "ps2_controller.v"
`include "southbridge.v"
@@ -21,25 +21,34 @@ module top
input wire ftdi_txd,
output wire ftdi_rxd,
-
- //output wire oled_csn,
- //output wire oled_clk,
- //output wire oled_mosi,
- //output wire oled_dc,
- //output wire oled_resn,
- //output wire oled_bl,
-
- //output wire flash_csn,
- ////output wire flash_clk, // Special, see below
- //output wire flash_mosi,
- //input wire flash_miso,
- //output wire flash_holdn,
- //output wire flash_wpn,
-
- //output wire sd_csn,
- //output wire sd_clk,
- //output wire sd_di,
- //input wire sd_do,
+ //input wire ftdi_nrts,
+ //input wire ftdi_ndtr,
+ //input wire ftdi_txden,
+ //input wire ftdi_nrxled,
+
+ output wire oled_csn,
+ output wire oled_clk,
+ output wire oled_mosi,
+ output wire oled_dc,
+ output wire oled_resn,
+ output wire oled_bl,
+
+ output wire flash_csn,
+ //output wire flash_clk, // Special, see below
+ output wire flash_mosi,
+ input wire flash_miso,
+ output wire flash_holdn,
+ output wire flash_wpn,
+
+ output wire sd_csn,
+ output wire sd_clk,
+ output wire sd_di,
+ input wire sd_do,
+
+ output wire adc_csn,
+ output wire adc_sclk,
+ output wire adc_mosi,
+ input wire adc_miso,
//// Used as PS/2
//input wire usb_fpga_bd_dp,
@@ -50,14 +59,31 @@ module top
//inout wire gpdi_scl,
//inout wire gpdi_sda,
+ //output wire sdram_clk,
+ //output wire sdram_cke,
+ //output wire sdram_csn,
+ //output wire sdram_wen,
+ //output wire sdram_rasn,
+ //output wire sdram_casn,
+ //output wire sdram_a[12:0],
+ //output wire sdram_ba[1:0],
+ //output wire sdram_dqm[1:0],
+ //inout wire sdram_d[15:0],
+
+ //output wire shutdown,
+
output wire wifi_en);
assign wifi_en = 0;
- //wire flash_clk;
- //wire flash_tri = 1'b0;
- //USRMCLK u1 (.USRMCLKI(flash_clk), .USRMCLKTS(flash_tri));
- //// Flash clock pin is special because it's used for FPGA config
- //// This module lets us use it as a normal output pin
+ wire flash_clk;
+ wire flash_tri = 1'b0;
+ USRMCLK u1 (.USRMCLKI(flash_clk), .USRMCLKTS(flash_tri));
+ // Flash clock pin is special because it's used for FPGA config
+ // This module lets us use it as a normal output pin
+
+ assign flash_holdn = 1;
+ assign flash_wpn = 1;
+ assign oled_bl = 1;
// -------------------------------------------------------------------
@@ -84,7 +110,16 @@ module top
SouthBridge sb(.clk(clk), .rst_out(rst), .nb_we(sb_we),
.nb_addr(sb_addr), .from_nb(nb_to_sb), .to_nb(sb_to_nb),
- .sw(sw), .btn(btn), .led(led), // Blinkenlights
- .from_ftdi_uart(ftdi_txd), .to_ftdi_uart(ftdi_rxd));
+ // SPI
+ .flash_csn(flash_csn), .flash_clk(flash_clk),
+ .flash_mosi(flash_mosi), .flash_miso(flash_miso),
+ .sd_csn(sd_csn), .sd_clk(sd_clk), .sd_di(sd_di), .sd_do(sd_do),
+ .oled_csn(oled_csn), .oled_clk(oled_clk), .oled_mosi(oled_mosi),
+ .oled_dc(oled_dc), .oled_resn(oled_resn),
+ .adc_csn(adc_csn), .adc_sclk(adc_sclk),
+ .adc_mosi(adc_mosi), .adc_miso(adc_miso),
+
+ .from_ftdi_uart(ftdi_txd), .to_ftdi_uart(ftdi_rxd), // UART0
+ .sw(sw), .btn(btn), .led(led)); // GPIO1
endmodule
diff --git a/src/echo.prog b/src/echo.prog
index fe3f644..ca38856 100644
--- a/src/echo.prog
+++ b/src/echo.prog
@@ -1,9 +1,9 @@
-3107E // lw 1,0,@uart
+31078 // lw 1,0,@uart
6117E // blz 1,-2
03122 // xor 3,1,2
03303 // msbl 3,3
6237B // bz 3,-5
12100 // mv 2,1
4107F // sw 1,0,@led
-4107E // sw 1,0,@uart
+41078 // sw 1,0,@uart
67077 // j -9
diff --git a/src/f1.f1 b/src/f1.f1
index bc39976..ec1f649 100644
--- a/src/f1.f1
+++ b/src/f1.f1
@@ -12,7 +12,7 @@
:getchar // -> char
3203F // lw 2,0,@lastChar
-3107E // lw 1,0,@uart
+31079 // lw 1,0,@uart
6117E // blz 1,-2
03122 // xor 3,1,2
03303 // msbl 3,3
@@ -24,9 +24,9 @@
// --------------------------------------------
:putchar // (char n)
-3207E // lw 2,0,@uart
+32079 // lw 2,0,@uart
6127E // blz 2,-2
-4107E // sw 1,0,@uart
+41079 // sw 1,0,@uart
50700 // ret
// --------------------------------------------
diff --git a/src/f1.prog b/src/f1.prog
index 061b885..784033d 100644
--- a/src/f1.prog
+++ b/src/f1.prog
@@ -14,7 +14,7 @@
// 0040
//:getchar // -> char
3203F // lw 2,0,@lastChar
-3107E // lw 1,0,@uart
+31079 // lw 1,0,@uart
6117E // blz 1,-2
03122 // xor 3,1,2
03303 // msbl 3,3
@@ -26,9 +26,9 @@
// 0049
//:putchar // (char n)
-3207E // lw 2,0,@uart
+32079 // lw 2,0,@uart
6127E // blz 2,-2
-4107E // sw 1,0,@uart
+41079 // sw 1,0,@uart
50700 // ret
diff --git a/src/flash.f1 b/src/flash.f1
new file mode 100644
index 0000000..1db83c1
--- /dev/null
+++ b/src/flash.f1
@@ -0,0 +1,137 @@
+// flash.f1
+// --------------------------------------------
+//
+// System config flash access test
+//
+// --------------------------------------------
+
+:busywait
+1107F // addi 1,0,-1 // Set up 2s timer
+22005 // lui 2,0100
+1223F // addi 2,2,3F
+
+// Sleep for ~2s
+1117F // addi 1,1,-1
+6517E // bnz 1,-2
+1227F // addi 2,2,-1
+6527C // bnz 2,-2
+
+50700 // ret
+
+// --------------------------------------------
+
+:putchar // (char n)
+32079 // lw 2,0,@uart
+6127E // blz 2,-2
+41079 // sw 1,0,@uart
+50700 // ret
+
+// --------------------------------------------
+
+:xchgspi // (char tx) -> char rx
+4107D // sw 1,0,@spi_dat
+3107D // lw 1,0,@spi_dat
+6117E // blz 1,-2
+01100 // lsbl 1,1
+50700 // ret
+
+:dualspi // (word tx) -> word rx
+47600 // | push 7
+1667F // +-------
+
+02100 // lsbl 2,1
+01103 // msbl 1,1
+@xchgspi
+01122 // xor 1,1,2
+02122 // xor 2,1,2
+01122 // xor 1,1,2
+@xchgspi
+02207 // swpb 2,2
+01121 // or 1,1,2
+
+16601 // +------
+37600 // | pop 7
+50700 // ret
+
+// --------------------------------------------
+
+:writeenableflash
+47600 // | push 7
+1667F // +-------
+
+// Set CS = 1
+11001 // addi 1,0,01
+4107C // sw 1,0,@spi_ctl
+
+// Send write enable command
+11006 // addi 1,0,06
+@xchgspi
+
+// Set CS = 0
+4007C // sw 0,0,@spi_ctl
+
+16601 // +------
+37600 // | pop 7
+50700 // ret
+
+// --------------------------------------------
+
+:start
+2677F // lui 6,FFC0 // Set up stack pointer
+@busywait
+
+
+//@writeenableflash
+//11001 // addi 1,0,01 // Set CS = 1
+//4107C // sw 1,0,@spi_ctl
+//11012 // addi 1,0,12 // Send write page command
+//@xchgspi
+//21001 // lui 1,0040 // Send address
+//@dualspi
+//11000 // mv 1,0
+//@dualspi
+//2167A // lui 1,DE80 // Send words
+//1112D // addi 1,1,2D
+//@dualspi
+//2157B // lui 1,BEC0 // Send words
+//1112F // addi 1,1,2F
+//@dualspi
+//4007C // sw 0,0,@spi_ctl // Set CS = 0
+//@busywait
+
+
+//@writeenableflash
+//11001 // addi 1,0,01 // Set CS = 1
+//4107C // sw 1,0,@spi_ctl
+//11021 // addi 1,0,21 // Send erase sector command
+//@xchgspi
+//21001 // lui 1,0040 // Send address
+//@dualspi
+//11000 // mv 1,0
+//@dualspi
+//4007C // sw 0,0,@spi_ctl // Set CS = 0
+//@busywait
+
+
+11001 // addi 1,0,01 // Set CS = 1
+4107C // sw 1,0,@spi_ctl
+11013 // addi 1,0,13 // Send read command
+@xchgspi
+21001 // lui 1,0040 // Send address
+@dualspi
+11000 // mv 1,0
+@dualspi
+14010 // addi 4,0,10 // Read bytes
+11000 // mv 1,0
+@xchgspi
+@putchar
+1447F // addi 4,4,-1
+65479 // bnz 4,-7
+4007C // sw 0,0,@spi_ctl // Set CS = 0
+
+
+6707F // wfi
+
+
+@start
+6707D // j -3
diff --git a/src/print.prog b/src/print.prog
index ace5e50..3bc7552 100644
--- a/src/print.prog
+++ b/src/print.prog
@@ -5,19 +5,19 @@
31200 // lw 1,2,0
62105 // bez 1,@cont
12201 // addi 2,2,1
-4107E // sw 1,0,@uart
-3107E // lw 1,0,@uart
+41079 // sw 1,0,@uart
+31079 // lw 1,0,@uart
6117E // blz 1,-2
67079 // j -7
-3107E // lw 1,0,@uart
+31079 // lw 1,0,@uart
6117E // blz 1,-2
03122 // xor 3,1,2
03303 // msbl 3,3
6237B // bz 3,-5
12100 // mv 2,1
4107F // sw 1,0,@led
-4107E // sw 1,0,@uart
+41079 // sw 1,0,@uart
67077 // j -9
// "Hello, RISC-16! :)\r\n"