Initial version of riscv-bldc-forced-communication

This commit is contained in:
2018-08-08 20:59:10 +02:00
parent 42b87091a4
commit 250fa831d0
101 changed files with 8428 additions and 0 deletions

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_ */

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);
}
}

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_ */

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_ */

View File

@ -0,0 +1,26 @@
/*
* peripherals.h
*
* Created on: 29.07.2018
* Author: eyck
*/
#ifndef PERIPHERALS_H_
#define PERIPHERALS_H_
#include "gpio.h"
#include "spi.h"
#include "pwm.h"
#include "uart.h"
using gpio0=gpio_regs<0x10012000>;
using uart0=uart_regs<0x10013000>;
using uart1=uart_regs<0x10023000>;
using qspi0=spi_regs<0x10014000>;
using qspi1=spi_regs<0x10024000>;
using qspi2=spi_regs<0x10034000>;
using pwm0 =pwm_regs<0x10015000>;
using pwm1 =pwm_regs<0x10025000>;
using pwm2 =pwm_regs<0x10035000>;
#endif /* PERIPHERALS_H_ */

View File

@ -0,0 +1,90 @@
/*
* 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 <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);
}
};
#endif /* PWM_H_ */

View File

@ -0,0 +1,202 @@
//============================================================================
// Name : riscv-bldc.cpp
// Author : Eyck Jentzsch
// Version :
// Copyright : Your copyright notice
// Description : Hello World in C++, Ansi-style
//============================================================================
#include "riscv-bldc.h"
#include "peripherals.h"
#include "delay.h"
#include "bsp.h"
#include "plic/plic_driver.h"
#include <array>
#include <limits>
#include <cstdio>
#include <cstdint>
volatile uint32_t nextCommutationStep;
volatile uint32_t nextDrivePattern;
volatile uint32_t zcPolarity;
volatile uint32_t filteredTimeSinceCommutation;
std::array<uint32_t, 6> cwDriveTable {
DRIVE_PATTERN_CW::STEP1,
DRIVE_PATTERN_CW::STEP2,
DRIVE_PATTERN_CW::STEP3,
DRIVE_PATTERN_CW::STEP4,
DRIVE_PATTERN_CW::STEP5,
DRIVE_PATTERN_CW::STEP6
};
std::array<uint32_t, 6> ccwDriveTable{
DRIVE_PATTERN_CCW::STEP1,
DRIVE_PATTERN_CCW::STEP2,
DRIVE_PATTERN_CCW::STEP3,
DRIVE_PATTERN_CCW::STEP4,
DRIVE_PATTERN_CCW::STEP5,
DRIVE_PATTERN_CCW::STEP6
};
std::array<unsigned int, 24> startupDelays{
// 200, 150, 100, 80, 70, 65, 60, 55, 50, 45, 40, 35, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25
200, 150, 100, 80, 70, 65, 60, 55, 50, 50, 50, 50, 50, 50, 50, 50, 50, 40, 40, 40, 40, 40, 40, 40
};
bool ccw=false;
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;
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);
}
// 1sec interval interrupt
extern "C" void handle_m_time_interrupt(){
clear_csr(mie, MIP_MTIP);
// Reset the timer for 3s in the future.
// This also clears the existing timer interrupt.
volatile uint64_t * mtime = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIME);
volatile uint64_t * mtimecmp = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIMECMP);
uint64_t now = *mtime;
uint64_t then = now + RTC_FREQ;
*mtimecmp = then;
// Re-enable the timer interrupt.
set_csr(mie, MIP_MTIP);
}
void no_interrupt_handler (void) {};
volatile bool pwm_active=false;
void pwm_interrupt_handler(){
pwm0::cfg_reg().cmp0ip=false;
pwm_active=false;
}
void platform_init(){
// configure clocks
PRCI_use_hfxosc(1); // is equivalent to
// init UART0 at 115200 baud
auto baud_rate=115200;
gpio0::output_en_reg()=0xffffffff;
gpio0::iof_sel_reg()&=~IOF0_UART0_MASK;
gpio0::iof_en_reg()|= IOF0_UART0_MASK;
uart0::div_reg()=get_cpu_freq() / baud_rate - 1;
uart0::txctrl_reg().txen=1;
// init SPI
gpio0::iof_sel_reg()&=~IOF0_SPI1_MASK;
gpio0::iof_en_reg()|= IOF0_SPI1_MASK;
qspi0::sckdiv_reg() = 8;
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);
if (read_csr(misa) & (1 << ('F' - 'A'))) { // if F extension is present
write_csr(mstatus, MSTATUS_FS); // allow FPU instructions without trapping
write_csr(fcsr, 0); // initialize rounding mode, undefined at reset
}
PLIC_init(&g_plic, PLIC_CTRL_ADDR, PLIC_NUM_INTERRUPTS, PLIC_NUM_PRIORITIES);
// 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;
g_ext_interrupt_handlers[40] = pwm_interrupt_handler;
// Priority must be set > 0 to trigger the interrupt.
PLIC_set_priority(&g_plic, 40, 1);
// Have to enable the interrupt both at the GPIO level, and at the PLIC level.
PLIC_enable_interrupt (&g_plic, 40);
// enable peripheral interrupt
// GPIO_REG(GPIO_RISE_IE) |= (1 << BUTTON_0_OFFSET);
// Set the machine timer to go off in 1 second.
volatile uint64_t * mtime = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIME);
volatile uint64_t * mtimecmp = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIMECMP);
uint64_t now = *mtime;
uint64_t then = now + RTC_FREQ;
*mtimecmp = then;
// Enable the Machine-External bit in MIE
set_csr(mie, MIP_MEIP);
// Enable the Machine-Timer bit in MIE
set_csr(mie, MIP_MTIP);
// Enable interrupts in general.
set_csr(mstatus, MSTATUS_MIE);
}
/*! \brief Generates a delay used during startup
*
* This functions is used to generate a delay during the startup procedure.
* The length of the delay equals delay * STARTUP_DELAY_MULTIPLIER microseconds.
* Since Timer/Counter1 is used in this function, it must never be called when
* sensorless operation is running.
*/
void StartupDelay(unsigned short delay){
#if 0
delayUS(delay * STARTUP_DELAY_MULTIPLIER);
#else
auto scaling_factor=0;
unsigned d = delay * STARTUP_DELAY_MULTIPLIER;
while(d/(1<<scaling_factor) > std::numeric_limits<unsigned short>::max()){
scaling_factor++;
}
pwm0::cfg_reg()=0;
pwm0::count_reg()=0;
pwm0::cfg_reg().scale=4+scaling_factor; // divide by 16 so we get 1us per pwm clock
pwm0::cmp0_reg().cmp0 = d/(1<<scaling_factor);
pwm_active=true;
pwm0::cfg_reg().enoneshot=true;
do{
asm("wfi");
asm("nop");
}while(pwm_active);
#endif
}
void StartMotor(void){
auto& driveTable = ccw?ccwDriveTable:cwDriveTable;
nextCommutationStep = 0;
//Preposition.
gpio0::port_reg() = driveTable[nextCommutationStep];
printf("init\n");
StartupDelay(STARTUP_LOCK_DELAY);
nextCommutationStep++;
nextDrivePattern = driveTable[nextCommutationStep];
const size_t size=startupDelays.size();
for (size_t i = 0; i < startupDelays.size()+100; i++){
printf("step%d\n", i);
gpio0::port_reg() = nextDrivePattern;
auto index = i>=size?size-1:i;
StartupDelay(startupDelays[index]);
// switch ADC input
// ADMUX = ADMUXTable[nextCommutationStep];
// Use LSB of nextCommutationStep to determine zero crossing polarity.
zcPolarity = nextCommutationStep & 0x01;
nextCommutationStep++;
if (nextCommutationStep >= 6){
nextCommutationStep = 0;
}
nextDrivePattern = driveTable[nextCommutationStep];
}
// Switch to sensorless commutation.
// Set filteredTimeSinceCommutation to the time to the next commutation.
filteredTimeSinceCommutation = startupDelays[startupDelays.size() - 1] * (STARTUP_DELAY_MULTIPLIER / 2);
}
int main() {
platform_init();
StartMotor();
printf("done...");
return 0;
}

View File

@ -0,0 +1,58 @@
/*
* riscv-bldc.h
*
* Created on: 28.07.2018
* Author: eyck
*/
#ifndef RISCV_BLDC_H_
#define RISCV_BLDC_H_
#include <cstdint>
extern uint32_t pwm;
extern uint32_t DRIVE_PORT;
enum PINS{
UL=1, //! Port pin connected to phase U, low side enable switch.
UH=0, //! Port pin connected to phase U, high side enable switch.
VL=11,//! Port pin connected to phase V, low side enable switch.
VH=10,//! Port pin connected to phase V, high side enable switch.
WL=19,//! Port pin connected to phase W, low side enable switch.
WH=20 //! Port pin connected to phase W, high side enable switch.
};
enum {
CW=0, //! Clockwise rotation flag.
CCW=1 //! Counterclockwise rotation flag.
};
namespace DRIVE_PATTERN_CCW{
enum {
STEP1=((1 << UL) | (1 << VH)),//! Drive pattern for commutation step 1, CCW rotation.
STEP2=((1 << UL) | (1 << WH)),//! Drive pattern for commutation step 2, CCW rotation.
STEP3=((1 << VL) | (1 << WH)),//! Drive pattern for commutation step 3, CCW rotation.
STEP4=((1 << VL) | (1 << UH)),//! Drive pattern for commutation step 4, CCW rotation.
STEP5=((1 << WL) | (1 << UH)),//! Drive pattern for commutation step 5, CCW rotation.
STEP6=((1 << WL) | (1 << VH)) //! Drive pattern for commutation step 6, CCW rotation.
};
}
namespace DRIVE_PATTERN_CW {
enum {
STEP1=((1 << VH) | (1 << WL)),//! Drive pattern for commutation step 1, CW rotation.
STEP2=((1 << UH) | (1 << WL)),//! Drive pattern for commutation step 2, CW rotation.
STEP3=((1 << UH) | (1 << VL)),//! Drive pattern for commutation step 3, CW rotation.
STEP4=((1 << WH) | (1 << VL)),//! Drive pattern for commutation step 4, CW rotation.
STEP5=((1 << WH) | (1 << UL)),//! Drive pattern for commutation step 5, CW rotation.
STEP6=((1 << VH) | (1 << UL)) //! Drive pattern for commutation step 6, CW rotation.
};
}
//! Startup delays are given in microseconds times STARTUP_DELAY_MULTIPLIER.
const auto STARTUP_DELAY_MULTIPLIER=1000;
/*!
* Number of milliseconds to lock rotor in first commutation step before
* the timed startup sequence is initiated.
*/
const auto STARTUP_LOCK_DELAY=50;
#endif /* RISCV_BLDC_H_ */

View File

@ -0,0 +1,170 @@
/*
* 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 <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);
}
};
#endif /* SPI_H_ */

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_ */

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_ */

View File

@ -0,0 +1,12 @@
/*
* utili.cpp
*
* Created on: 28.07.2018
* Author: eyck
*/
// see https://stackoverflow.com/questions/34308720/where-is-dso-handle-defined#39521737
void* __dso_handle = (void*) &__dso_handle;

View File

@ -0,0 +1,271 @@
/* The functions in this file are only meant to support Dhrystone on an
* embedded RV32 system and are obviously incorrect in general. */
#include <stdarg.h>
#include <stddef.h>
#include <stdio.h>
#include <stdint.h>
#include <string.h>
#include <unistd.h>
#undef putchar
int putchar(int ch)
{
return write(STDOUT_FILENO, &ch, 1) == 1 ? ch : -1;
}
static void sprintf_putch(int ch, void** data)
{
char** pstr = (char**)data;
**pstr = ch;
(*pstr)++;
}
static unsigned long getuint(va_list *ap, int lflag)
{
if (lflag)
return va_arg(*ap, unsigned long);
else
return va_arg(*ap, unsigned int);
}
static long getint(va_list *ap, int lflag)
{
if (lflag)
return va_arg(*ap, long);
else
return va_arg(*ap, int);
}
static inline void printnum(void (*putch)(int, void**), void **putdat,
unsigned long num, unsigned base, int width, int padc)
{
unsigned digs[sizeof(num)*8];
int pos = 0;
while (1)
{
digs[pos++] = num % base;
if (num < base)
break;
num /= base;
}
while (width-- > pos)
putch(padc, putdat);
while (pos-- > 0)
putch(digs[pos] + (digs[pos] >= 10 ? 'a' - 10 : '0'), putdat);
}
static inline void print_double(void (*putch)(int, void**), void **putdat,
double num, int width, int prec)
{
union {
double d;
uint64_t u;
} u;
u.d = num;
if (u.u & (1ULL << 63)) {
putch('-', putdat);
u.u &= ~(1ULL << 63);
}
for (int i = 0; i < prec; i++)
u.d *= 10;
char buf[32], *pbuf = buf;
printnum(sprintf_putch, (void**)&pbuf, (unsigned long)u.d, 10, 0, 0);
if (prec > 0) {
for (int i = 0; i < prec; i++) {
pbuf[-i] = pbuf[-i-1];
}
pbuf[-prec] = '.';
pbuf++;
}
for (char* p = buf; p < pbuf; p++)
putch(*p, putdat);
}
static void vprintfmt(void (*putch)(int, void**), void **putdat, const char *fmt, va_list ap)
{
register const char* p;
const char* last_fmt;
register int ch, err;
unsigned long num;
int base, lflag, width, precision, altflag;
char padc;
while (1) {
while ((ch = *(unsigned char *) fmt) != '%') {
if (ch == '\0')
return;
fmt++;
putch(ch, putdat);
}
fmt++;
// Process a %-escape sequence
last_fmt = fmt;
padc = ' ';
width = -1;
precision = -1;
lflag = 0;
altflag = 0;
reswitch:
switch (ch = *(unsigned char *) fmt++) {
// flag to pad on the right
case '-':
padc = '-';
goto reswitch;
// flag to pad with 0's instead of spaces
case '0':
padc = '0';
goto reswitch;
// width field
case '1':
case '2':
case '3':
case '4':
case '5':
case '6':
case '7':
case '8':
case '9':
for (precision = 0; ; ++fmt) {
precision = precision * 10 + ch - '0';
ch = *fmt;
if (ch < '0' || ch > '9')
break;
}
goto process_precision;
case '*':
precision = va_arg(ap, int);
goto process_precision;
case '.':
if (width < 0)
width = 0;
goto reswitch;
case '#':
altflag = 1;
goto reswitch;
process_precision:
if (width < 0)
width = precision, precision = -1;
goto reswitch;
// long flag
case 'l':
if (lflag)
goto bad;
goto reswitch;
// character
case 'c':
putch(va_arg(ap, int), putdat);
break;
// double
case 'f':
print_double(putch, putdat, va_arg(ap, double), width, precision);
break;
// string
case 's':
if ((p = va_arg(ap, char *)) == NULL)
p = "(null)";
if (width > 0 && padc != '-')
for (width -= strnlen(p, precision); width > 0; width--)
putch(padc, putdat);
for (; (ch = *p) != '\0' && (precision < 0 || --precision >= 0); width--) {
putch(ch, putdat);
p++;
}
for (; width > 0; width--)
putch(' ', putdat);
break;
// (signed) decimal
case 'd':
num = getint(&ap, lflag);
if ((long) num < 0) {
putch('-', putdat);
num = -(long) num;
}
base = 10;
goto signed_number;
// unsigned decimal
case 'u':
base = 10;
goto unsigned_number;
// (unsigned) octal
case 'o':
// should do something with padding so it's always 3 octits
base = 8;
goto unsigned_number;
// pointer
case 'p':
lflag = 1;
putch('0', putdat);
putch('x', putdat);
/* fall through to 'x' */
// (unsigned) hexadecimal
case 'x':
base = 16;
unsigned_number:
num = getuint(&ap, lflag);
signed_number:
printnum(putch, putdat, num, base, width, padc);
break;
// escaped '%' character
case '%':
putch(ch, putdat);
break;
// unrecognized escape sequence - just print it literally
default:
bad:
putch('%', putdat);
fmt = last_fmt;
break;
}
}
}
int __wrap_printf(const char* fmt, ...)
{
va_list ap;
va_start(ap, fmt);
vprintfmt((void*)putchar, 0, fmt, ap);
va_end(ap);
return 0; // incorrect return value, but who cares, anyway?
}
int __wrap_sprintf(char* str, const char* fmt, ...)
{
va_list ap;
char* str0 = str;
va_start(ap, fmt);
vprintfmt(sprintf_putch, (void**)&str, fmt, ap);
*str = 0;
va_end(ap);
return str - str0;
}

View File

@ -0,0 +1,15 @@
#include "platform.h"
/* The functions in this file are only meant to support Dhrystone on an
* embedded RV32 system and are obviously incorrect in general. */
long time(void)
{
return get_timer_value() / get_timer_freq();
}
// set the number of dhrystone iterations
void __wrap_scanf(const char* fmt, int* n)
{
*n = 100000000;
}