Create separate xspn-fpga FW

Add xspn data for different accelerators
This commit is contained in:
2021-03-04 11:19:35 +01:00
parent 7f8ddf3201
commit 6bfe684e73
110 changed files with 52472 additions and 35 deletions

22
fpga_spn/src/bsp.h Normal file
View File

@ -0,0 +1,22 @@
/*
* bsp.h
*
* Created on: 30.07.2018
* Author: eyck
*/
#ifndef BSP_H_
#define BSP_H_
#ifdef __cplusplus
extern "C" {
#endif
#include <fe300prci/fe300prci_driver.h>
#include <platform.h>
#include <encoding.h>
extern void trap_entry();
#ifdef __cplusplus
}
#endif
#endif /* BSP_H_ */

123
fpga_spn/src/delay.c Normal file
View File

@ -0,0 +1,123 @@
/*
* delay.c
*
* Created on: 30.07.2018
* Author: eyck
*/
#include "delay.h"
#define rdmcycle(x) { \
uint32_t lo, hi, hi2; \
__asm__ __volatile__ ("1:\n\t" \
"csrr %0, mcycleh\n\t" \
"csrr %1, mcycle\n\t" \
"csrr %2, mcycleh\n\t" \
"bne %0, %2, 1b\n\t" \
: "=r" (hi), "=r" (lo), "=r" (hi2)) ; \
*(x) = lo | ((uint64_t) hi << 32); \
}
typedef struct {
uint32_t n;
uint32_t mult;
uint32_t shift;
} int_inverse ;
int_inverse f_cpu_1000_inv;
int_inverse f_cpu_1000000_inv;
uint32_t F_CPU=1000000;
void calc_inv(uint32_t n, int_inverse * res){
uint32_t one = ~0;
uint32_t d = one/n;
uint32_t r = one%n + 1;
if (r >= n) ++d;
if (d == 0) --d;
uint32_t shift = 0;
while ((d & 0x80000000) == 0){
d <<= 1;
++shift;
}
res->n = n;
res->mult = d;
res->shift = shift;
}
uint32_t divide32_using_inverse(uint32_t n, int_inverse *inv){
uint32_t d = (uint32_t)(((uint64_t)n * inv->mult) >> 32);
d >>= inv->shift;
if (n - d*inv->n >= inv->n) ++d;
return d;
}
// Almost full-range 64/32 divide.
// If divisor-1 has i bits, then the answer is exact for n of up to 64-i bits
// e.g. for divisors up to a million, n can have up to 45 bits
// On RV32IM with divide32_using_inverse inlines this uses 5 multiplies,
// 33 instructions, zero branches, 3 loads, 0 stores.
uint64_t divide64_using_inverse(uint64_t n, int_inverse *inv){
uint32_t preshift = (31 - inv->shift) & 31;
uint64_t d = (uint64_t)divide32_using_inverse(n >> preshift, inv) << preshift;
uint32_t r = n - d * inv->n;
d += divide32_using_inverse(r, inv);
return d;
}
uint32_t millis(){
uint64_t x;
rdmcycle(&x);
x = divide64_using_inverse(x, &f_cpu_1000_inv);
return((uint32_t) (x & 0xFFFFFFFF));
}
uint32_t micros(void){
uint64_t x;
rdmcycle(&x);
// For Power-of-two MHz F_CPU,
// this compiles into a simple shift,
// and is faster than the general solution.
#if F_CPU==16000000
x = x / (F_CPU / 1000000);
#else
#if F_CPU==256000000
x = x / (F_CPU / 1000000);
#else
x = divide64_using_inverse(x, &f_cpu_1000000_inv);
#endif
#endif
return((uint32_t) (x & 0xFFFFFFFF));
}
void delayMS(uint32_t dwMs){
uint64_t current, later;
rdmcycle(&current);
later = current + dwMs * (F_CPU/1000);
if (later > current){ // usual case
while (later > current)
rdmcycle(&current);
} else { // wrap. Though this is unlikely to be hit w/ 64-bit mcycle
while (later < current)
rdmcycle(&current);
while (current < later)
rdmcycle(&current);
}
}
void delayUS(uint32_t dwUs){
uint64_t current, later;
rdmcycle(&current);
later = current + dwUs * (F_CPU/1000000);
if (later > current){ // usual case
while (later > current)
rdmcycle(&current);
} else {// wrap. Though this is unlikely to be hit w/ 64-bit mcycle
while (later < current)
rdmcycle(&current);
while (current < later)
rdmcycle(&current);
}
}

25
fpga_spn/src/delay.h Normal file
View File

@ -0,0 +1,25 @@
/*
* delay.h
*
* Created on: 30.07.2018
* Author: eyck
*/
#ifndef DELAY_H_
#define DELAY_H_
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t F_CPU;
void delayMS(uint32_t dwMs);
void delayUS(uint32_t dwUs);
#ifdef __cplusplus
}
#endif
#endif /* DELAY_H_ */

56
fpga_spn/src/dma_regs.h Normal file
View File

@ -0,0 +1,56 @@
#ifndef _DMA_REGS_H_
#define _DMA_REGS_H_
#include <util/bit_field.h>
#include <cstdint>
#define DMA_REG_START 0x00
#define DMA_REG_CLEAR_INTERRUPT 0x0C
#define DMA_REG_FPGA_ADDRESS 0x10
#define DMA_REG_SC_ADDRESS 0x20
#define DMA_REG_WRITE 0x30
#define DMA_REG_BYTES 0x40
template<uint32_t BASE_ADDR>
class dma_regs {
public:
// storage declarations
// BEGIN_BF_DECL(start_t, uint32_t);
// BF_FIELD(start, 0, 1);
// END_BF_DECL() r_start;
uint32_t r_start;
uint32_t r_address;
uint32_t r_write;
uint32_t r_bytes;
static inline uint32_t& start_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_START);
}
static inline uint32_t& clear_interrupt_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_CLEAR_INTERRUPT);
}
static inline uint32_t & fpga_address_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_FPGA_ADDRESS);
}
static inline uint32_t & sc_address_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_SC_ADDRESS);
}
static inline uint32_t & write_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_WRITE);
}
static inline uint32_t & bytes_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+DMA_REG_BYTES);
}
};
#endif // _SPN_REGS_H_

89
fpga_spn/src/init.h Normal file
View File

@ -0,0 +1,89 @@
#ifndef SRC_INIT_H_
#define SRC_INIT_H_
#include <cstdio>
#include <array>
#include "delay.h"
#include "bsp.h"
#include "plic/plic_driver.h"
typedef void (*function_ptr_t) (void);
//! Instance data for the PLIC.
plic_instance_t g_plic;
std::array<function_ptr_t,PLIC_NUM_INTERRUPTS> g_ext_interrupt_handlers;
bool hw_interrupt{true};
/*! \brief external interrupt handler
*
* routes the peripheral interrupts to the the respective handler
*
*/
extern "C" void handle_m_ext_interrupt() {
plic_source int_num = PLIC_claim_interrupt(&g_plic);
if ((int_num >=1 ) && (int_num < PLIC_NUM_INTERRUPTS))
g_ext_interrupt_handlers[int_num]();
else
exit(1 + (uintptr_t) int_num);
PLIC_complete_interrupt(&g_plic, int_num);
}
/*! \brief dummy interrupt handler
*
*/
void no_interrupt_handler (void) {};
/*! \brief configure the per-interrupt handler
*
*/
void configure_irq(size_t irq_num, function_ptr_t handler, unsigned char prio=1) {
g_ext_interrupt_handlers[irq_num] = handler;
// Priority must be set > 0 to trigger the interrupt.
PLIC_set_priority(&g_plic, irq_num, prio);
// Have to enable the interrupt both at the GPIO level, and at the PLIC level.
PLIC_enable_interrupt(&g_plic, irq_num);
}
static void msi_interrupt_handler(){
hw_interrupt = false;
}
void wait_for_interrupt() {
// wait until HW is done
if(hw_interrupt) {
do{
asm("wfi");
asm("nop");
}while(hw_interrupt);
}
hw_interrupt=true;
}
/*!\brief initializes platform
*
*/
void platform_init(){
// UART init section TODO: clarify how to get the functions from init.c?
GPIO_REG(GPIO_IOF_SEL) &= ~IOF0_UART0_MASK;
GPIO_REG(GPIO_IOF_EN) |= IOF0_UART0_MASK;
UART0_REG(UART_REG_TXCTRL) |= UART_TXEN;
F_CPU=PRCI_measure_mcycle_freq(20, RTC_FREQ);
printf("core freq at %d Hz\n", F_CPU);
// initialie interupt & trap handling
write_csr(mtvec, &trap_entry);
PLIC_init(&g_plic, PLIC_CTRL_ADDR, PLIC_NUM_INTERRUPTS, PLIC_NUM_PRIORITIES, 0);
// Disable the machine & timer interrupts until setup is done.
clear_csr(mie, MIP_MEIP);
clear_csr(mie, MIP_MTIP);
for (auto& h:g_ext_interrupt_handlers) h=no_interrupt_handler;
configure_irq(2, msi_interrupt_handler);
// Enable interrupts in general.
set_csr(mstatus, MSTATUS_MIE);
// Enable the Machine-External bit in MIE
set_csr(mie, MIP_MEIP);
//hw_interrupt = false;
}
#endif /* SRC_INIT_H_ */

89
fpga_spn/src/io/gpio.h Normal file
View File

@ -0,0 +1,89 @@
/*
* gpio.h
*
* Created on: 29.07.2018
* Author: eyck
*/
#ifndef GPIO_H_
#define GPIO_H_
#include <sifive/devices/gpio.h>
#include <cstdint>
template<uint32_t BASE_ADDR>
class gpio_regs {
public:
static inline uint32_t& value_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_INPUT_VAL);
}
static inline uint32_t& input_en_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_INPUT_EN);
}
static inline uint32_t& output_en_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_OUTPUT_EN);
}
static inline uint32_t& port_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_OUTPUT_VAL);
}
static inline uint32_t& pue_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_PULLUP_EN);
}
static inline uint32_t& ds_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_DRIVE);
}
static inline uint32_t& rise_ie_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_RISE_IE);
}
static inline uint32_t& rise_ip_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_RISE_IP);
}
static inline uint32_t& fall_ie_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_FALL_IE);
}
static inline uint32_t& fall_ip_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_FALL_IP);
}
static inline uint32_t& high_ie_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_HIGH_IE);
}
static inline uint32_t& high_ip_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_HIGH_IP);
}
static inline uint32_t& low_ie_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_LOW_IE);
}
static inline uint32_t& low_ip_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_LOW_IP);
}
static inline uint32_t& iof_en_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_IOF_EN);
}
static inline uint32_t& iof_sel_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_IOF_SEL);
}
static inline uint32_t& out_xor_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+GPIO_OUTPUT_XOR);
}
};
#endif /* GPIO_H_ */

122
fpga_spn/src/io/pwm.h Normal file
View File

@ -0,0 +1,122 @@
/*
* pwm.h
*
* Created on: 29.07.2018
* Author: eyck
*/
#ifndef PWM_H_
#define PWM_H_
#include <sifive/devices/pwm.h>
#include "util/bit_field.h"
#include <limits>
#include <cstdint>
template<uint32_t BASE_ADDR>
class pwm_regs {
public:
BEGIN_BF_DECL(pwmcfg_t, uint32_t);
BF_FIELD(scale, 0, 4);
BF_FIELD(sticky, 8, 1);
BF_FIELD(zerocmp, 9, 1);
BF_FIELD(deglitch, 10, 1);
BF_FIELD(enalways, 12, 1);
BF_FIELD(enoneshot, 13, 1);
BF_FIELD(cmp0center, 16, 1);
BF_FIELD(cmp1center, 17, 1);
BF_FIELD(cmp2center, 18, 1);
BF_FIELD(cmp3center, 19, 1);
BF_FIELD(cmp0gang, 24, 1);
BF_FIELD(cmp1gang, 25, 1);
BF_FIELD(cmp2gang, 26, 1);
BF_FIELD(cmp3gang, 27, 1);
BF_FIELD(cmp0ip, 28, 1);
BF_FIELD(cmp1ip, 29, 1);
BF_FIELD(cmp2ip, 30, 1);
BF_FIELD(cmp3ip, 31, 1);
END_BF_DECL();
BEGIN_BF_DECL(pwms_t, uint32_t);
BF_FIELD(s, 0, 16);
END_BF_DECL() r_pwms;
BEGIN_BF_DECL(pwmcmp0_t, uint32_t);
BF_FIELD(cmp0, 0, 16);
END_BF_DECL() r_pwmcmp0;
BEGIN_BF_DECL(pwmcmp1_t, uint32_t);
BF_FIELD(cmp0, 0, 16);
END_BF_DECL() r_pwmcmp1;
BEGIN_BF_DECL(pwmcmp2_t, uint32_t);
BF_FIELD(cmp0, 0, 16);
END_BF_DECL() r_pwmcmp2;
BEGIN_BF_DECL(pwmcmp3_t, uint32_t);
BF_FIELD(cmp0, 0, 16);
END_BF_DECL() r_pwmcmp3;
static inline pwmcfg_t& cfg_reg(){
return *reinterpret_cast<pwmcfg_t*>(BASE_ADDR+PWM_CFG);
}
static inline uint32_t& count_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+PWM_COUNT);
}
static inline pwms_t& s_reg(){
return *reinterpret_cast<pwms_t*>(BASE_ADDR+PWM_S);
}
static inline pwmcmp0_t& cmp0_reg(){
return *reinterpret_cast<pwmcmp0_t*>(BASE_ADDR+PWM_CMP0);
}
static inline pwmcmp1_t& cmp1_reg(){
return *reinterpret_cast<pwmcmp1_t*>(BASE_ADDR+PWM_CMP1);
}
static inline pwmcmp2_t& cmp2_reg(){
return *reinterpret_cast<pwmcmp2_t*>(BASE_ADDR+PWM_CMP2);
}
static inline pwmcmp3_t& cmp3_reg(){
return *reinterpret_cast<pwmcmp3_t*>(BASE_ADDR+PWM_CMP3);
}
static inline bool oneshot_delay(long delay_us){
auto scaling_factor=0;
while(delay_us/(1<<scaling_factor) > std::numeric_limits<unsigned short>::max()){
scaling_factor++;
}
cfg_reg()=0;
count_reg()=0;
cfg_reg().scale=4+scaling_factor; // divide by 16 so we get 1us per pwm clock
cmp0_reg().cmp0 = delay_us/(1<<scaling_factor);
pwm_active=true;
cfg_reg().enoneshot=true;
do{
asm("wfi");
asm("nop");
}while(pwm_active);
return true;
}
static void pwm_interrupt_handler(){
cfg_reg().cmp0ip=false;
pwm_active=false;
}
inline
static bool is_active(){ return pwm_active; }
inline
static void set_active() {pwm_active=true;}
private:
static volatile bool pwm_active;
};
#endif /* PWM_H_ */

200
fpga_spn/src/io/spi.h Normal file
View File

@ -0,0 +1,200 @@
/*
* spi.h
*
* Created on: 29.07.2018
* Author: eyck
*/
#ifndef SPI_H_
#define SPI_H_
#include <sifive/devices/spi.h>
#include "util/bit_field.h"
#include <array>
#include <cstdint>
template<uint32_t BASE_ADDR>
class spi_regs {
public:
// storage declarations
BEGIN_BF_DECL(sckdiv_t, uint32_t);
BF_FIELD(div, 0, 12);
END_BF_DECL();
BEGIN_BF_DECL(sckmode_t, uint32_t);
BF_FIELD(pha, 0, 1);
BF_FIELD(pol, 1, 1);
END_BF_DECL();
uint32_t r_csid;
uint32_t r_csdef;
BEGIN_BF_DECL(csmode_t, uint32_t);
BF_FIELD(mode, 0, 2);
END_BF_DECL();
BEGIN_BF_DECL(delay0_t, uint32_t);
BF_FIELD(cssck, 0, 8);
BF_FIELD(sckcs, 16, 8);
END_BF_DECL();
BEGIN_BF_DECL(delay1_t, uint32_t);
BF_FIELD(intercs, 0, 16);
BF_FIELD(interxfr, 16, 8);
END_BF_DECL();
BEGIN_BF_DECL(fmt_t, uint32_t);
BF_FIELD(proto, 0, 2);
BF_FIELD(endian, 2, 1);
BF_FIELD(dir, 3, 1);
BF_FIELD(len, 16, 4);
END_BF_DECL();
BEGIN_BF_DECL(txdata_t, uint32_t);
BF_FIELD(data, 0, 8);
BF_FIELD(full, 31, 1);
END_BF_DECL() r_txdata;
BEGIN_BF_DECL(rxdata_t, uint32_t);
BF_FIELD(data, 0, 8);
BF_FIELD(empty, 31, 1);
END_BF_DECL();
BEGIN_BF_DECL(txmark_t, uint32_t);
BF_FIELD(txmark, 0, 3);
END_BF_DECL();
BEGIN_BF_DECL(rxmark_t, uint32_t);
BF_FIELD(rxmark, 0, 3);
END_BF_DECL();
BEGIN_BF_DECL(fctrl_t, uint32_t);
BF_FIELD(en, 0, 1);
END_BF_DECL();
BEGIN_BF_DECL(ffmt_t, uint32_t);
BF_FIELD(cmd_en, 0, 1);
BF_FIELD(addr_len, 1, 2);
BF_FIELD(pad_cnt, 3, 4);
BF_FIELD(cmd_proto, 7, 2);
BF_FIELD(addr_proto, 9, 2);
BF_FIELD(data_proto, 11, 2);
BF_FIELD(cmd_code, 16, 8);
BF_FIELD(pad_code, 24, 8);
END_BF_DECL();
BEGIN_BF_DECL(ie_t, uint32_t);
BF_FIELD(txwm, 0, 1);
BF_FIELD(rxwm, 1, 1);
END_BF_DECL();
BEGIN_BF_DECL(ip_t, uint32_t);
BF_FIELD(txwm, 0, 1);
BF_FIELD(rxwm, 1, 1);
END_BF_DECL();
static inline sckdiv_t& sckdiv_reg(){
return *reinterpret_cast<sckdiv_t*>(BASE_ADDR+SPI_REG_SCKDIV);
}
static inline sckmode_t& sckmode_reg(){
return *reinterpret_cast<sckmode_t*>(BASE_ADDR+SPI_REG_SCKMODE);
}
static inline uint32_t& csid_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPI_REG_CSID);
}
static inline uint32_t& csdef_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPI_REG_CSDEF);
}
static inline csmode_t& csmode_reg(){
return *reinterpret_cast<csmode_t*>(BASE_ADDR+SPI_REG_CSMODE);
}
static inline delay0_t& dcssck_reg(){
return *reinterpret_cast<delay0_t*>(BASE_ADDR+SPI_REG_DCSSCK);
}
static inline uint32_t& dsckcs_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPI_REG_DSCKCS);
}
static inline delay1_t& dintercs_reg(){
return *reinterpret_cast<delay1_t*>(BASE_ADDR+SPI_REG_DINTERCS);
}
static inline uint32_t& dinterxfr_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPI_REG_DINTERXFR);
}
static inline fmt_t& fmt_reg(){
return *reinterpret_cast<fmt_t*>(BASE_ADDR+SPI_REG_FMT);
}
static inline txdata_t& txfifo_reg(){
return *reinterpret_cast<txdata_t*>(BASE_ADDR+SPI_REG_TXFIFO);
}
static inline rxdata_t& rxfifo_reg(){
return *reinterpret_cast<rxdata_t*>(BASE_ADDR+SPI_REG_RXFIFO);
}
static inline txmark_t& txctrl_reg(){
return *reinterpret_cast<txmark_t*>(BASE_ADDR+SPI_REG_TXCTRL);
}
static inline rxmark_t& rxctrl_reg(){
return *reinterpret_cast<rxmark_t*>(BASE_ADDR+SPI_REG_RXCTRL);
}
static inline fctrl_t& fctrl_reg(){
return *reinterpret_cast<fctrl_t*>(BASE_ADDR+SPI_REG_FCTRL);
}
static inline ffmt_t& ffmt_reg(){
return *reinterpret_cast<ffmt_t*>(BASE_ADDR+SPI_REG_FFMT);
}
static inline ie_t& ie_reg(){
return *reinterpret_cast<ie_t*>(BASE_ADDR+SPI_REG_IE);
}
static inline ip_t& ip_reg(){
return *reinterpret_cast<ip_t*>(BASE_ADDR+SPI_REG_IP);
}
template<size_t SIZE>
static bool transfer(std::array<uint8_t, SIZE>& bytes){
csmode_reg().mode=2; // HOLD mode
rxctrl_reg().rxmark=bytes.size()-1; // trigger irq if more than 2 bytes are received;
ie_reg().rxwm=1;
// write data bytes
for(size_t i=0; i<bytes.size(); ++i)
txfifo_reg()=bytes[i];
// wait until SPI is done
spi_active=true;
do{
asm("wfi");
asm("nop");
}while(spi_active);
// deactivate SPI
csmode_reg().mode=0; // AUTO mode, deactivates CS
// fetch results
for(size_t i=0; i<bytes.size(); ++i) bytes[i]=rxfifo_reg();
return true;
}
static void spi_rx_interrupt_handler(){
ip_reg().rxwm=0;
ie_reg().rxwm=0;
spi_active=false;
}
private:
static volatile bool spi_active;
};
#endif /* SPI_H_ */

83
fpga_spn/src/io/uart.h Normal file
View File

@ -0,0 +1,83 @@
/*
* spi.h
*
* Created on: 29.07.2018
* Author: eyck
*/
#ifndef UART_H_
#define UART_H_
#include <sifive/devices/uart.h>
#include "util/bit_field.h"
#include <cstdint>
template<uint32_t BASE_ADDR>
class uart_regs {
public:
BEGIN_BF_DECL(txdata_t, uint32_t);
BF_FIELD(data, 0, 8);
BF_FIELD(full, 31, 1);
END_BF_DECL() ;
BEGIN_BF_DECL(rxdata_t, uint32_t);
BF_FIELD(data, 0, 8);
BF_FIELD(empty, 31, 1);
END_BF_DECL();
BEGIN_BF_DECL(txctrl_t, uint32_t);
BF_FIELD(txen, 0, 1);
BF_FIELD(nstop, 1, 1);
BF_FIELD(txcnt, 16, 3);
END_BF_DECL();
BEGIN_BF_DECL(rxctrl_t, uint32_t);
BF_FIELD(rxen, 0, 1);
BF_FIELD(rxcnt, 16, 3);
END_BF_DECL();
BEGIN_BF_DECL(ie_t, uint32_t);
BF_FIELD(txwm, 0, 1);
BF_FIELD(rxwm, 1, 1);
END_BF_DECL();
BEGIN_BF_DECL(ip_t, uint32_t);
BF_FIELD(txwm, 0, 1);
BF_FIELD(rxwm, 1, 1);
END_BF_DECL();
BEGIN_BF_DECL(div_t, uint32_t);
BF_FIELD(div, 0, 16);
END_BF_DECL();
static inline txdata_t& txdata_reg(){
return *reinterpret_cast<txdata_t*>(BASE_ADDR+UART_REG_TXFIFO);
}
static inline rxdata_t& rxdata_reg(){
return *reinterpret_cast<rxdata_t*>(BASE_ADDR+UART_REG_RXFIFO);
}
static inline txctrl_t& txctrl_reg(){
return *reinterpret_cast<txctrl_t*>(BASE_ADDR+UART_REG_TXCTRL);
}
static inline rxctrl_t& rxctrl_reg(){
return *reinterpret_cast<rxctrl_t*>(BASE_ADDR+UART_REG_RXCTRL);
}
static inline ie_t& ie_reg(){
return *reinterpret_cast<ie_t*>(BASE_ADDR+UART_REG_IE);
}
static inline ip_t& ip_reg(){
return *reinterpret_cast<ip_t*>(BASE_ADDR+UART_REG_IP);
}
static inline div_t& div_reg(){
return *reinterpret_cast<div_t*>(BASE_ADDR+UART_REG_DIV);
}
};
#endif /* SPI_H_ */

117
fpga_spn/src/raven_spn.cpp Normal file
View File

@ -0,0 +1,117 @@
#include "raven_spn.h"
#include "spn_regs.h"
#include "dma_regs.h"
#include "init.h"
#include <math.h>
using spn = spn_regs<0x90000000>;
using dma = dma_regs<0xB0000000>;
// huge arrays of XSPN input and referance data
extern std::array<uint8_t, 50000> input_data;
extern std::array<double, 10000> ref_data;
bool double_equals(double a, double b, double epsilon = 0.001)
{
return std::abs(a - b) < epsilon;
}
void run_xspn(int in_addr, int out_addr, int num_samples, int in_beats, int out_beats) {
spn::mode_reg() = 0;
spn::input_length_reg() = num_samples; // each sample consists of 5 uint8 values
spn::input_addr_reg() = in_addr;
spn::output_addr_reg() = out_addr;
spn::num_of_in_beats_reg() = in_beats; // Number of AXI4 burst beats needed to load all input data
spn::num_of_out_beats_reg() = out_beats; // Number of AXI4 burst beats needed to store all result data
printf("Starting XSPN\n");
spn::start_reg() = 1;
}
void fpga_dma(int direction, int fpga_address, int sc_address, int num_bytes) {
dma::write_reg() = direction;
dma::fpga_address_reg() = fpga_address;
dma::sc_address_reg() = sc_address;
dma::bytes_reg() = num_bytes;
dma::start_reg() = 1;
wait_for_interrupt();
dma::clear_interrupt_reg() = 1;
}
void check_results(int addr, int k, int step) {
bool result = 0;
double *res_base = (double*) (addr);
int * error_exit = (int *)0xF0000000;
printf("Start result comparison %d - %d\n", k, k+step);
for (int i = 0; i < step; i++) {
//printf("%x%x vs %x%x\n", ((uint32_t*)res_base)[2*i], ((uint32_t*)res_base)[1+2*i], ((uint32_t*)ref_data.data())[2*i+k*20], ((uint32_t*)ref_data.data())[1+2*i+k*20]);
if (!double_equals(res_base[i], ref_data.at(k + i))) {
printf("XSPN ref %d comparison FAILED\n", k + i);
*error_exit = 0x1;
result = 1;
}
}
printf("Compared samples %d - %d with the reference\n", k, k+step);
}
/*! \brief main function
*
*/
int main() {
platform_init();
spn::mode_reg() = 1;
spn::start_reg() = 1;
wait_for_interrupt();
spn::interrupt_reg() = 1;
uint32_t readout = spn::readout_reg();
printf("READOUT HW:0x%x\n", readout);
uint32_t axi_bytes = readout;
axi_bytes = axi_bytes & 0xff;
axi_bytes = 1 << axi_bytes;
printf("AXI Bytes: %d\n", axi_bytes);
uint32_t sample_bytes = readout;
sample_bytes = sample_bytes >> 16;
sample_bytes = sample_bytes / 8;
printf("Sample Bytes: %d\n", sample_bytes);
uint32_t result_bytes = 8;
printf("Result Bytes: %d\n", result_bytes);
uint32_t step = 500;
uint32_t iterations = 10;
uint32_t in_beats = (step * sample_bytes) / axi_bytes;
if (in_beats * axi_bytes < step * sample_bytes) in_beats++;
uint32_t out_beats = (step * result_bytes) / axi_bytes;
if (out_beats * axi_bytes < step * result_bytes) out_beats++;
int in_addr = (int)input_data.data();
int out_addr = 0x800B0000;
int fpga_address_in = 0x10000000;
int fpga_address_out = 0x20000000;
//run_xspn(in_addr, out_addr);
for (int k = 0; k < iterations*step; k+=step) {
printf("XSPN processes samples %d - %d\n", k, k+step);
fpga_dma(1, fpga_address_in, in_addr, step * sample_bytes);
run_xspn(fpga_address_in, fpga_address_out, step, in_beats, out_beats);
wait_for_interrupt();
printf("XSPN finished\n");
spn::interrupt_reg() = 1;
fpga_dma(0, fpga_address_out, out_addr, step * result_bytes);
//check_results(out_addr, k, step);
//in_addr += step * sample_bytes; // 5 bytes in each sample
}
return 0;
}

6
fpga_spn/src/raven_spn.h Normal file
View File

@ -0,0 +1,6 @@
#ifndef RAVEN_SPN_H_
#define RAVEN_SPN_H_
extern "C" void handle_m_ext_interrupt();
#endif /* RAVEN_SPN_H_ */

116
fpga_spn/src/spn_regs.h Normal file
View File

@ -0,0 +1,116 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Created on: Thu Oct 01 15:45:55 CEST 2020
// * spn_regs.h Author: <RDL Generator>
//
////////////////////////////////////////////////////////////////////////////////
#ifndef _SPN_REGS_H_
#define _SPN_REGS_H_
#include <util/bit_field.h>
#include <cstdint>
#define SPN_REG_START 0x00
#define SPN_REG_READOUT 0x10
#define SPN_REG_MODE 0x20
#define SPN_REG_INPUT_LENGTH 0x30
#define SPN_REG_INPUT_ADDR 0x40
#define SPN_REG_OUTPUT_ADDR 0x50
#define SPN_REG_NUM_OF_INPUT_BEATS 0x60
#define SPN_REG_NUM_OF_OUTPUT_BEATS 0x70
#define SPN_REG_INTERRUPT 0x0C
template<uint32_t BASE_ADDR>
class spn_regs {
public:
// storage declarations
// BEGIN_BF_DECL(start_t, uint32_t);
// BF_FIELD(start, 0, 1);
// END_BF_DECL() r_start;
uint32_t r_start;
uint32_t r_readout;
uint32_t r_mode;
uint32_t r_input_length;
uint32_t r_input_addr;
uint32_t r_output_addr;
uint32_t r_num_of_input_beats;
uint32_t r_num_of_output_beats;
// static inline start_t& start_reg(){
// return *reinterpret_cast<start_t*>(BASE_ADDR+SPN_REG_START);
// }
static inline uint32_t& start_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_START);
}
static inline uint32_t & readout_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_READOUT);
}
static inline uint32_t & mode_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_MODE);
}
static inline uint32_t & input_length_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_INPUT_LENGTH);
}
static inline uint32_t & input_addr_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_INPUT_ADDR);
}
static inline uint32_t & output_addr_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_OUTPUT_ADDR);
}
static inline uint32_t & num_of_in_beats_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_NUM_OF_INPUT_BEATS);
}
static inline uint32_t & num_of_out_beats_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_NUM_OF_OUTPUT_BEATS);
}
static inline uint32_t & interrupt_reg(){
return *reinterpret_cast<uint32_t*>(BASE_ADDR+SPN_REG_INTERRUPT);
}
};
#endif // _SPN_REGS_H_

View File

@ -0,0 +1,179 @@
/*---------------------------------------------------------
Copyright (c) 2015 Jeff Preshing
This software is provided 'as-is', without any express or implied
warranty. In no event will the authors be held liable for any damages
arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it
freely, subject to the following restrictions:
1. The origin of this software must not be misrepresented; you must not
claim that you wrote the original software. If you use this software
in a product, an acknowledgement in the product documentation would be
appreciated but is not required.
2. Altered source versions must be plainly marked as such, and must not be
misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
---------------------------------------------------------*/
#ifndef BIT_FIELD_H_
#define BIT_FIELD_H_
#ifndef __CPP11OM_BITFIELD_H__
#define __CPP11OM_BITFIELD_H__
#include <cassert>
//---------------------------------------------------------
// BitFieldMember<>: Used internally by ADD_BITFIELD_MEMBER macro.
// All members are public to simplify compliance with sections 9.0.7 and
// 9.5.1 of the C++11 standard, thereby avoiding undefined behavior.
//---------------------------------------------------------
template <typename T, int Offset, int Bits> struct BitFieldMember {
T value;
static_assert(Offset + Bits <= (int)sizeof(T) * 8, "Member exceeds bitfield boundaries");
static_assert(Bits < (int)sizeof(T) * 8, "Can't fill entire bitfield with one member");
static const T Maximum = (T(1) << Bits) - 1;
static const T Mask = Maximum << Offset;
T maximum() const { return Maximum; }
T one() const { return T(1) << Offset; }
operator T() const { return (value >> Offset) & Maximum; }
BitFieldMember &operator=(T v) {
assert(v <= Maximum); // v must fit inside the bitfield member
value = (value & ~Mask) | (v << Offset);
return *this;
}
BitFieldMember &operator+=(T v) {
assert(T(*this) + v <= Maximum); // result must fit inside the bitfield member
value += v << Offset;
return *this;
}
BitFieldMember &operator-=(T v) {
assert(T(*this) >= v); // result must not underflow
value -= v << Offset;
return *this;
}
BitFieldMember &operator++() { return *this += 1; }
BitFieldMember operator++(int) { // postfix form
BitFieldMember tmp(*this);
operator++();
return tmp;
}
BitFieldMember &operator--() { return *this -= 1; }
BitFieldMember operator--(int) { // postfix form
BitFieldMember tmp(*this);
operator--();
return tmp;
}
};
//---------------------------------------------------------
// BitFieldArray<>: Used internally by ADD_BITFIELD_ARRAY macro.
// All members are public to simplify compliance with sections 9.0.7 and
// 9.5.1 of the C++11 standard, thereby avoiding undefined behavior.
//---------------------------------------------------------
template <typename T, int BaseOffset, int BitsPerItem, int NumItems> class BitFieldArray {
public:
T value;
static_assert(BaseOffset + BitsPerItem * NumItems <= (int)sizeof(T) * 8, "Array exceeds bitfield boundaries");
static_assert(BitsPerItem < (int)sizeof(T) * 8, "Can't fill entire bitfield with one array element");
static const T Maximum = (T(1) << BitsPerItem) - 1;
T maximum() const { return Maximum; }
int numItems() const { return NumItems; }
class Element {
private:
T &value;
int offset;
public:
Element(T &value, int offset)
: value(value)
, offset(offset) {}
T mask() const { return Maximum << offset; }
operator T() const { return (value >> offset) & Maximum; }
Element &operator=(T v) {
assert(v <= Maximum); // v must fit inside the bitfield member
value = (value & ~mask()) | (v << offset);
return *this;
}
Element &operator+=(T v) {
assert(T(*this) + v <= Maximum); // result must fit inside the bitfield member
value += v << offset;
return *this;
}
Element &operator-=(T v) {
assert(T(*this) >= v); // result must not underflow
value -= v << offset;
return *this;
}
Element &operator++() { return *this += 1; }
Element operator++(int) { // postfix form
Element tmp(*this);
operator++();
return tmp;
}
Element &operator--() { return *this -= 1; }
Element operator--(int) { // postfix form
Element tmp(*this);
operator--();
return tmp;
}
};
Element operator[](int i) {
assert(i >= 0 && i < NumItems); // array index must be in range
return Element(value, BaseOffset + BitsPerItem * i);
}
const Element operator[](int i) const {
assert(i >= 0 && i < NumItems); // array index must be in range
return Element(value, BaseOffset + BitsPerItem * i);
}
};
//---------------------------------------------------------
// Bitfield definition macros.
// All members are public to simplify compliance with sections 9.0.7 and
// 9.5.1 of the C++11 standard, thereby avoiding undefined behavior.
//---------------------------------------------------------
#define BEGIN_BF_DECL(typeName, T) \
union typeName { \
struct Wrapper { \
T value; \
}; \
Wrapper flat; \
typeName(T v = 0) { flat.value = v; } \
typeName &operator=(T v) { \
flat.value = v; \
return *this; \
} \
operator T &() { return flat.value; } \
operator T() const { return flat.value; } \
using StorageType = T;
#define BF_FIELD(memberName, offset, bits) BitFieldMember<StorageType, offset, bits> memberName;
#define BF_ARRAY(memberName, offset, bits, numItems) BitFieldArray<StorageType, offset, bits, numItems> memberName;
#define END_BF_DECL() }
#endif // __CPP11OM_BITFIELD_H__
#endif /* BIT_FIELD_H_ */

20007
fpga_spn/src/xspn_data.cpp Normal file

File diff suppressed because it is too large Load Diff