Start of public OpenTitan development history
Code contributors:
Alex Bradbury <asb@lowrisc.org>
Cindy Chen <chencindy@google.com>
Eunchan Kim <eunchan@google.com>
Gaurang Chitroda <gaurangg@google.com>
Mark Hayter <mark.hayter@gmail.com>
Michael Schaffner <msf@google.com>
Miguel Osorio <miguelosorio@google.com>
Nils Graf <nilsg@google.com>
Philipp Wagner <phw@lowrisc.org>
Pirmin Vogel <vogelpi@lowrisc.org>
Ram Babu Penugonda <rampenugonda@google.com>
Scott Johnson <scottdj@google.com>
Shail Kushwah <kushwahs@google.com>
Srikrishna Iyer <sriyer@google.com>
Steve Nelson <Steve.Nelson@wdc.com>
Tao Liu <taliu@google.com>
Timothy Chen <timothytim@google.com>
Tobias Wölfel <tobias.woelfel@mailbox.org>
Weicai Yang <weicai@google.com>
diff --git a/sw/lib/Makefile b/sw/lib/Makefile
new file mode 100644
index 0000000..922cd58
--- /dev/null
+++ b/sw/lib/Makefile
@@ -0,0 +1,61 @@
+# Copyright lowRISC contributors.
+# Licensed under the Apache License, Version 2.0, see LICENSE for details.
+# SPDX-License-Identifier: Apache-2.0
+#
+# Generate a baremetal application for the microcontroller
+
+DIF_SRCS = uart.c gpio.c spi_device.c flash_ctrl.c hmac.c usbdev.c rv_timer.c
+EXT_SRCS = usb_controlep.c usb_simpleserial.c irq.c handler.c
+EXT_ASMS = irq_vectors.S
+GENHDRS := ${DIF_SRCS:.c=_regs.h}
+GENHDR_BASE := ${DIF_SRCS:.c=}
+ARCH = rv32imc
+# ARCH = rv32im # to disable compressed instructions
+
+RV_TOOLS ?= /tools/riscv/bin/
+
+CC := ${RV_TOOLS}/riscv32-unknown-elf-gcc
+CFLAGS ?= -Wall -g -Os -march=$(ARCH) -mabi=ilp32 -static -mcmodel=medany \
+ -fvisibility=hidden -nostdlib -nostartfiles
+
+ifeq ($(SIM),1)
+ CFLAGS += -DSIMULATION
+endif
+
+AR := $(subst gcc,ar,$(wordlist 1,1,$(CC)))
+ARFLAGS := rc
+
+REGTOOL = ../../util/regtool.py
+
+OBJS := ${DIF_SRCS:.c=.o} ${EXT_SRCS:.c=.o} ${EXT_ASMS:.S=.o}
+DEPS = $(OBJS:%.o=%.d)
+
+OUTFILES = libot.a
+
+$(OUTFILES): $(OBJS)
+ $(AR) $(ARFLAGS) $@ $(OBJS)
+
+all: $(OUTFILES)
+
+%.o: %.c %.S
+ $(CC) $(CFLAGS) -MMD -c $(INCS) -o $@ $<
+
+define header_gen
+ $1.c: $1_regs.h
+
+ $1_regs.h: ../../hw/ip/$1/doc/*.hjson
+ if [ -f ../../hw/ip/$1/doc/$1.hjson ]; then \
+ $(REGTOOL) -D -o $1_regs.h ../../hw/ip/$1/doc/$1.hjson ; \
+ else \
+ $(REGTOOL) -D -o $1_regs.h ../../hw/ip/$1/doc/$1_reg.hjson ; \
+ fi
+endef
+$(foreach f,$(GENHDR_BASE),$(eval $(call header_gen,$f)))
+
+-include $(DEPS)
+
+clean:
+ $(RM) *.o *.d $(GENHDRS)
+
+distclean: clean
+ $(RM) $(OUTFILES)
diff --git a/sw/lib/common.h b/sw/lib/common.h
new file mode 100644
index 0000000..2b989f2
--- /dev/null
+++ b/sw/lib/common.h
@@ -0,0 +1,45 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _COMMON_H_
+#define _COMMON_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+
+// Adjust clock speed to match simulation
+//#define SIMULATION
+
+#ifdef SIMULATION
+#define CLK_FIXED_FREQ_HZ (500 * 1000)
+static const unsigned long UART_BAUD_RATE = 9600;
+#else
+#define CLK_FIXED_FREQ_HZ (50ULL * 1000 * 1000)
+static const unsigned long UART_BAUD_RATE = 230400;
+#endif
+
+// Flash memory base defines, _SZ are presented in bytes
+#define FLASH_MEM_BASE_ADDR 0x20000000
+#define FLASH_WORDS_PER_PAGE 256
+#define FLASH_WORD_SZ 4
+#define FLASH_PAGE_SZ FLASH_WORDS_PER_PAGE *FLASH_WORD_SZ
+#define FLASH_PAGES_PER_BANK 256
+#define FLASH_BANK_SZ FLASH_PAGES_PER_BANK *FLASH_PAGE_SZ
+
+#define REG8(add) *((volatile uint8_t *)(add))
+#define REG16(add) *((volatile uint16_t *)(add))
+#define REG32(add) *((volatile uint32_t *)(add))
+#define SETBIT(val, bit) (val | 1 << bit)
+#define CLRBIT(val, bit) (val & ~(1 << bit))
+
+/* Hamming weight */
+#define BITLENGTH_1(X) ((X) - (((X) >> 1) & 0x55555555))
+#define BITLENGTH_2(X) (((X)&0x33333333) + (((X) >> 2) & 0x33333333))
+#define BITLENGTH_3(X) (((X) + ((X) >> 4)) & 0x0f0f0f0f)
+#define BITLENGTH_4(X) ((X) + ((X) >> 8))
+#define BITLENGTH_5(X) ((X) + ((X) >> 16))
+#define BITLENGTH(X) \
+ ((BITLENGTH_5(BITLENGTH_4(BITLENGTH_3(BITLENGTH_2(BITLENGTH_1(X)))))) & 0x7f)
+
+#endif
diff --git a/sw/lib/flash_ctrl.c b/sw/lib/flash_ctrl.c
new file mode 100644
index 0000000..a780a00
--- /dev/null
+++ b/sw/lib/flash_ctrl.c
@@ -0,0 +1,164 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "flash_ctrl.h"
+
+#include <stdint.h>
+
+#include "common.h"
+
+static uint32_t get_clr_err(void) {
+ uint32_t err_status;
+
+ // extract error status
+ err_status =
+ REG32(FLASH_CTRL_INTR_STATE(0)) & (0x1 << FLASH_CTRL_INTR_STATE_OP_ERROR);
+
+ // clear error if set
+ REG32(FLASH_CTRL_INTR_STATE(0)) = err_status;
+
+ // return status
+ return err_status;
+}
+
+// flash initialization done
+void wait_flash_init(void) {
+ while ((REG32(FLASH_CTRL_STATUS(0)) & (1 << FLASH_CTRL_STATUS_INIT_WIP)) >
+ 0) {
+ }
+}
+
+// wait for flash done and ack
+void wait_done_and_ack(void) {
+ while ((REG32(FLASH_CTRL_OP_STATUS(0)) & (1 << FLASH_CTRL_OP_STATUS_DONE)) ==
+ 0)
+ ;
+
+ REG32(FLASH_CTRL_OP_STATUS(0)) = 0;
+}
+
+// setup flash prog
+void setup_flash_prog(uint32_t addr, uint32_t num) {
+ uint32_t val;
+
+ val = FlashProg << FLASH_CTRL_CONTROL_OP_OFFSET |
+ (num - 1) << FLASH_CTRL_CONTROL_NUM_OFFSET |
+ 0x1 << FLASH_CTRL_CONTROL_START;
+
+ REG32(FLASH_CTRL_ADDR(0)) = addr;
+
+ REG32(FLASH_CTRL_CONTROL(0)) = val;
+}
+
+// program data
+uint32_t prog_flash(uint32_t addr, uint32_t num, uint32_t *data) {
+ uint32_t i = 0;
+
+ // setup flash programming
+ setup_flash_prog(addr, num);
+
+ // beginning filling up the fifo
+ for (i = 0; i < num; i++) {
+ REG32(FLASH_CTRL_PROG_FIFO(FLASH_CTRL0_BASE_ADDR)) = *data;
+ data++;
+ }
+
+ // wait for operation finish
+ wait_done_and_ack();
+
+ // return error status
+ return get_clr_err();
+}
+
+// read data
+uint32_t read_flash(uint32_t addr, uint32_t num, uint32_t *data) {
+ uint32_t val;
+ uint32_t i = 0;
+
+ // kick off flash operation
+ val = FlashRead << FLASH_CTRL_CONTROL_OP_OFFSET |
+ (num - 1) << FLASH_CTRL_CONTROL_NUM_OFFSET |
+ 0x1 << FLASH_CTRL_CONTROL_START;
+
+ REG32(FLASH_CTRL_ADDR(0)) = addr;
+
+ REG32(FLASH_CTRL_CONTROL(0)) = val;
+
+ while (i < num) {
+ // if not empty, read a word
+ if (((REG32(FLASH_CTRL_STATUS(0)) >> FLASH_CTRL_STATUS_RD_EMPTY) & 0x1) ==
+ 0) {
+ *data++ = REG32(FLASH_CTRL_RD_FIFO(FLASH_CTRL0_BASE_ADDR));
+ i++;
+ }
+ }
+
+ // wait for operation finish
+ wait_done_and_ack();
+
+ // return error status
+ return get_clr_err();
+}
+
+// page erase flash
+// wrap down to closest down to page boundary
+uint32_t page_erase(uint32_t addr) {
+ uint32_t val;
+ uint32_t data[ERASE_CHECK_WORDS];
+ uint32_t verify_rounds;
+ uint32_t error;
+
+ error = 0;
+ verify_rounds = WORDS_PER_PAGE / ERASE_CHECK_WORDS;
+
+ // kick off flash operation
+ val = FlashErase << FLASH_CTRL_CONTROL_OP_OFFSET |
+ PageErase << FLASH_CTRL_CONTROL_ERASE_SEL |
+ 0x1 << FLASH_CTRL_CONTROL_START;
+
+ REG32(FLASH_CTRL_ADDR(0)) = addr;
+
+ REG32(FLASH_CTRL_CONTROL(0)) = val;
+
+ // wait for operation finish
+ wait_done_and_ack();
+
+ error += get_clr_err();
+
+ // verify erase
+ for (uint32_t i = 0; i < verify_rounds; i++) {
+ error += read_flash(addr + i * ERASE_CHECK_WORDS * BYTES_PER_WORD,
+ ERASE_CHECK_WORDS, data);
+
+ for (uint32_t j = 0; j < ERASE_CHECK_WORDS; j++) {
+ if (data[i] != 0xFFFFFFFF) {
+ REG32(FLASH_CTRL_SCRATCH(0)) = data[i];
+
+ // re-init array
+ data[i] = 0;
+ error++;
+ }
+ }
+ }
+
+ // return error status
+ return error;
+}
+
+void flash_default_region(uint32_t rd_en, uint32_t prog_en, uint32_t erase_en) {
+ REG32(FLASH_CTRL_DEFAULT_REGION(0)) =
+ rd_en << FLASH_CTRL_DEFAULT_REGION_RD_EN |
+ prog_en << FLASH_CTRL_DEFAULT_REGION_PROG_EN |
+ erase_en << FLASH_CTRL_DEFAULT_REGION_ERASE_EN;
+}
+
+void flash_cfg_region(mp_region_t region_cfg) {
+ REG32(FLASH_CTRL_MP_REGION_CFG0(0) + region_cfg.num * 4) =
+ region_cfg.base << FLASH_CTRL_MP_REGION_CFG0_BASE0_OFFSET |
+ region_cfg.size << FLASH_CTRL_MP_REGION_CFG0_SIZE0_OFFSET |
+ region_cfg.rd_en << FLASH_CTRL_MP_REGION_CFG0_RD_EN0 |
+ region_cfg.prog_en << FLASH_CTRL_MP_REGION_CFG0_PROG_EN0 |
+ region_cfg.erase_en << FLASH_CTRL_MP_REGION_CFG0_ERASE_EN0 |
+ 0x1 << FLASH_CTRL_MP_REGION_CFG0_EN0;
+}
diff --git a/sw/lib/flash_ctrl.h b/sw/lib/flash_ctrl.h
new file mode 100644
index 0000000..21e90a1
--- /dev/null
+++ b/sw/lib/flash_ctrl.h
@@ -0,0 +1,43 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _FLASH_H_
+#define _FLASH_H_
+
+#include <stdint.h>
+
+#include "flash_ctrl_regs.h"
+
+#define FLASH_CTRL0_BASE_ADDR 0x40030000
+#define WORDS_PER_PAGE 256
+#define ERASE_CHECK_WORDS 16
+#define BYTES_PER_WORD 4
+
+typedef enum flash_op {
+ FlashRead = 0,
+ FlashProg = 1,
+ FlashErase = 2
+} flash_op_t;
+
+typedef enum erase_type { PageErase = 0, BankErase = 1 } erase_type_t;
+
+typedef struct mp_region {
+ uint32_t num; // which region to program
+ uint32_t base;
+ uint32_t size;
+ uint32_t rd_en;
+ uint32_t prog_en;
+ uint32_t erase_en;
+} mp_region_t;
+
+void wait_flash_init(void);
+void wait_done_and_ack(void);
+void setup_flash_prog(uint32_t addr, uint32_t num);
+uint32_t prog_flash(uint32_t addr, uint32_t num, uint32_t *data);
+uint32_t read_flash(uint32_t addr, uint32_t num, uint32_t *data);
+uint32_t page_erase(uint32_t addr);
+void flash_default_region(uint32_t rd_en, uint32_t prog_en, uint32_t erase_en);
+void flash_cfg_region(mp_region_t region_cfg);
+
+#endif
diff --git a/sw/lib/gpio.c b/sw/lib/gpio.c
new file mode 100644
index 0000000..a78fc4b
--- /dev/null
+++ b/sw/lib/gpio.c
@@ -0,0 +1,36 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "gpio.h"
+
+#include "assert.h"
+#include "common.h"
+
+/**
+ * @param oe bits to use as output
+ */
+void gpio_init(uint32_t oe) { REG32(GPIO_DIRECT_OE(0)) = oe; }
+
+void gpio_write_bit(unsigned int bit, unsigned int val) {
+ uint32_t mask = 0;
+ uint32_t reg_val = 0;
+ volatile uint32_t *gpio_masked_out_reg = 0;
+
+ if (bit < 16) {
+ gpio_masked_out_reg = (uint32_t *)GPIO_MASKED_OUT_LOWER(0);
+ } else if (bit < 32) {
+ gpio_masked_out_reg = (uint32_t *)GPIO_MASKED_OUT_UPPER(0);
+ } else {
+ assert(1 && "bit must be < 32");
+ }
+ bit %= 16;
+
+ mask = (1 << bit);
+ reg_val = (mask << 16) | ((val & 0x01) << bit);
+ *gpio_masked_out_reg = reg_val;
+}
+
+void gpio_write_all(uint32_t val) { REG32(GPIO_DIRECT_OUT(0)) = val; }
+
+uint32_t gpio_read(void) { return REG32(GPIO_DATA_IN(0)); }
diff --git a/sw/lib/gpio.h b/sw/lib/gpio.h
new file mode 100644
index 0000000..1397b5f
--- /dev/null
+++ b/sw/lib/gpio.h
@@ -0,0 +1,19 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _GPIO_H_
+#define _GPIO_H_
+
+#include <stdint.h>
+
+#include "gpio_regs.h"
+
+#define GPIO0_BASE_ADDR 0x40010000
+
+void gpio_init(uint32_t oe);
+void gpio_write_bit(unsigned int bit, unsigned int val);
+void gpio_write_all(uint32_t val);
+uint32_t gpio_read(void);
+
+#endif
diff --git a/sw/lib/handler.c b/sw/lib/handler.c
new file mode 100644
index 0000000..cefe4e5
--- /dev/null
+++ b/sw/lib/handler.c
@@ -0,0 +1,46 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "common.h"
+
+/**
+ * Default exception handler. Can be overidden.
+ */
+void handler_exception(void) __attribute__((aligned(4), interrupt, weak));
+
+/**
+ * SW IRQ handler. Can be overidden.
+ */
+void handler_irq_software(void) __attribute__((aligned(4), interrupt, weak));
+
+/**
+ * Timer IRQ handler. Can be overidden.
+ */
+void handler_irq_timer(void) __attribute__((aligned(4), interrupt, weak));
+
+/**
+ * external IRQ handler. Can be overidden.
+ */
+void handler_irq_external(void) __attribute__((aligned(4), interrupt, weak));
+
+// Below functions are default weak exception handlers meant to be overriden
+void handler_exception(void) {
+ while (1) {
+ }
+}
+
+void handler_irq_software(void) {
+ while (1) {
+ }
+}
+
+void handler_irq_timer(void) {
+ while (1) {
+ }
+}
+
+void handler_irq_external(void) {
+ while (1) {
+ }
+}
diff --git a/sw/lib/hmac.c b/sw/lib/hmac.c
new file mode 100644
index 0000000..7318c90
--- /dev/null
+++ b/sw/lib/hmac.c
@@ -0,0 +1,109 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "hmac.h"
+
+#include "common.h"
+#include "hmac_regs.h"
+
+#define HMAC0_BASE_ADDR 0x40120000
+#define HMAC_FIFO_MAX 16
+#define HMAC_FIFO_GROUP_SIZE HMAC_FIFO_MAX / 2
+
+void hmac_init(hmac_cfg_t hmac_cfg) {
+ REG32(HMAC_CFG(0)) = hmac_cfg.input_endian_swap << HMAC_CFG_ENDIAN_SWAP |
+ 1 << hmac_cfg.mode |
+ hmac_cfg.digest_endian_swap << HMAC_CFG_DIGEST_SWAP;
+
+ REG32(HMAC_MSG_LENGTH_LOWER(0)) = hmac_cfg.length_lower;
+ REG32(HMAC_MSG_LENGTH_UPPER(0)) = hmac_cfg.length_upper;
+
+ for (int i = 0; i < 8; i++) {
+ REG32(HMAC_KEY0(0) + i * sizeof(uint32_t)) = hmac_cfg.keys[i];
+ }
+
+ REG32(HMAC_CMD(0)) = -1;
+};
+
+int hmac_fifo_full(void) {
+ return (REG32(HMAC_STATUS(0)) >> HMAC_STATUS_FIFO_FULL) & 0x1;
+}
+
+static int hmac_fifo_depth(void) {
+ return (REG32(HMAC_STATUS(0)) >> HMAC_STATUS_FIFO_DEPTH_OFFSET) &
+ HMAC_STATUS_FIFO_DEPTH_MASK;
+}
+
+static int fifo_avail(void) { return HMAC_FIFO_MAX - hmac_fifo_depth(); }
+
+void hmac_write(const void *data, size_t size_in_bytes) {
+ const uint8_t *bp;
+ const uint32_t *wp;
+ uint32_t bytes_per_word = sizeof(uint32_t) / sizeof(uint8_t);
+ uint32_t bytes_left_over = (size_in_bytes % bytes_per_word);
+ size_t words_remaining = size_in_bytes / bytes_per_word;
+
+ wp = (uint32_t *)data;
+
+ // write in all words
+ while (words_remaining > 0) {
+ if (words_remaining > HMAC_FIFO_GROUP_SIZE) {
+ // wait until FIFO is at least half drained
+ while (fifo_avail() <= HMAC_FIFO_GROUP_SIZE) {
+ }
+
+ // write a whole group
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ words_remaining -= HMAC_FIFO_GROUP_SIZE;
+
+ } else {
+ REG32(HMAC_MSG_FIFO(0)) = *wp++;
+ words_remaining--;
+ };
+ }
+
+ // TODO: this is necessary because hmac only understands words right now, we
+ // cannot do a byte write. Once that is addressed, change following to
+ // byte writes directly
+ // Despite no byte support, it would have been okay to just read the entire
+ // word and write it to hmac, since hmac knows exactly which bytes to ignore /
+ // process. The problem however, is that the DV environment does not like
+ // reading of unknown data. So imagine if we have one byte (0xab) left over,
+ // in DV memory, this is represented as
+ // XXXX_XXab. Our environment assertions will fail when a full word read is
+ // made to the X's, thus it is converted to byte reads below to avoid that
+ // problem
+ uint32_t padded_word = 0;
+ uint8_t *last_word_ptr = (uint8_t *)&padded_word;
+ bp = (uint8_t *)wp;
+
+ while (bytes_left_over > 0) {
+ *last_word_ptr++ = *bp++;
+ bytes_left_over--;
+ }
+
+ // this word is ignored if no bytes are left over
+ REG32(HMAC_MSG_FIFO(0)) = padded_word;
+}
+
+int hmac_done(uint32_t *digest) {
+ // TODO need a timeout mechanism
+ // wait for done to assert
+ while (!((REG32(HMAC_INTR_STATE(0)) >> HMAC_INTR_STATE_HMAC_DONE) & 0x1)) {
+ }
+
+ for (uint32_t i = 0; i < 8; i++) {
+ *digest++ = REG32(HMAC_DIGEST0(0) + i * sizeof(uintptr_t));
+ }
+
+ // eventually when we timeout, need to return an error code
+ return 0;
+}
diff --git a/sw/lib/hmac.h b/sw/lib/hmac.h
new file mode 100644
index 0000000..12ee6c1
--- /dev/null
+++ b/sw/lib/hmac.h
@@ -0,0 +1,39 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _F_LIB_HMAC_H__
+#define _F_LIB_HMAC_H__
+
+#include <stddef.h>
+#include <stdint.h>
+
+/* hmac operations */
+typedef enum hmac_ops { Hmac = 0, Sha256 = 1 } hmac_ops_t;
+
+typedef struct hmac_cfg {
+ hmac_ops_t mode;
+ // input swapping only (from reg)
+ uint32_t input_endian_swap;
+ // output swapping only (to digest)
+ uint32_t digest_endian_swap;
+ // length in bits
+ uint32_t length_lower;
+ // lenght in bits
+ uint32_t length_upper;
+ uint32_t keys[8];
+} hmac_cfg_t;
+
+/* Intialize hmac to desired mode. */
+void hmac_init(hmac_cfg_t hmac_cfg);
+
+/* Returns 1 if hmac fifo is full, 0 otherwise. */
+int hmac_fifo_full(void);
+
+/* Write |data| to hmac with |size| in Bytes */
+void hmac_write(const void *data, size_t size);
+
+/* Poll for hmac done and read out digest. */
+int hmac_done(uint32_t *digest);
+
+#endif // _F_LIB_HMAC_H__
diff --git a/sw/lib/irq.c b/sw/lib/irq.c
new file mode 100644
index 0000000..7dc8654
--- /dev/null
+++ b/sw/lib/irq.c
@@ -0,0 +1,54 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "irq.h"
+
+#include "common.h"
+
+static const uint32_t IRQ_EXT_ENABLE_OFFSET = 11;
+static const uint32_t IRQ_TIMER_ENABLE_OFFSET = 7;
+static const uint32_t IRQ_SW_ENABLE_OFFSET = 3;
+
+static void irq_mie_set(uint32_t value) {
+ asm volatile("csrrs zero, mie, %0" : : "r"(value) :);
+}
+
+static void irq_mie_clr(uint32_t value) {
+ asm volatile("csrrc zero, mie, %0" : : "r"(value) :);
+}
+
+void irq_global_ctrl(bool en) {
+ if (en) {
+ asm volatile("csrsi mstatus, 0x8" : : :);
+ } else {
+ asm volatile("csrci mstatus, 0x8" : : :);
+ }
+}
+
+void irq_external_ctrl(bool en) {
+ const uint32_t value = 1 << IRQ_EXT_ENABLE_OFFSET;
+ if (en) {
+ irq_mie_set(value);
+ } else {
+ irq_mie_clr(value);
+ }
+}
+
+void irq_timer_ctrl(bool en) {
+ const uint32_t value = 1 << IRQ_TIMER_ENABLE_OFFSET;
+ if (en) {
+ irq_mie_set(value);
+ } else {
+ irq_mie_clr(value);
+ }
+}
+
+void irq_software_ctrl(bool en) {
+ const uint32_t value = 1 << IRQ_SW_ENABLE_OFFSET;
+ if (en) {
+ irq_mie_set(value);
+ } else {
+ irq_mie_clr(value);
+ }
+}
diff --git a/sw/lib/irq.h b/sw/lib/irq.h
new file mode 100644
index 0000000..a992889
--- /dev/null
+++ b/sw/lib/irq.h
@@ -0,0 +1,36 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _IRQ_H_
+#define _IRQ_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+
+/**
+ * Update to the location of vectors as specificed in the linker file
+ */
+extern void update_mtvec(void);
+
+/**
+ * Enable / disable ibex globlal interrupts
+ */
+void irq_global_ctrl(bool en);
+
+/**
+ * Enable / disable ibex external interrupts
+ */
+void irq_external_ctrl(bool en);
+
+/**
+ * Enable / disable ibex timer interrupts
+ */
+void irq_timer_ctrl(bool en);
+
+/**
+ * Enable / disable ibex software interrupts
+ */
+void irq_software_ctrl(bool en);
+
+#endif
diff --git a/sw/lib/irq_vectors.S b/sw/lib/irq_vectors.S
new file mode 100644
index 0000000..5d16746
--- /dev/null
+++ b/sw/lib/irq_vectors.S
@@ -0,0 +1,36 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+.extern handler_exception
+.extern handler_irq_software
+.extern handler_irq_timer
+.extern handler_irq_external
+.extern _svectors
+
+update_mtvec:
+ .section .text
+ .global update_mtvec
+ la a0, _svectors
+ csrw mtvec, a0
+ ret
+
+exception_handlers:
+ .section .vectors
+ .global vector_handlers
+
+ // exception handler
+ .org 0x0
+ jal x0, handler_exception
+
+ // software interrupt handler
+ .org 0x0c
+ jal x0, handler_irq_software
+
+ // timer interrupt handler
+ .org 0x1c
+ jal x0, handler_irq_timer
+
+ // external interrupt handler
+ .org 0x2c
+ jal x0, handler_irq_external
diff --git a/sw/lib/rv_timer.c b/sw/lib/rv_timer.c
new file mode 100644
index 0000000..d9acefb
--- /dev/null
+++ b/sw/lib/rv_timer.c
@@ -0,0 +1,44 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "rv_timer.h"
+
+#include "common.h"
+#include "rv_timer_regs.h"
+
+#define RV_TIMER0_BASE_ADDR 0x40080000
+#define HART_CFG_ADDR_GAP 0x100
+
+static const uint32_t NS_IN_S = 1000 * 1000 * 1000;
+
+void rv_timer_set_us_tick(uint32_t hart) {
+ uint32_t ticks_per_us = (uint32_t)((1000 * CLK_FIXED_FREQ_HZ) / NS_IN_S) - 1;
+
+ REG32(RV_TIMER_CFG0(0) + hart * 4) =
+ (ticks_per_us & RV_TIMER_CFG0_PRESCALE_MASK) |
+ (1 << RV_TIMER_CFG0_STEP_OFFSET);
+}
+
+void rv_timer_set_cmp(uint32_t hart, uint64_t cmp) {
+ REG32(RV_TIMER_COMPARE_UPPER0_0(0) + hart * HART_CFG_ADDR_GAP) = -1;
+ REG32(RV_TIMER_COMPARE_LOWER0_0(0) + hart * HART_CFG_ADDR_GAP) =
+ (uint32_t)cmp;
+ REG32(RV_TIMER_COMPARE_UPPER0_0(0) + hart * HART_CFG_ADDR_GAP) =
+ (uint32_t)(cmp >> 32);
+}
+
+void rv_timer_ctrl(uint32_t hart, bool en) {
+ REG32(RV_TIMER_CTRL(0)) = (en) ? SETBIT(REG32(RV_TIMER_CTRL(0)), hart)
+ : CLRBIT(REG32(RV_TIMER_CTRL(0)), hart);
+}
+
+void rv_timer_intr_enable(uint32_t hart, bool en) {
+ REG32(RV_TIMER_INTR_ENABLE0(0)) =
+ (en) ? SETBIT(REG32(RV_TIMER_INTR_ENABLE0(0)), hart)
+ : CLRBIT(REG32(RV_TIMER_INTR_ENABLE0(0)), hart);
+}
+
+void rv_timer_clr_all_intrs(void) {
+ REG32(RV_TIMER_INTR_STATE0(0)) = REG32(RV_TIMER_INTR_STATE0(0));
+}
diff --git a/sw/lib/rv_timer.h b/sw/lib/rv_timer.h
new file mode 100644
index 0000000..7d74c6e
--- /dev/null
+++ b/sw/lib/rv_timer.h
@@ -0,0 +1,49 @@
+#ifndef _F_LIB_RV_TIMER_H__
+#define _F_LIB_RV_TIMER_H__
+
+#include <stdbool.h>
+#include <stddef.h>
+#include <stdint.h>
+
+/**
+ * Set hart timer prescaler
+ *
+ * Program hart timer prescaler to produce 1us ticks
+ *
+ * @param hart hart selection
+ */
+void rv_timer_set_us_tick(uint32_t hart);
+
+/**
+ * Set hart timer compare value
+ *
+ * Program hart timer compare value. When this value is met, an interrupt will
+ * be triggered.
+ *
+ * @param hart hart selection
+ */
+void rv_timer_set_cmp(uint32_t hart, uint64_t cmp);
+
+/**
+ * Enable hart timer to begin counting
+ *
+ * @param hart hart selection
+ * @param en 1 enables timer, 0 disables timer
+ */
+void rv_timer_ctrl(uint32_t hart, bool en);
+
+/**
+ * Set hart timer interrupt enable
+ *
+ * @param hart hart selection
+ * @param en 1 enables interrupt, 0 disables interrupt
+ */
+void rv_timer_intr_enable(uint32_t hart, bool en);
+
+/**
+ * Clear all active interrupts
+ * Interrupt state clearing is W1C (write-one-clear)
+ */
+void rv_timer_clr_all_intrs(void);
+
+#endif // _F_LIB_RV_TIMER_H__
diff --git a/sw/lib/spi_device.c b/sw/lib/spi_device.c
new file mode 100644
index 0000000..3222058
--- /dev/null
+++ b/sw/lib/spi_device.c
@@ -0,0 +1,211 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "spi_device.h"
+
+#include "common.h"
+#include "uart.h"
+
+uint32_t calc_depth(uint32_t wptr, uint32_t rptr, uint32_t size);
+
+/**
+ * Init SPI Device
+ *
+ * Configure registers, RXF_ADDR, TXF_ADDR, CTRL.TIMER_V
+ */
+void spid_init(void) {
+ /* Abort 0 */
+ REG32(SPI_DEVICE_CONTROL(0)) =
+ REG32(SPI_DEVICE_CONTROL(0)) & ~(1 << SPI_DEVICE_CONTROL_ABORT);
+
+ /* CPOL(0), CPHA(0), ORDERs(00), TIMER(63) */
+ REG32(SPI_DEVICE_CFG(0)) =
+ ((0 << SPI_DEVICE_CFG_CPOL) | (0 << SPI_DEVICE_CFG_CPHA) |
+ (0 << SPI_DEVICE_CFG_RX_ORDER) | (0 << SPI_DEVICE_CFG_TX_ORDER) |
+ ((63 & SPI_DEVICE_CFG_TIMER_V_MASK) << SPI_DEVICE_CFG_TIMER_V_OFFSET));
+
+ /* SRAM RXF/TXF ADDR. */
+ REG32(SPI_DEVICE_RXF_ADDR(0)) =
+ ((SPID_RXF_BASE & SPI_DEVICE_RXF_ADDR_BASE_MASK)
+ << SPI_DEVICE_RXF_ADDR_BASE_OFFSET) |
+ (((SPID_RXF_SIZE - 1) & SPI_DEVICE_RXF_ADDR_LIMIT_MASK)
+ << SPI_DEVICE_RXF_ADDR_LIMIT_OFFSET);
+
+ REG32(SPI_DEVICE_TXF_ADDR(0)) =
+ ((SPID_TXF_BASE & SPI_DEVICE_TXF_ADDR_BASE_MASK)
+ << SPI_DEVICE_TXF_ADDR_BASE_OFFSET) |
+ (((SPID_TXF_SIZE - 1) & SPI_DEVICE_TXF_ADDR_LIMIT_MASK)
+ << SPI_DEVICE_TXF_ADDR_LIMIT_OFFSET);
+}
+
+/**
+ * Calculation FIFO depth in bytes
+ *
+ * Assume SRAM size is fixed (constant) given by SPI_DEVICE_BUFFER_SIZE
+ *
+ * Fifo pointers are in bytes
+ */
+inline uint32_t calc_depth(uint32_t wptr, uint32_t rptr, uint32_t size) {
+ const uint32_t sram_szw = BITLENGTH(SPI_DEVICE_BUFFER_SIZE_BYTES - 1);
+ uint32_t depth;
+ uint32_t wptr_phase, rptr_phase, wptr_v, rptr_v;
+ wptr_phase = wptr >> sram_szw;
+ rptr_phase = rptr >> sram_szw;
+ wptr_v = wptr & (SPI_DEVICE_BUFFER_SIZE_BYTES - 1);
+ rptr_v = rptr & (SPI_DEVICE_BUFFER_SIZE_BYTES - 1);
+
+ if (wptr_phase == rptr_phase) {
+ depth = (wptr_v - rptr_v);
+ } else {
+ depth = size - rptr_v + wptr_v;
+ }
+
+ return depth;
+}
+
+/*
+ * Increment pointer, zero and flip phase if it gets to size
+ */
+uint32_t ptr_inc(uint32_t ptr, uint32_t inc, uint32_t size) {
+ uint32_t phase = ptr & SPI_DEVICE_BUFFER_SIZE_BYTES;
+ ptr = (ptr & (SPI_DEVICE_BUFFER_SIZE_BYTES - 1)) + inc;
+ if (ptr >= size) {
+ ptr -= size;
+ phase ^= SPI_DEVICE_BUFFER_SIZE_BYTES;
+ }
+ return ptr | phase;
+}
+
+static int word_aligned(void *p) { return (((int)p & 0x3) == 0); }
+
+/**
+ * Send data over SPI
+ *
+ * @param data pointer to buffer of uint_8 to send
+ * @param len_bytes number of bytes to send
+ * @return number of bytes actually sent (<len if no space in the fifo)
+ */
+size_t spid_send(void *data, size_t len_bytes) {
+ uint32_t txf_ptr, txf_wptr, txf_rptr;
+ uint32_t fifo_inuse_bytes;
+ uint32_t msg_length_bytes;
+
+ /* Check if TXF has enough space */
+ txf_ptr = REG32(SPI_DEVICE_TXF_PTR(0));
+ txf_wptr = (txf_ptr >> SPI_DEVICE_TXF_PTR_WPTR_OFFSET) &
+ SPI_DEVICE_TXF_PTR_WPTR_MASK;
+ txf_rptr = (txf_ptr >> SPI_DEVICE_TXF_PTR_RPTR_OFFSET) &
+ SPI_DEVICE_TXF_PTR_RPTR_MASK;
+
+ fifo_inuse_bytes = calc_depth(txf_wptr, txf_rptr, SPID_TXF_SIZE);
+
+ // Reserve the last 4 bytes in the fifo so it is always safe
+ // to write 32-bit words
+ if (len_bytes < SPID_TXF_SIZE - fifo_inuse_bytes - 4) {
+ // Safe to send all data
+ msg_length_bytes = len_bytes;
+ } else {
+ msg_length_bytes = SPID_TXF_SIZE - fifo_inuse_bytes - 4;
+ }
+ int tocopy = msg_length_bytes;
+
+ // Aligned case can just copy words
+ if (word_aligned(data) && word_aligned((void *)txf_wptr)) {
+ uint32_t *data_w = (uint32_t *)data;
+ while (tocopy > 0) {
+ ACCESS32_TXFPTR(txf_wptr) = *data_w++;
+ if (tocopy >= 4) {
+ txf_wptr = ptr_inc(txf_wptr, 4, SPID_TXF_SIZE);
+ tocopy -= 4;
+ } else {
+ txf_wptr = ptr_inc(txf_wptr, tocopy, SPID_TXF_SIZE);
+ tocopy = 0; // tocopy -= tocopy always gives zero
+ }
+ }
+ } else {
+ // preserve data if unaligned start
+ uint8_t *data_b = (uint8_t *)data;
+ uint32_t d = ACCESS32_TXFPTR(txf_wptr);
+ while (tocopy > 0) {
+ int shift = (txf_wptr & 0x3) * 8;
+ uint32_t mask = 0xff << shift;
+ d = (d & ~mask) | (*data_b++ << shift);
+ if ((txf_wptr & 0x3) == 0x3) {
+ ACCESS32_TXFPTR(txf_wptr) = d;
+ }
+ txf_wptr = ptr_inc(txf_wptr, 1, SPID_TXF_SIZE);
+ tocopy--;
+ }
+ }
+
+ // Write pointer, requires read pointer to be RO
+ REG32(SPI_DEVICE_TXF_PTR(0)) = txf_wptr << SPI_DEVICE_TXF_PTR_WPTR_OFFSET;
+
+ return msg_length_bytes;
+}
+
+/**
+ * Read the amount of the data from SRAM RX FIFO
+ *
+ * If remained data is smaller than length, it returns only up to data
+ */
+size_t spid_read_nb(void *data, size_t len_bytes) {
+ uint32_t rxf_ptr, rxf_wptr, rxf_rptr;
+ uint32_t msg_len_bytes;
+
+ rxf_ptr = REG32(SPI_DEVICE_RXF_PTR(0));
+ rxf_wptr = (rxf_ptr >> SPI_DEVICE_RXF_PTR_WPTR_OFFSET) &
+ SPI_DEVICE_RXF_PTR_WPTR_MASK;
+ rxf_rptr = (rxf_ptr >> SPI_DEVICE_RXF_PTR_RPTR_OFFSET) &
+ SPI_DEVICE_RXF_PTR_RPTR_MASK;
+
+ msg_len_bytes = calc_depth(rxf_wptr, rxf_rptr, SPID_RXF_SIZE);
+ if (msg_len_bytes == 0) {
+ return 0;
+ }
+ uart_send_uint(rxf_ptr, 32);
+ uart_send_char(' ');
+ uart_send_uint(msg_len_bytes, 32);
+ uart_send_char(' ');
+ /* Check there is room for the whole buffer */
+ if (msg_len_bytes > len_bytes) {
+ msg_len_bytes = len_bytes;
+ }
+
+ int tocopy = msg_len_bytes;
+ // Aligned case -- which for now it always will be
+ // if tocopy is not multiple of 4 then will read / write extra bytes
+ // so check buffer length
+ if (word_aligned(data) && ((len_bytes & 0x3) == 0) &&
+ word_aligned((void *)rxf_ptr)) {
+ uint32_t *data_w = (uint32_t *)data;
+ while (tocopy > 0) {
+ *data_w++ = READ32_RXFPTR(rxf_rptr);
+ if (tocopy >= 4) {
+ rxf_rptr = ptr_inc(rxf_rptr, 4, SPID_RXF_SIZE);
+ tocopy -= 4;
+ } else {
+ rxf_rptr = ptr_inc(rxf_rptr, tocopy, SPID_RXF_SIZE);
+ tocopy = 0; // tocopy -= tocopy always gives zero
+ }
+ }
+ } else {
+ uint8_t *data_b = (uint8_t *)data;
+ // Have to deal with only being able to do 32-bit accesses
+ int dst = 0;
+ uint32_t d = READ32_RXFPTR(rxf_rptr & ~0x3);
+ while (tocopy--) {
+ int boff = rxf_rptr & 0x3;
+ data_b[dst++] = (d >> (boff * 8)) & 0xff;
+ rxf_rptr = ptr_inc(rxf_rptr, 1, SPID_RXF_SIZE);
+ if (((rxf_rptr & 0x3) == 0) && tocopy) {
+ d = READ32_RXFPTR(rxf_rptr);
+ }
+ }
+ }
+ /* Update read pointer -- NB relies on write pointer being RO */
+ REG32(SPI_DEVICE_RXF_PTR(0)) = rxf_rptr << SPI_DEVICE_RXF_PTR_RPTR_OFFSET;
+
+ return msg_len_bytes;
+}
diff --git a/sw/lib/spi_device.h b/sw/lib/spi_device.h
new file mode 100644
index 0000000..18d3278
--- /dev/null
+++ b/sw/lib/spi_device.h
@@ -0,0 +1,35 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _SPI_DEVICE_H_
+#define _SPI_DEVICE_H_
+
+#include <stddef.h>
+
+#include "common.h"
+
+#define SPI_DEVICE0_BASE_ADDR 0x40020000
+
+#include "spi_device_regs.h"
+
+#define SPID_SRAM_ADDR SPI_DEVICE_BUFFER(SPI_DEVICE0_BASE_ADDR)
+#define SPID_RXF_BASE 0x000
+#define SPID_RXF_SIZE 0x400
+#define SPID_TXF_BASE 0x600
+#define SPID_TXF_SIZE 0x200
+
+#define SPID_SRAM_SIZE (0x800)
+
+/* Note: these will correctly remove the phase bit */
+#define READ32_RXFPTR(P) \
+ REG32(SPID_SRAM_ADDR + SPID_RXF_BASE + ((P) & (SPID_RXF_SIZE - 1)))
+
+#define ACCESS32_TXFPTR(P) \
+ REG32(SPID_SRAM_ADDR + SPID_TXF_BASE + ((P) & ((SPID_TXF_SIZE - 1) & ~0x3)))
+
+void spid_init(void);
+size_t spid_send(void *data, size_t len_bytes);
+size_t spid_read_nb(void *data, size_t len);
+
+#endif /* _SPI_DEVICE_H_ */
diff --git a/sw/lib/uart.c b/sw/lib/uart.c
new file mode 100644
index 0000000..c8fd52d
--- /dev/null
+++ b/sw/lib/uart.c
@@ -0,0 +1,71 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#include "uart.h"
+
+#include "common.h"
+
+inline void uart_init(unsigned int baud) {
+ // nco = 2^20 * baud / fclk
+ uint64_t uart_ctrl_nco = ((uint64_t)baud << 20) / CLK_FIXED_FREQ_HZ;
+ REG32(UART_CTRL(0)) =
+ ((uart_ctrl_nco & UART_CTRL_NCO_MASK) << UART_CTRL_NCO_OFFSET) |
+ (1 << UART_CTRL_TX) | (1 << UART_CTRL_RX);
+
+ // reset RX/TX FIFOs
+ REG32(UART_FIFO_CTRL(0)) =
+ (1 << UART_FIFO_CTRL_RXRST) | (1 << UART_FIFO_CTRL_TXRST);
+
+ // disable interrupts
+ REG32(UART_INTR_ENABLE(0)) = 0;
+}
+
+static int uart_tx_rdy(void) {
+ return !(REG32(UART_STATUS(0)) & (1 << UART_STATUS_TXFULL));
+}
+
+void uart_send_char(char c) {
+ while (!uart_tx_rdy()) {
+ }
+ REG32(UART_WDATA(0)) = c;
+}
+
+/**
+ * Send a NULL-terminated string over UART
+ */
+void uart_send_str(char *str) {
+ while (*str != '\0') {
+ uart_send_char(*str++);
+ }
+}
+
+#define hexchar(i) (((i & 0xf) > 9) ? (i & 0xf) - 10 + 'A' : (i & 0xf) + '0')
+
+/**
+ * Send unsigned int over UART
+ */
+void uart_send_uint(uint32_t n, int bits) {
+ for (int i = bits - 4; i >= 0; i -= 4) {
+ uart_send_char(hexchar(n >> i));
+ }
+}
+
+int uart_rx_empty(void) {
+ return !!(REG32(UART_STATUS(0)) & (1 << UART_STATUS_RXEMPTY));
+}
+
+/**
+ * Receive a single character from UART
+ *
+ * @param c received character, caller-allocated
+ * @return 0 on success, -1 if no data is available
+ */
+int uart_rcv_char(char *c) {
+ if (uart_rx_empty()) {
+ return -1;
+ }
+
+ *c = REG32(UART_RDATA(0));
+ return 0;
+}
diff --git a/sw/lib/uart.h b/sw/lib/uart.h
new file mode 100644
index 0000000..acc4590
--- /dev/null
+++ b/sw/lib/uart.h
@@ -0,0 +1,21 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _UART_H_
+#define _UART_H_
+
+#include <stdint.h>
+
+#define UART0_BASE_ADDR 0x40000000
+
+#include "uart_regs.h"
+
+void uart_send_char(char c);
+void uart_send_uint(uint32_t n, int size);
+void uart_init(unsigned int baud);
+void uart_send_str(char *str);
+int uart_rx_empty(void);
+int uart_rcv_char(char *c);
+
+#endif
diff --git a/sw/lib/usb_consts.h b/sw/lib/usb_consts.h
new file mode 100644
index 0000000..5e2ebb7
--- /dev/null
+++ b/sw/lib/usb_consts.h
@@ -0,0 +1,54 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _USB_CONSTS_H_
+#define _USB_CONSTS_H_
+
+// SETUP requests
+typedef enum usb_setup_req {
+ kUsbSetupReqGetStatus = 0,
+ kUsbSetupReqClearFeature = 1,
+ kUsbSetupReqSetFeature = 3,
+ kUsbSetupReqSetAddress = 5,
+ kUsbSetupReqGetDescriptor = 6,
+ kUsbSetupReqSetDescriptor = 7,
+ kUsbSetupReqGetConfiguration = 8,
+ kUsbSetupReqSetConfiguration = 9,
+ kUsbSetupReqGetInterface = 10,
+ kUsbSetupReqSetInterface = 11,
+ kUsbSetupReqSynchFrame = 12
+} usb_setup_req_t;
+
+typedef enum usb_req_type { // bmRequestType
+ kUsbReqTypeRecipientMask = 0x1f,
+ kUsbReqTypeDevice = 0,
+ kUsbReqTypeInterface = 1,
+ kUsbReqTypeEndpoint = 2,
+ kUsbReqTypeOther = 3,
+ kUsbReqTypeTypeMask = 0x60,
+ KUsbReqTypeStandard = 0,
+ KUsbReqTypeClass = 0x20,
+ KUsbReqTypeVendor = 0x40,
+ KUsbReqTypeReserved = 0x60,
+ kUsbReqTypeDirMask = 0x80,
+ kUsbReqTypeDirH2D = 0x00,
+ kUsbReqTypeDirD2H = 0x80,
+} usb_req_type_t;
+
+typedef enum usb_feature_req {
+ kUsbFeatureEndpointHalt = 0, // recipient is endpoint
+ kUsbFeatureDeviceRemoteWakeup = 1, // recipient is device
+ kUsbFeatureTestMode = 2, // recipient is device
+ kUsbFeatureBHnpEnable = 3, // recipient is device only if OTG
+ kUsbFeatureAHnpSupport = 4, // recipient is device only if OTG
+ kUsbFeatureAAltHnpSupport = 5 // recipient is device only if OTG
+} usb_feature_req_t;
+
+typedef enum usb_status {
+ kUsbStatusSelfPowered = 1, // Device status request
+ kUsbStatusRemWake = 2, // Device status request
+ kUsbStatusHalted = 1 // Endpoint status request
+} usb_status_t;
+
+#endif // _USB_CONSTS_H_
diff --git a/sw/lib/usb_controlep.c b/sw/lib/usb_controlep.c
new file mode 100644
index 0000000..7327f8a
--- /dev/null
+++ b/sw/lib/usb_controlep.c
@@ -0,0 +1,243 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+// Get NULL from here
+#include "usb_controlep.h"
+
+#include <stddef.h>
+
+#include "common.h"
+#include "usb_consts.h"
+#include "usbdev.h"
+
+// Device descriptor
+static uint8_t dev_dscr[] = {
+ 18, // bLength
+ 1, // bDescriptorType
+ 0x00, // bcdUSB[0]
+ 0x02, // bcdUSB[1]
+ 0x00, // bDeviceClass (defined at interface level)
+ 0x00, // bDeviceSubClass
+ 0x00, // bDeviceProtocol
+ 64, // bMaxPacketSize0
+
+ 0xd1, // idVendor[0] 0x18d1 Google Inc.
+ 0x18, // idVendor[1]
+ 0x3a, // idProduct[0] lowRISC generic FS USB
+ 0x50, // idProduct[1] (allocated by Google)
+
+ 0, // bcdDevice[0]
+ 0x1, // bcdDevice[1]
+ 0, // iManufacturer
+ 0, // iProduct
+ 0, // iSerialNumber
+ 1 // bNumConfigurations
+};
+
+static ctstate_t setup_req(usb_controlep_ctx_t *ctctx, void *ctx,
+ usbbufid_t buf, int bmRequestType, int bRequest,
+ int wValue, int wIndex, int wLength) {
+ size_t len;
+ uint32_t stat;
+ int zero, type;
+ switch (bRequest) {
+ case kUsbSetupReqGetDescriptor:
+ if ((wValue & 0xff00) == 0x100) {
+ // Device descriptor
+ len = sizeof(dev_dscr);
+ if (wLength < len) {
+ len = wLength;
+ }
+ usbdev_buf_copyto_byid(ctx, buf, dev_dscr, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+ } else if ((wValue & 0xff00) == 0x200) {
+ // Configuration descriptor
+ len = ctctx->cfg_dscr_len;
+ if (wLength < len) {
+ len = wLength;
+ }
+ usbdev_buf_copyto_byid(ctx, buf, ctctx->cfg_dscr, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+ }
+ return kCtIdle; // unknown
+
+ case kUsbSetupReqSetAddress:
+ ctctx->new_dev = wValue & 0x7f;
+ // send zero length packet for status phase
+ usbdev_sendbuf_byid(ctx, buf, 0, ctctx->ep);
+ return kCtAddrStatIn;
+
+ case kUsbSetupReqSetConfiguration:
+ // only ever expect this to be 1 since there is one config descriptor
+ ctctx->usb_config = wValue;
+ // send zero length packet for status phase
+ usbdev_sendbuf_byid(ctx, buf, 0, ctctx->ep);
+ return kCtStatIn;
+
+ case kUsbSetupReqGetConfiguration:
+ len = sizeof(ctctx->usb_config);
+ if (wLength < len) {
+ len = wLength;
+ }
+ // return the value that was set
+ usbdev_buf_copyto_byid(ctx, buf, &ctctx->usb_config, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+
+ case kUsbSetupReqSetFeature:
+ if (wValue == kUsbFeatureEndpointHalt) {
+ usbdev_halt(ctx, wIndex, 1);
+ } else if (wValue == kUsbFeatureDeviceRemoteWakeup) {
+ usbdev_rem_wake_en(ctx, 1);
+ }
+ // send zero length packet for status phase
+ usbdev_sendbuf_byid(ctx, buf, 0, ctctx->ep);
+ return kCtStatIn;
+
+ case kUsbSetupReqClearFeature:
+ if (wValue == kUsbFeatureEndpointHalt) {
+ usbdev_halt(ctx, wIndex, 0);
+ } else if (wValue == kUsbFeatureDeviceRemoteWakeup) {
+ usbdev_rem_wake_en(ctx, 0);
+ }
+ // send zero length packet for status phase
+ usbdev_sendbuf_byid(ctx, buf, 0, ctctx->ep);
+ return kCtStatIn;
+
+ case kUsbSetupReqGetStatus:
+ len = 2;
+ type = bmRequestType & kUsbReqTypeRecipientMask;
+ if (type == kUsbReqTypeDevice) {
+ stat = (usbdev_can_rem_wake(ctx) ? kUsbStatusRemWake : 0) |
+ kUsbStatusSelfPowered;
+ } else if (type == kUsbReqTypeEndpoint) {
+ stat = usbdev_halted(ctx, wIndex) ? kUsbStatusHalted : 0;
+ } else {
+ stat = 0;
+ }
+ if (wLength < len) {
+ len = wLength;
+ }
+ // return the value that was set
+ usbdev_buf_copyto_byid(ctx, buf, &stat, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+
+ case kUsbSetupReqSetInterface:
+ // Don't support alternate interfaces, so just ignore
+ // send zero length packet for status phase
+ usbdev_sendbuf_byid(ctx, buf, 0, ctctx->ep);
+ return kCtStatIn;
+
+ case kUsbSetupReqGetInterface:
+ zero = 0;
+ len = 1;
+ if (wLength < len) {
+ len = wLength;
+ }
+ // Don't support interface, so return zero
+ usbdev_buf_copyto_byid(ctx, buf, &zero, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+
+ case kUsbSetupReqSynchFrame:
+ zero = 0;
+ len = 2;
+ if (wLength < len) {
+ len = wLength;
+ }
+ // Don't support synch_frame so return zero
+ usbdev_buf_copyto_byid(ctx, buf, &zero, len);
+ usbdev_sendbuf_byid(ctx, buf, len, ctctx->ep);
+ return kCtWaitIn;
+ }
+ return kCtError;
+}
+
+static void ctrl_tx_done(void *ctctx_v) {
+ usb_controlep_ctx_t *ctctx = (usb_controlep_ctx_t *)ctctx_v;
+ void *ctx = ctctx->ctx;
+ TRC_C('A' + ctctx->ctrlstate);
+ switch (ctctx->ctrlstate) {
+ case kCtAddrStatIn:
+ // Now the status was sent on device 0 can switch to new device ID
+ usbdev_set_deviceid(ctx, ctctx->new_dev);
+ TRC_I(ctctx->new_dev, 8);
+ ctctx->ctrlstate = kCtIdle;
+ return;
+ case kCtStatIn:
+ ctctx->ctrlstate = kCtIdle;
+ return;
+ case kCtWaitIn:
+ ctctx->ctrlstate = kCtStatOut;
+ return;
+ default:
+ break;
+ }
+ TRC_S("USB: unexpected IN ");
+ TRC_I((ctctx->ctrlstate << 24), 32);
+}
+
+static void ctrl_rx(void *ctctx_v, usbbufid_t buf, int size, int setup) {
+ usb_controlep_ctx_t *ctctx = (usb_controlep_ctx_t *)ctctx_v;
+ void *ctx = ctctx->ctx;
+ volatile uint8_t *bp = (volatile uint8_t *)usbdev_buf_idtoaddr(ctx, buf);
+ if (size > BUF_LENGTH) {
+ size = BUF_LENGTH;
+ }
+
+ TRC_C('0' + ctctx->ctrlstate);
+ switch (ctctx->ctrlstate) {
+ case kCtIdle:
+ // Waiting to be set up
+ if (setup && (size == 8)) {
+ int bmRequestType = bp[0];
+ int bRequest = bp[1];
+ int wValue = (bp[3] << 8) | bp[2];
+ int wIndex = (bp[5] << 8) | bp[4];
+ int wLength = (bp[7] << 8) | bp[6];
+ TRC_C('0' + bRequest);
+
+ ctctx->ctrlstate = setup_req(ctctx, ctx, buf, bmRequestType, bRequest,
+ wValue, wIndex, wLength);
+ if (ctctx->ctrlstate != kCtError) {
+ return;
+ }
+ }
+ break;
+
+ case kCtStatOut:
+ // Have sent some data, waiting STATUS stage
+ if (!setup && (size == 0)) {
+ ctctx->ctrlstate = kCtIdle;
+ return;
+ }
+ // anything else is unexpected
+ break;
+
+ default:
+ // Error
+ break;
+ }
+ TRC_S("USB: unCT ");
+ TRC_I((ctctx->ctrlstate << 24) | setup << 16 | size, 32);
+ TRC_C(':');
+ for (int i = 0; i < size; i++) {
+ TRC_I(bp[i], 8);
+ TRC_C(' ');
+ }
+ usbdev_buf_free_byid(ctx, buf);
+ ctctx->ctrlstate = kCtIdle;
+}
+
+void usb_controlep_init(usb_controlep_ctx_t *ctctx, usbdev_ctx_t *ctx, int ep,
+ const uint8_t *cfg_dscr, size_t cfg_dscr_len) {
+ ctctx->ctx = ctx;
+ usbdev_endpoint_setup(ctx, ep, 1, ctctx, ctrl_tx_done, ctrl_rx, NULL);
+ ctctx->ctrlstate = kCtIdle;
+ ctctx->cfg_dscr = cfg_dscr;
+ ctctx->cfg_dscr_len = cfg_dscr_len;
+}
diff --git a/sw/lib/usb_controlep.h b/sw/lib/usb_controlep.h
new file mode 100644
index 0000000..3be4840
--- /dev/null
+++ b/sw/lib/usb_controlep.h
@@ -0,0 +1,96 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef __USB_CONTROLEP_H__
+#define __USB_CONTROLEP_H__
+#include <stddef.h>
+
+#include "common.h"
+#include "usbdev.h"
+
+typedef enum ctstate {
+ kCtIdle,
+ kCtWaitIn, // Queued IN data stage, waiting ack
+ kCtStatOut, // Waiting for OUT status stage
+ kCtAddrStatIn, // Queued status stage, waiting ack afterwhich set dev_addr
+ kCtStatIn, // Queued status stage, waiting ack
+ kCtError // Something bad
+} ctstate_t;
+
+typedef struct usb_controlep_ctx {
+ usbdev_ctx_t *ctx;
+ int ep;
+ ctstate_t ctrlstate;
+ uint32_t new_dev;
+ uint8_t usb_config;
+ const uint8_t *cfg_dscr;
+ size_t cfg_dscr_len;
+} usb_controlep_ctx_t;
+
+/**
+ * Initialize control endpoint
+ *
+ * @param ctctx uninitialized context for this instance
+ * @param ctx initialized context for usbdev driver
+ * @param ep endpoint (if this is other than 0 make sure you know why)
+ * @param cfg_dscr configuration descriptor for the device
+ * @param cfg_dscr_len length of cfg_dscr
+ */
+void usb_controlep_init(usb_controlep_ctx_t *ctctx, usbdev_ctx_t *ctx, int ep,
+ const uint8_t *cfg_dscr, size_t cfg_dscr_len);
+
+/********************************************************************/
+/* Below this point are macros used to construct the USB descriptor */
+/* Use them to initialize a uint8_t array for cfg_dscr */
+
+#define USB_CFG_DSCR_LEN 9
+#define USB_CFG_DSCR_HEAD(total_len, nint) \
+ /* This is the actual configuration descriptor */ \
+ USB_CFG_DSCR_LEN, /* bLength */ \
+ 2, /* bDescriptorType */ \
+ (total_len)&0xff, /* wTotalLength[0] */ \
+ (total_len) >> 8, /* wTotalLength[1] */ \
+ (nint), /* bNumInterfaces */ \
+ 1, /* bConfigurationValu */ \
+ 0, /* iConfiguration */ \
+ 0xC0, /* bmAttributes: must-be-one, self-powered */ \
+ 50, /* bMaxPower */ /* MUST be followed \
+ by (nint) \
+ Interface + \
+ Endpoint \
+ Descriptors */
+
+// KEEP BLANK LINE ABOVE, it is in the macro!
+
+#define USB_INTERFACE_DSCR_LEN 9
+#define VEND_INTERFACE_DSCR(inum, nep, subclass, protocol) \
+ /* interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12 */ \
+ USB_INTERFACE_DSCR_LEN, /* bLength */ \
+ 4, /* bDescriptorType */ \
+ (inum), /* bInterfaceNumber */ \
+ 0, /* bAlternateSetting */ \
+ (nep), /* bNumEndpoints */ \
+ 0xff, /* bInterfaceClass (Vendor Specific) */ \
+ (subclass), /* bInterfaceSubClass */ \
+ (protocol), /* bInterfaceProtocol */ \
+ 0, /* iInterface */ /* MUST be followed by \
+ (nep) Endpoint \
+ Descriptors */
+
+// KEEP BLANK LINE ABOVE, it is in the macro!
+
+#define USB_EP_DSCR_LEN 7
+#define USB_BULK_EP_DSCR(in, ep, maxsize, interval) \
+ /* endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13 */ \
+ USB_EP_DSCR_LEN, /* bLength */ \
+ 5, /* bDescriptorType */ \
+ (ep) | (((in) << 7) & 0x80), /* bEndpointAddress, top bit set for IN */ \
+ 0x02, /* bmAttributes (0x02=bulk, data) */ \
+ (maxsize)&0xff, /* wMaxPacketSize[0] */ \
+ (maxsize) >> 8, /* wMaxPacketSize[1] */ \
+ (interval), /* bInterval */
+
+// KEEP BLANK LINE ABOVE, it is in the macro!
+
+#endif
diff --git a/sw/lib/usb_simpleserial.c b/sw/lib/usb_simpleserial.c
new file mode 100644
index 0000000..0268768
--- /dev/null
+++ b/sw/lib/usb_simpleserial.c
@@ -0,0 +1,80 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+// Get NULL from here
+#include "usb_simpleserial.h"
+
+#include <stddef.h>
+
+#include "common.h"
+#include "usbdev.h"
+
+#define MAX_GATHER 16
+
+static void ss_rx(void *ssctx_v, usbbufid_t buf, int size, int setup) {
+ usb_ss_ctx_t *ssctx = (usb_ss_ctx_t *)ssctx_v;
+ void *ctx = ssctx->ctx;
+ volatile uint8_t *bp = (volatile uint8_t *)usbdev_buf_idtoaddr(ctx, buf);
+
+ if (size > BUF_LENGTH) {
+ size = BUF_LENGTH;
+ }
+
+ while (size--) {
+ ssctx->got_byte(*bp++);
+ }
+}
+
+// Called periodically by the main loop to ensure characters don't
+// stick around too long
+static void ss_flush(void *ssctx_v) {
+ usb_ss_ctx_t *ssctx = (usb_ss_ctx_t *)ssctx_v;
+ void *ctx = ssctx->ctx;
+ volatile uint32_t *bp_w;
+ if ((ssctx->cur_buf == -1) || (ssctx->cur_cpos <= 0)) {
+ return;
+ }
+ if ((ssctx->cur_cpos & 0x3) != 0) {
+ // unwritten data to copy over
+ bp_w = usbdev_buf_idtoaddr(ctx, ssctx->cur_buf);
+ // no -1 here because cpos is in the word we are writing
+ bp_w[(ssctx->cur_cpos / 4)] = ssctx->chold.data_w;
+ }
+ usbdev_sendbuf_byid(ctx, ssctx->cur_buf, ssctx->cur_cpos, ssctx->ep);
+ ssctx->cur_buf = -1; // given it to the hardware
+}
+
+// Simple send byte will gather data for a while and send
+void usb_simpleserial_send_byte(usb_ss_ctx_t *ssctx, uint8_t c) {
+ volatile uint32_t *bp_w;
+ if (ssctx->cur_buf == -1) {
+ ssctx->cur_buf = usbdev_buf_allocate_byid(ssctx->ctx);
+ ssctx->cur_cpos = 0;
+ }
+ // Abort if completely out of buffers and allocation returned -1
+ if (ssctx->cur_buf < 0) {
+ return;
+ }
+ ssctx->chold.data_b[ssctx->cur_cpos++ & 0x3] = c;
+ if ((ssctx->cur_cpos & 0x3) == 0) {
+ // just wrote last byte in word
+ bp_w = usbdev_buf_idtoaddr(ssctx->ctx, ssctx->cur_buf);
+ // -1 here because cpos already incremented to next word
+ bp_w[(ssctx->cur_cpos / 4) - 1] = ssctx->chold.data_w;
+ if (ssctx->cur_cpos >= MAX_GATHER) {
+ usbdev_sendbuf_byid(ssctx->ctx, ssctx->cur_buf, ssctx->cur_cpos,
+ ssctx->ep);
+ ssctx->cur_buf = -1; // given it to the hardware
+ }
+ }
+}
+
+void usb_simpleserial_init(usb_ss_ctx_t *ssctx, usbdev_ctx_t *ctx, int ep,
+ void (*got_byte)(uint8_t)) {
+ usbdev_endpoint_setup(ctx, ep, 1, ssctx, NULL, ss_rx, ss_flush);
+ ssctx->ctx = ctx;
+ ssctx->ep = ep;
+ ssctx->got_byte = got_byte;
+ ssctx->cur_buf = -1;
+}
diff --git a/sw/lib/usb_simpleserial.h b/sw/lib/usb_simpleserial.h
new file mode 100644
index 0000000..52ca8be
--- /dev/null
+++ b/sw/lib/usb_simpleserial.h
@@ -0,0 +1,42 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef __USB_SIMPLESERIAL_H__
+#define __USB_SIMPLESERIAL_H__
+
+#include "common.h"
+#include "usbdev.h"
+
+// This is only here because caller of _init needs it
+typedef struct usb_ss_ctx {
+ void *ctx;
+ int ep;
+ int cur_buf;
+ int cur_cpos;
+ union usb_ss_b2w {
+ uint32_t data_w;
+ uint8_t data_b[4];
+ } chold;
+ void (*got_byte)(uint8_t);
+} usb_ss_ctx_t;
+
+/**
+ * Send a byte on a simpleserial endpoint
+ * ssctx - instance context
+ * c - byte to send
+ */
+void usb_simpleserial_send_byte(usb_ss_ctx_t *ssctx, uint8_t c);
+
+/**
+ * Initialize a simpleserial endpoint
+ *
+ * ctx - initialized usbdev context
+ * ep - endpoint number for this instance
+ * ssctx - unintialized simpleserial instance context
+ * got_byte - callback function for when a byte is received
+ */
+void usb_simpleserial_init(usb_ss_ctx_t *ssctx, usbdev_ctx_t *ctx, int ep,
+ void (*got_byte)(uint8_t));
+
+#endif
diff --git a/sw/lib/usbdev.c b/sw/lib/usbdev.c
new file mode 100644
index 0000000..96d6b55
--- /dev/null
+++ b/sw/lib/usbdev.c
@@ -0,0 +1,225 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+// Get NULL from here
+#include "usbdev.h"
+
+#include <stddef.h>
+
+#include "common.h"
+
+#define USBDEV_BASE_ADDR 0x40020000
+
+#include "usbdev_regs.h"
+#define EXTRACT(n, f) ((n >> USBDEV_##f##_OFFSET) & USBDEV_##f##_MASK)
+
+// Free buffer pool is held on a simple stack
+// Initalize to all buffer IDs are free
+static void buf_init(usbdev_ctx_t *ctx) {
+ for (int i = 0; i < NUM_BUFS; i++) {
+ ctx->freebuf[i] = i;
+ }
+ ctx->nfree = NUM_BUFS;
+}
+
+// Allocating a buffer just pops next ID from the stack
+usbbufid_t usbdev_buf_allocate_byid(usbdev_ctx_t *ctx) {
+ if (ctx->nfree <= 0) {
+ return -1;
+ }
+ return ctx->freebuf[--ctx->nfree];
+}
+
+// Freeing a buffer just pushes the ID back on the stack
+int usbdev_buf_free_byid(usbdev_ctx_t *ctx, usbbufid_t buf) {
+ if ((ctx->nfree >= NUM_BUFS) || (buf >= NUM_BUFS)) {
+ return -1;
+ }
+ ctx->freebuf[ctx->nfree++] = buf;
+ return 0;
+}
+
+uint32_t *usbdev_buf_idtoaddr(usbdev_ctx_t *ctx, usbbufid_t buf) {
+ return (uint32_t *)(USBDEV_BUFFER(USBDEV_BASE_ADDR) + (buf * BUF_LENGTH));
+}
+
+void usbdev_buf_copyto_byid(usbdev_ctx_t *ctx, usbbufid_t buf, const void *from,
+ size_t len_bytes) {
+ int32_t *from_word = (int32_t *)from;
+ int len_words;
+ volatile uint32_t *bp = usbdev_buf_idtoaddr(ctx, buf);
+
+ if (len_bytes > BUF_LENGTH) {
+ len_bytes = BUF_LENGTH;
+ }
+ // This will round up if len_bytes is not on a multiple of int32_t
+ // Always ok to fill the extra bytes since the buffers are aligned
+ len_words = (len_bytes + sizeof(int32_t) - 1) / sizeof(int32_t);
+ for (int i = 0; i < len_words; i++) {
+ bp[i] = from_word[i];
+ }
+}
+
+// Supply as many buffers to the receive available fifo as possible
+inline static void fill_av_fifo(usbdev_ctx_t *ctx) {
+ while (!(REG32(USBDEV_USBSTAT()) & (1 << USBDEV_USBSTAT_AV_FULL))) {
+ usbbufid_t buf = usbdev_buf_allocate_byid(ctx);
+ if (buf < 0) {
+ // no more free buffers, can't fill AV FIFO
+ break;
+ }
+ REG32(USBDEV_AVBUFFER()) = buf;
+ }
+}
+
+void usbdev_sendbuf_byid(usbdev_ctx_t *ctx, usbbufid_t buf, size_t size,
+ int endpoint) {
+ uint32_t configin = USBDEV_CONFIGIN0() + (4 * endpoint);
+
+ if ((endpoint >= NUM_ENDPOINTS) || (buf >= NUM_BUFS)) {
+ return;
+ }
+
+ if (size > BUF_LENGTH) {
+ size = BUF_LENGTH;
+ }
+
+ REG32(configin) =
+ ((buf << USBDEV_CONFIGIN0_BUFFER0_OFFSET) |
+ (size << USBDEV_CONFIGIN0_SIZE0_OFFSET) | (1 << USBDEV_CONFIGIN0_RDY0));
+}
+
+void usbdev_poll(usbdev_ctx_t *ctx) {
+ uint32_t istate = REG32(USBDEV_INTR_STATE());
+
+ // Do this first to keep things going
+ fill_av_fifo(ctx);
+
+ // Process IN completions first so we get the fact that send completed
+ // before processing a response
+ if (istate & (1 << USBDEV_INTR_STATE_PKT_SENT)) {
+ uint32_t sentep = REG32(USBDEV_IN_SENT());
+ uint32_t configin = USBDEV_CONFIGIN0();
+ TRC_C('a' + sentep);
+ for (int ep = 0; ep < NUM_ENDPOINTS; ep++) {
+ if (sentep & (1 << ep)) {
+ // Free up the buffer and optionally callback
+ int32_t cfgin = REG32(configin + (4 * ep));
+ usbdev_buf_free_byid(ctx, EXTRACT(cfgin, CONFIGIN0_BUFFER0));
+ if (ctx->tx_done_callback[ep]) {
+ ctx->tx_done_callback[ep](ctx->ep_ctx[ep]);
+ }
+ }
+ }
+ // Write one to clear all the ones we handled
+ REG32(USBDEV_IN_SENT()) = sentep;
+ // Clear the interupt
+ REG32(USBDEV_INTR_STATE()) = (1 << USBDEV_INTR_STATE_PKT_SENT);
+ }
+
+ if (istate & (1 << USBDEV_INTR_STATE_PKT_RECEIVED)) {
+ while (!(REG32(USBDEV_USBSTAT()) & (1 << USBDEV_USBSTAT_RX_EMPTY))) {
+ uint32_t rxinfo = REG32(USBDEV_RXFIFO());
+ usbbufid_t buf = EXTRACT(rxinfo, RXFIFO_BUFFER);
+ int size = EXTRACT(rxinfo, RXFIFO_SIZE);
+ int endpoint = EXTRACT(rxinfo, RXFIFO_EP);
+ int setup = (rxinfo >> USBDEV_RXFIFO_SETUP) & 1;
+
+ if (ctx->rx_callback[endpoint]) {
+ ctx->rx_callback[endpoint](ctx->ep_ctx[endpoint], buf, size, setup);
+ } else {
+ TRC_S("USB: unexpected RX ");
+ TRC_I(rxinfo, 24);
+ }
+ usbdev_buf_free_byid(ctx, buf);
+ }
+ // Clear the interupt
+ REG32(USBDEV_INTR_STATE()) = (1 << USBDEV_INTR_STATE_PKT_RECEIVED);
+ }
+ if (istate & ~((1 << USBDEV_INTR_STATE_PKT_RECEIVED) |
+ (1 << USBDEV_INTR_STATE_PKT_SENT))) {
+ TRC_C('I');
+ TRC_I(istate, 12);
+ TRC_C(' ');
+ REG32(USBDEV_INTR_STATE()) =
+ istate & ~((1 << USBDEV_INTR_STATE_PKT_RECEIVED) |
+ (1 << USBDEV_INTR_STATE_PKT_SENT));
+ }
+ // TODO(mdhayter) - clean this up
+ // Frame ticks every 1ms, use to flush data every 16ms
+ // (faster in DPI but this seems to work ok)
+ // At reset frame count is 0, compare to 1 so no calls before SOF received
+ uint32_t usbframe = EXTRACT(REG32(USBDEV_USBSTAT()), USBSTAT_FRAME);
+ if ((usbframe & 0xf) == 1) {
+ if (ctx->flushed == 0) {
+ for (int i = 0; i < NUM_ENDPOINTS; i++) {
+ if (ctx->flush[i]) {
+ ctx->flush[i](ctx->ep_ctx[i]);
+ }
+ }
+ ctx->flushed = 1;
+ }
+ } else {
+ ctx->flushed = 0;
+ }
+ // TODO(mdhater) Errors? What Errors?
+}
+
+void usbdev_set_deviceid(usbdev_ctx_t *ctx, int deviceid) {
+ REG32(USBDEV_USBCTRL()) = (1 << USBDEV_USBCTRL_ENABLE) |
+ (deviceid << USBDEV_USBCTRL_DEVICE_ADDRESS_OFFSET);
+}
+
+void usbdev_halt(usbdev_ctx_t *ctx, int endpoint, int enable) {
+ uint32_t epbit = 1 << endpoint;
+ uint32_t stall = REG32(USBDEV_STALL());
+ if (enable) {
+ stall |= epbit;
+ } else {
+ stall &= ~epbit;
+ }
+ REG32(USBDEV_STALL()) = stall;
+ ctx->halted = stall;
+ // TODO future addition would be to callback the endpoint driver
+ // for now it just sees its traffic has stopped
+}
+
+// TODO got hang with this inline
+int usbdev_can_rem_wake(usbdev_ctx_t *ctx) { return ctx->can_wake; }
+
+void usbdev_endpoint_setup(usbdev_ctx_t *ctx, int ep, int enableout,
+ void *ep_ctx, void (*tx_done)(void *),
+ void (*rx)(void *, usbbufid_t, int, int),
+ void (*flush)(void *)) {
+ ctx->ep_ctx[ep] = ep_ctx;
+ ctx->tx_done_callback[ep] = tx_done;
+ ctx->rx_callback[ep] = rx;
+ ctx->flush[ep] = flush;
+ if (enableout) {
+ uint32_t rxen = REG32(USBDEV_RXENABLE());
+ rxen |= (1 << (ep + USBDEV_RXENABLE_OUT0));
+ REG32(USBDEV_RXENABLE()) = rxen;
+ }
+}
+
+void usbdev_init(usbdev_ctx_t *ctx) {
+ // setup context
+ for (int i = 0; i < NUM_ENDPOINTS; i++) {
+ usbdev_endpoint_setup(ctx, i, 0, NULL, NULL, NULL, NULL);
+ }
+ ctx->halted = 0;
+ ctx->can_wake = 0;
+ buf_init(ctx);
+
+ // All about polling...
+ REG32(USBDEV_INTR_ENABLE()) = 0;
+
+ // Provide buffers for any reception
+ fill_av_fifo(ctx);
+
+ REG32(USBDEV_RXENABLE()) =
+ ((1 << USBDEV_RXENABLE_SETUP0) | (1 << USBDEV_RXENABLE_OUT0));
+
+ REG32(USBDEV_USBCTRL()) = (1 << USBDEV_USBCTRL_ENABLE);
+}
diff --git a/sw/lib/usbdev.h b/sw/lib/usbdev.h
new file mode 100644
index 0000000..003a388
--- /dev/null
+++ b/sw/lib/usbdev.h
@@ -0,0 +1,183 @@
+// Copyright lowRISC contributors.
+// Licensed under the Apache License, Version 2.0, see LICENSE for details.
+// SPDX-License-Identifier: Apache-2.0
+
+#ifndef _USBDEV_H_
+#define _USBDEV_H_
+
+#include <stddef.h>
+#include <stdint.h>
+
+// Hardware parameters
+#define NUM_BUFS 32
+#define BUF_LENGTH 64
+#define NUM_ENDPOINTS 12
+
+// USB buffers are held in the SRAM in the interface, referenced by ID
+// Buffer IDs are 0 to NUM_BUFS
+// Use negative buffer ID for error
+typedef int usbbufid_t;
+typedef struct usbdev_ctx usbdev_ctx_t;
+
+// Note: this is only needed here because the caller of init needs it
+struct usbdev_ctx {
+ // TODO: base_addr goes here once header files support using it
+ int can_wake;
+ uint8_t freebuf[NUM_BUFS];
+ uint32_t halted; // bit vector per endpoint
+ int nfree;
+ int flushed;
+ usbdev_ctx_t *ep_ctx[NUM_ENDPOINTS];
+ void (*tx_done_callback[NUM_ENDPOINTS])(void *);
+ void (*rx_callback[NUM_ENDPOINTS])(void *, usbbufid_t, int, int);
+ void (*flush[NUM_ENDPOINTS])(void *);
+};
+
+/**
+ * Allocate a buffer for the caller to use
+ *
+ * @param ctx usbdev context pointer
+ * @return buffer ID or negative for out of buffer error
+ */
+usbbufid_t usbdev_buf_allocate_byid(usbdev_ctx_t *ctx);
+
+/**
+ * Free a buffer when caller no longer needs it
+ *
+ * @param ctx usbdev context pointer
+ * @param buf buffer ID being returned to free pool
+ * @return 0 or -1 if the free pool is full (shouldn't happen)
+ */
+int usbdev_buf_free_byid(usbdev_ctx_t *ctx, usbbufid_t buf);
+
+/**
+ * Get memory address for accessing data in a buffer
+ *
+ * Hardware restriction: buffer can only be written with 32-bit words
+ * Ok to cast the return value to int8_t * for reading
+ *
+ * @param ctx usbdev context pointer
+ * @param buf buffer ID to access
+ * @return pointer to access the data of @p buf
+ */
+uint32_t *usbdev_buf_idtoaddr(usbdev_ctx_t *ctx, usbbufid_t buf);
+
+/**
+ * Copy from memory into a buffer, referencing by buffer ID
+ *
+ * Implementation restriction: from must be 4-byte aligned
+ * TODO(mdhayer) remove restriction
+ *
+ * @param ctx usbdev context pointer
+ * @param buf buffer ID to copy to
+ * @param from source address for data
+ * @param len_bytes length in bytes of data to copy
+ */
+void usbdev_buf_copyto_byid(usbdev_ctx_t *ctx, usbbufid_t buf, const void *from,
+ size_t len_bytes);
+
+/**
+ * Schedule a buffer for transmission on an endpoint
+ *
+ * Send happens on next IN request for that endpoint from the host.
+ * Once this call is made the buffer is owned by the hardware
+ *
+ * @param ctx usbdev context pointer
+ * @param buf buffer ID to send
+ * @param size length in bytes of data to send, zero is valid (used as ack)
+ * @param endpoint endpoint to send from
+ */
+void usbdev_sendbuf_byid(usbdev_ctx_t *ctx, usbbufid_t buf, size_t size,
+ int endpoint);
+
+/**
+ * Call regularly to poll the usbdev interface
+ *
+ * @param ctx usbdev context pointer
+ */
+void usbdev_poll(usbdev_ctx_t *ctx);
+
+/**
+ * Set the USB device ID
+ *
+ * Device ID must be zero at init. When the host assigns an ID
+ * with a SET_ADDRESS packet and the complete SETUP transaction is
+ * complete, this function should be called to set the new ID. Note
+ * on a reset the hardware will clear the device ID back to 0.
+ *
+ * @param usbdev context pointer
+ * @param new deviceid
+ */
+void usbdev_set_deviceid(usbdev_ctx_t *ctx, int deviceid);
+
+/**
+ * Halt or release an endpoint
+ *
+ * By default endpoints are enabled, but they can be halted but the host
+ *
+ * @param usbdev context pointer
+ * @param endpoint number
+ * @param enable set/clear
+ */
+void usbdev_halt(usbdev_ctx_t *ctx, int endpoint, int enable);
+
+/**
+ * Get halted status for an endpoint
+ *
+ * @param usbdev context pointer
+ * @return 1 if endpoint is halted else 0
+ */
+inline int usbdev_halted(usbdev_ctx_t *ctx, int endpoint) {
+ return (ctx->halted >> endpoint) & 0x1;
+}
+
+/**
+ * Enable or disable remote wake
+ *
+ * @param usbdev context pointer
+ * @param enable set/clear
+ */
+inline void usbdev_rem_wake_en(usbdev_ctx_t *ctx, int enable) {
+ ctx->can_wake = (enable) ? 1 : 0;
+}
+
+/**
+ * Get ability to wake the host
+ *
+ * @param usbdev context pointer
+ * @return 1 if remote wake is permitted else 0
+ */
+int usbdev_can_rem_wake(usbdev_ctx_t *ctx);
+
+/**
+ * Call to setup an endpoint
+ *
+ * @param ctx usbdev context pointer
+ * @param ep endpoint number
+ * @param enableout boolean, true to enable OUT transactions on the endpoint
+ * (OUT means host->device, ie receive by us)
+ * @param ep_ctx context pointer for callee
+ * @param tx_done(void *ep_ctx) callback once send has been Acked
+ * @param rx(void *ep_ctx, usbbufid_t buf, int size, int setup)
+ called when a packet is received
+ * @param flush(void *ep_ctx) called every 16ms based USB host timebase
+ */
+void usbdev_endpoint_setup(usbdev_ctx_t *ctx, int ep, int enableout,
+ void *ep_ctx, void (*tx_done)(void *),
+ void (*rx)(void *, usbbufid_t, int, int),
+ void (*flush)(void *));
+
+/**
+ * Initialize the usbdev interface
+ *
+ * @param ctx uninitialized usbdev context pointer
+ */
+void usbdev_init(usbdev_ctx_t *ctx);
+
+// Used for tracing what is going on
+#include "uart.h"
+#define TRC_S(s) uart_send_str(s)
+#define TRC_I(i, b) uart_send_uint(i, b)
+#define TRC_C(c) uart_send_char(c)
+
+#endif