Commit 5759163a authored by Mathias Kreider's avatar Mathias Kreider

ebm: added demo program for raw udp

parent 4f96ad1f
LD := lm32-elf-ld
CC := lm32-elf-gcc
CFLAGS := -Wall -mmultiply-enabled -mbarrel-shift-enabled -Os -ggdb -ffreestanding
LD := lm32-elf-ld
CC := lm32-elf-gcc
TARGET = ebm_udp_demo
MYPATH = .
CHECKOUT = ../../../../..
INCPATH = $(CHECKOUT)/modules/lm32-include
W1 = $(CHECKOUT)/ip_cores/wrpc-sw
CFLAGS = -std=gnu99 -I$(INCPATH) -mmultiply-enabled -mbarrel-shift-enabled -Os -I$(W1)/include -I$(W1)/pp_printf \
ebmdemo.bin: ebmdemo.elf
all: $(TARGET).bin $(TARGET).elf
$(TARGET).bin: $(TARGET).elf
lm32-elf-objcopy -O binary $< $@
ebmdemo.elf: crt0.o display.o ebm.o irq.o main.o
$(CC) $(CFLAGS) -o $@ -nostdlib -T linker.ld $^
$(TARGET).elf: $(INCPATH)/dbg.c $(INCPATH)/aux.c $(INCPATH)/ebm.c $(INCPATH)/irq.c \
$(INCPATH)/mini_sdb.c $(MYPATH)/main.c $(INCPATH)/crt0.S $(INCPATH)/mprintf.c \
$(W1)/dev/uart.c
$(CC) $(CFLAGS) -o $@ -nostdlib -T linker.ld $^
clean:
......
/****************************************************************************
**
** Name: crt0ram.S
**
** Description:
** Implements boot-code that calls LatticeDDInit (that calls main())
** Implements exception handlers (actually, redirectors)
**
** $Revision: $
**
** Disclaimer:
**
** This source code is intended as a design reference which
** illustrates how these types of functions can be implemented. It
** is the user's responsibility to verify their design for
** consistency and functionality through the use of formal
** verification methods. Lattice Semiconductor provides no warranty
** regarding the use or functionality of this code.
**
** --------------------------------------------------------------------
**
** Lattice Semiconductor Corporation
** 5555 NE Moore Court
** Hillsboro, OR 97214
** U.S.A
**
** TEL: 1-800-Lattice (USA and Canada)
** (503)268-8001 (other locations)
**
** web: http://www.latticesemi.com
** email: techsupport@latticesemi.com
**
** --------------------------------------------------------------------------
**
** Change History (Latest changes on top)
**
** Ver Date Description
** --------------------------------------------------------------------------
** 3.8 Apr-15-2011 Added __MICO_USER_<handler>_HANDLER__ preprocessor to
** allow customers to implement their own handlers for:
** DATA_ABORT, INST_ABORT
**
** 3.1 Jun-18-2008 Added __MICO_NO_INTERRUPTS__ preprocessor
** option to exclude invoking MicoISRHandler
** to reduce code-size in apps that don't use
** interrupts
**
** 3.0 Mar-25-2008 Added Header
**
**---------------------------------------------------------------------------
*****************************************************************************/
/*
* LatticeMico32 C startup code.
*
* 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.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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.
*/
/* From include/sys/signal.h */
#define SIGINT 2 /* interrupt */
#define SIGTRAP 5 /* trace trap */
#define SIGFPE 8 /* arithmetic exception */
#define SIGSEGV 11 /* segmentation violation */
//#define MICO32_FULL_CONTEXT_SAVE_RESTORE
/* Exception handlers - Must be 32 bytes long. */
.section .boot, "ax", @progbits
.global _start
_start:
.global _reset_handler
.type _reset_handler, @function
_reset_handler:
xor r0, r0, r0
wcsr IE, r0
wcsr IM, r0
mvhi r1, hi(_reset_handler)
ori r1, r1, lo(_reset_handler)
wcsr EBA, r1
calli _crt0
nop
.size _reset_handler, .-_reset_handler
.extern _irq_entry
.org 0xc0
.global _interrupt_handler
.type _interrupt_handler, @function
_interrupt_handler:
sw (sp+0), ra
calli _save_all
mvi r1, SIGINT
#ifndef __MICO_NO_INTERRUPTS__
calli _irq_entry
#else
wcsr IE, r0
#endif
bi _restore_all_and_return
nop
nop
nop
.org 0x100
.global _crt0
.type _crt0, @function
_crt0:
/* Clear r0 */
xor r0, r0, r0
/* Setup stack and global pointer */
mvhi sp, hi(_fstack)
ori sp, sp, lo(_fstack)
mvhi gp, hi(_gp)
ori gp, gp, lo(_gp)
mvhi r1, hi(_fbss)
ori r1, r1, lo(_fbss)
mvi r2, 0
mvhi r3, hi(_ebss)
ori r3, r3, lo(_ebss)
sub r3, r3, r1
calli memset
mvi r1, 0
mvi r2, 0
mvi r3, 0
calli main
loopf:
bi loopf
.global _save_all
.type _save_all, @function
_save_all:
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
addi sp, sp, -128
#else
addi sp, sp, -60
#endif
sw (sp+4), r1
sw (sp+8), r2
sw (sp+12), r3
sw (sp+16), r4
sw (sp+20), r5
sw (sp+24), r6
sw (sp+28), r7
sw (sp+32), r8
sw (sp+36), r9
sw (sp+40), r10
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
sw (sp+44), r11
sw (sp+48), r12
sw (sp+52), r13
sw (sp+56), r14
sw (sp+60), r15
sw (sp+64), r16
sw (sp+68), r17
sw (sp+72), r18
sw (sp+76), r19
sw (sp+80), r20
sw (sp+84), r21
sw (sp+88), r22
sw (sp+92), r23
sw (sp+96), r24
sw (sp+100), r25
sw (sp+104), r26
sw (sp+108), r27
sw (sp+120), ea
sw (sp+124), ba
/* ra and sp need special handling, as they have been modified */
lw r1, (sp+128)
sw (sp+116), r1
mv r1, sp
addi r1, r1, 128
sw (sp+112), r1
#else
sw (sp+52), ea
sw (sp+56), ba
/* ra and sp need special handling, as they have been modified */
lw r1, (sp+60)
sw (sp+48), r1
mv r1, sp
addi r1, r1, 60
sw (sp+44), r1
#endif
// xor r1, r1, r1
// wcsr ie, r1
ret
.size _save_all, .-_save_all
.global _restore_all_and_return
.type _restore_all_and_return, @function
/* Restore all registers and return from exception */
_restore_all_and_return:
// addi r1, r0, 2
// wcsr ie, r1
lw r1, (sp+4)
lw r2, (sp+8)
lw r3, (sp+12)
lw r4, (sp+16)
lw r5, (sp+20)
lw r6, (sp+24)
lw r7, (sp+28)
lw r8, (sp+32)
lw r9, (sp+36)
lw r10, (sp+40)
#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
lw r11, (sp+44)
lw r12, (sp+48)
lw r13, (sp+52)
lw r14, (sp+56)
lw r15, (sp+60)
lw r16, (sp+64)
lw r17, (sp+68)
lw r18, (sp+72)
lw r19, (sp+76)
lw r20, (sp+80)
lw r21, (sp+84)
lw r22, (sp+88)
lw r23, (sp+92)
lw r24, (sp+96)
lw r25, (sp+100)
lw r26, (sp+104)
lw r27, (sp+108)
lw ra, (sp+116)
lw ea, (sp+120)
lw ba, (sp+124)
/* Stack pointer must be restored last, in case it has been updated */
lw sp, (sp+112)
#else
lw ra, (sp+48)
lw ea, (sp+52)
lw ba, (sp+56)
/* Stack pointer must be restored last, in case it has been updated */
lw sp, (sp+44)
#endif
nop
eret
.size _restore_all_and_return, .-_restore_all_and_return
#include "display.h"
const unsigned int REG_MODE = 0x00000000;
const unsigned int REG_RST = 0x00000004;
const unsigned int REG_UART = 0x00010000;
const unsigned int REG_CHAR = 0x00020000;
const unsigned int REG_RAW = 0x00030000;
const char MODE_RAW = 0x03;
const char MODE_UART = 0x01;
const char MODE_CHAR = 0x02;
const char MODE_IDLE = 0x00;
const char ROW_LEN = 11;
void disp_reset()
{
*(display + REG_RST) = 1;
}
void disp_put_c(char ascii)
{
*(display + (REG_MODE>>2)) = (unsigned int)MODE_UART;
*(display + (REG_UART>>2)) = (unsigned int)ascii;
}
void disp_put_str(const char *sPtr)
{
*(display + (REG_MODE>>2)) = (unsigned int)MODE_UART;
while(*sPtr != '\0') *(display + (REG_UART>>2)) = (unsigned int)*sPtr++;
}
void disp_put_line(const char *sPtr, unsigned char row)
{
unsigned char col, outp, pad;
pad = 0;
for(col=0; col<ROW_LEN; col++)
{
if(*(sPtr+col) == '\0') pad = 1;
if(pad) outp = ' ';
else outp = (unsigned int)*(sPtr+col);
disp_loc_c(outp, row, col);
}
}
void disp_loc_c(char ascii, unsigned char row, unsigned char col)
{
unsigned int rowcol;
*(display + (REG_MODE>>2)) = (unsigned int)MODE_CHAR;
rowcol = ((0x07 & (unsigned int)row)<<6) + ((0x0f & (unsigned int)col)<<2);
*(display + ((REG_CHAR + rowcol)>>2)) = (unsigned int)ascii;
}
void disp_put_raw(char pixcol, unsigned int address, char color)
{
char oldpixcol;
*(display + (REG_MODE>>2)) = (unsigned int)MODE_RAW;
oldpixcol = *(display + (REG_RAW>>2) + ((address & 0x3FFF))); //read out old memcontent
if(color) // 1 -> White
*(display + (REG_RAW>>2) + ((address & 0x3FFF))) = (unsigned int)(pixcol | oldpixcol);
else
*(display + (REG_RAW>>2) + ((address & 0x3FFF))) = (unsigned int)(~pixcol & oldpixcol);
*(display + (REG_MODE>>2)) = (unsigned int)MODE_IDLE;
}
unsigned int get_pixcol_addr(unsigned char x_in, unsigned char y_in)
{
unsigned int addr_base = 0x230;
unsigned int x, y;
x = x_in & 0x3F;
if(y_in < 48) y = ((y_in>>3)<<8); //determine row. Shift by 8bit
else y = (5<<8); //outside visible area, take start of bottom row instead
return addr_base + y + x;
}
unsigned int get_pixcol_val(unsigned char y_in)
{
return 1<<(y_in & 0x07);
}
#ifndef _DISPLAY_H_
#define _DISPLAY_H_
extern volatile unsigned int* display;
extern const unsigned int MODE_REG;
extern const unsigned int RST_REG;
extern const unsigned int UART_REG;
extern const unsigned int CHAR_REG;
extern const unsigned int RAW_REG;
extern const char MODE_RAW;
extern const char MODE_UART;
extern const char MODE_CHAR;
extern const char MODE_IDLE;
extern const char ROW_LEN;
void disp_put_c(char ascii);
void disp_put_int(int number);
void disp_put_str(const char *sPtr);
void disp_put_line(const char *sPtr, unsigned char row);
void disp_reset();
void disp_loc_c(char ascii, unsigned char row, unsigned char col);
void disp_put_raw(char pixcol, unsigned int address, char color);
unsigned int get_pixcol_addr(unsigned char x_in, unsigned char y_in);
unsigned int get_pixcol_val(unsigned char y_in);
#endif
/** @file ebm.c
* @brief EtherBone Master API
*
* Copyright (C) 2011-2012 GSI Helmholtz Centre for Heavy Ion Research GmbH
*
* @author Mathias Kreider <m.kreider@gsi.de>
*
* @bug None!
*
*******************************************************************************
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************
*/
#include <stdlib.h>
#include <string.h>
#include "ebm.h"
extern unsigned int* ebm;
static inline char* strsplit(const char* numstr, const char* delimeter);
static inline unsigned char* numStrToBytes(const char* numstr, unsigned char* bytes, unsigned char len, unsigned char base, const char* delimeter);
static inline unsigned char* addressStrToBytes(const char* addressStr, unsigned char* addressBytes, adress_type_t addtype);
static inline unsigned int ebm_parse_adr(struct eb_lm32_udp_link* link, const char* address);
void ebm_config_if(target_t conf, const char* con_info)
{
struct eb_lm32_udp_link* link;
unsigned int offset;
unsigned int tmp;
ebm_parse_adr(link, con_info);
if(conf == LOCAL) offset = EBM_OFFS_LOCAL;
if(conf == REMOTE) offset = EBM_OFFS_REMOTE;
tmp = (link->mac[0] << 24) | (link->mac[1] << 16) | (link->mac[2] << 8) | link->mac[3];
*(ebm + ((offset + EBM_OFFS_MAC_HI) >>2)) = tmp;
tmp = (link->mac[4] << 24) | (link->mac[5] << 16);
*(ebm + ((offset + EBM_OFFS_MAC_LO) >>2)) = tmp;
tmp = (link->ipv4[0] << 24) | (link->ipv4[1] << 16) | (link->ipv4[2] << 8) | link->ipv4[3];
*(ebm + ((offset + EBM_OFFS_IPV4) >>2)) = tmp;
*(ebm + ((offset + EBM_OFFS_UDP_PORT) >>2)) = (unsigned int)link->port;
}
void ebm_config_meta(unsigned int pac_len, unsigned int hi_bits, unsigned int max_ops, unsigned int eb_ops)
{
*(ebm + (EBM_REG_PAC_LEN >>2)) = pac_len;
*(ebm + (EBM_REG_OPA_HI >>2)) = hi_bits;
*(ebm + (EBM_REG_OPS_MAX >>2)) = max_ops;
*(ebm + (EBM_REG_EB_OPT >>2)) = eb_ops;
}
void ebm_op(unsigned int address, unsigned int value, unsigned int optype)
{
unsigned int offset = EBM_OFFS_DAT;
//set hibits according to desired address
*(ebm + (EBM_REG_OPA_HI >> 2)) = (address & ~ADR_MASK);
offset += optype;
offset += (address & ADR_MASK);
*(ebm + (offset>>2)) = value;
return;
}
void ebm_flush(void)
{
*(ebm + (EBM_REG_FLUSH>>2)) = 0x01;
}
//String helper functions
static char* strsplit(const char* numstr, const char* delimeter)
{
char* pch = (char*)numstr;
while (*(pch) != '\0')
if(*(pch++) == *delimeter) return pch;
return pch;
}
static unsigned char* numStrToBytes(const char* numstr, unsigned char* bytes, unsigned char len, unsigned char base, const char* delimeter)
{
char * pch;
char * pend;
unsigned char byteCount=0;
long tmpconv;
pch = (char *) numstr;
while ((pch != NULL) && byteCount < len )
{
pend = strsplit(pch, delimeter)-1;
tmpconv = strtol((const char *)pch, &(pend), base);
// in case of a 16 bit value
if(tmpconv > 255) bytes[byteCount++] = (unsigned char)(tmpconv>>8 & 0xff);
bytes[byteCount++] = (unsigned char)(tmpconv & 0xff);
pch = pend+1;
}
return bytes;
}
static unsigned char* addressStrToBytes(const char* addressStr, unsigned char* addressBytes, adress_type_t addtype)
{
unsigned char len;
unsigned char base;
char del;
if(addtype == MAC)
{
len = 6;
base = 16;
del = ':';
}
else if(addtype == IP)
{
len = 4;
base = 10;
del = '.';
}
else{
return NULL;
}
return numStrToBytes(addressStr, addressBytes, len, base, &del);
}
static unsigned int ebm_parse_adr(struct eb_lm32_udp_link* link, const char* address) {
char * pch;
unsigned int stat = 1;
//a proper address string must contain, MAC, IP and port: "hw/11:22:33:44:55:66/udp/192.168.0.1/port/60368"
//parse and fill link struct
pch = (char*) address;
if(pch != NULL)
{
if(strncmp("hw", pch, 2) == 0)
{
pch = strsplit(pch,"/");
if(pch != NULL)
{
addressStrToBytes((const char*)pch, link->mac, MAC);
pch = strsplit(pch,"/");
if(pch != NULL)
{
if(strncmp("udp", pch, 3) == 0)
{
pch = strsplit(pch,"/");
if(pch != NULL) addressStrToBytes(pch, link->ipv4, IP);
pch = strsplit(pch,"/");
if(pch != NULL)
if(strncmp("port", pch, 4) == 0)
{
pch = strsplit(pch,"/");
if(pch != NULL)
{
//addressStrToBytes(pch, link->port, PORT);
link->port = atoi (pch);
stat = 0;
}
}
}
}
}
}
}
return stat;
}
/** @file ebm.h
* @brief Header file for EB Master Core
*
* Copyright (C) 2011-2012 GSI Helmholtz Centre for Heavy Ion Research GmbH
*
*
* @author Mathias Kreider <m.kreider@gsi.de>
*
* @bug None!
*
*******************************************************************************
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************
*/
#ifndef EBM_H
#define EBM_H
#define EBM_REG_RESET 0
#define EBM_REG_FLUSH (EBM_REG_RESET +4)
#define EBM_REG_STATUS (EBM_REG_FLUSH +4)
#define EBM_REG_SRC_MAC_HI (EBM_REG_STATUS +4)
#define EBM_REG_SRC_MAC_LO (EBM_REG_SRC_MAC_HI +4)
#define EBM_REG_SRC_IPV4 (EBM_REG_SRC_MAC_LO +4)
#define EBM_REG_SRC_UDP_PORT (EBM_REG_SRC_IPV4 +4)
#define EBM_REG_DST_MAC_HI (EBM_REG_SRC_UDP_PORT +4)
#define EBM_REG_DST_MAC_LO (EBM_REG_DST_MAC_HI +4)
#define EBM_REG_DST_IPV4 (EBM_REG_DST_MAC_LO +4)
#define EBM_REG_DST_UDP_PORT (EBM_REG_DST_IPV4 +4)
#define EBM_REG_PAC_LEN (EBM_REG_DST_UDP_PORT +4)
#define EBM_REG_OPA_HI (EBM_REG_PAC_LEN +4)
#define EBM_REG_OPS_MAX (EBM_REG_OPA_HI +4)
#define EBM_REG_WOA_BASE (EBM_REG_OPS_MAX +4)
#define EBM_REG_ROA_BASE (EBM_REG_WOA_BASE +4)
#define EBM_REG_EB_OPT (EBM_REG_ROA_BASE +4)
#define EBM_REG_LAST (EBM_REG_EB_OPT;
#define EBM_OFFS_DAT 0x00800000
#define EBM_OFFS_WR 0x00400000
#define EBM_OFFS_LOCAL (EBM_REG_SRC_MAC_HI)
#define EBM_OFFS_REMOTE (EBM_REG_DST_MAC_HI)
#define EBM_OFFS_MAC_HI 0
#define EBM_OFFS_MAC_LO (EBM_OFFS_MAC_HI +4)
#define EBM_OFFS_IPV4 (EBM_OFFS_MAC_LO +4)
#define EBM_OFFS_UDP_PORT (EBM_OFFS_IPV4 +4)
#define WRITE (EBM_OFFS_WR)
#define READ 0x00000000
#define ADR_MASK 0x003FFFFF
typedef struct eb_lm32_udp_link {
/* Contents must fit in 12 bytes */
unsigned char mac[6];
unsigned char ipv4[4];
unsigned short port;
};
typedef unsigned int adress_type_t;
typedef unsigned char target_t;
static const target_t LOCAL = 0;
static const target_t REMOTE = 1;
static const adress_type_t MAC = 1;
static const adress_type_t IP = 2;
static const adress_type_t PORT = 3;
static const unsigned short myPort = 0xEBD0;
void ebm_config_if(target_t conf, const char* con_info);
void ebm_config_meta(unsigned int pac_len, unsigned int hi_bits, unsigned int max_ops, unsigned int eb_ops);
void ebm_op(unsigned int address, unsigned int value, unsigned int optype);
void ebm_flush(void);
#endif
/** @file irq.c
* @brief MSI capable IRQ handler for the LM32
*
* Copyright (C) 2011-2012 GSI Helmholtz Centre for Heavy Ion Research GmbH
*
* @author Mathias Kreider <m.kreider@gsi.de>
*
* @bug None!
*
*******************************************************************************
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************
*/
#include "irq.h"
//#include "display.h" DEBUG
extern unsigned int* irq_slave;
const unsigned int IRQ_REG_RST = 0x00000000;
const unsigned int IRQ_REG_STAT = 0x00000004;
const unsigned int IRQ_REG_POP = 0x00000008;
const unsigned int IRQ_OFFS_MSG = 0x00000000;
const unsigned int IRQ_OFFS_SRC = 0x00000004;
const unsigned int IRQ_OFFS_SEL = 0x00000008;
inline void irq_pop_msi( unsigned int irq_no)
{
unsigned int* msg_queue = (unsigned int*)(irq_slave + ((irq_no +1)<<2));
global_msi.msg = *(msg_queue+(IRQ_OFFS_MSG>>2));
global_msi.src = *(msg_queue+(IRQ_OFFS_SRC>>2));
global_msi.sel = *(msg_queue+(IRQ_OFFS_SEL>>2));
*(irq_slave + (IRQ_REG_POP>>2)) = 1<<irq_no;
return;
}
inline void isr_table_clr(void)
{
//set all ISR table entries to Null
unsigned int i;
for(i=0;i<32;i++) isr_ptr_table[i] = 0;
}
inline unsigned int irq_get_mask(void)
{
//read IRQ mask
unsigned int im;
asm volatile ( "rcsr %0, im": "=&r" (im));
return im;
}
inline void irq_set_mask( unsigned int im)
{
//write IRQ mask
asm volatile ( "wcsr im, %0": "=&r" (im));
return;
}
inline void irq_disable(void)
{
//globally disable interrupts
unsigned int ie;
asm volatile ( "rcsr %0, IE\n" \
"andi %0, %0, 0xFFFE\n" \
"wcsr IE, %0" : "=&r" (ie));
return;
}
inline void irq_enable(void)
{
//globally enable interrupts
unsigned int ie;
asm volatile ( "rcsr %0, IE\n" \
"ori %0, %0, 1\n" \
"wcsr IE, %0" : "=&r" (ie));
return;
}
inline void irq_clear( unsigned int mask)
{
//clear pending interrupt flag(s)
unsigned int ip;
asm volatile ( "rcsr %0, ip\n" \
"and %0, %0, %1\n" \
"wcsr ip, %0" : "=&r" (ip): "r" (mask) );
return;
}
inline void irq_process(void)
{
char buffer[12];
unsigned int ip;
unsigned char irq_no = 0;
//get pending flags
asm volatile ("rcsr %0, ip": "=r"(ip));
while(ip) //irqs pending ?
{
if(ip & 0x01) //check if irq with lowest number is pending
{
irq_pop_msi(irq_no); //pop msg from msi queue into global_msi variable
irq_clear(1<<irq_no); //clear pending bit
if((unsigned int)isr_ptr_table[irq_no]) isr_ptr_table[irq_no](); //execute isr
//else disp_put_str("No ISR\nptr found!\n"); DEBUG
}
irq_no++;
ip = ip >> 1; //process next irq
}
return;
}
/** @file irq.h
* @brief Header file for MSI capable IRQ handler for the LM32
*
* Copyright (C) 2011-2012 GSI Helmholtz Centre for Heavy Ion Research GmbH
*
* Usage:
*
* void <an ISR>(void) { <evaluate global_msi and do something useful> }
* ...
* void _irq_entry(void) {irq_process();}
* ...
* void main(void) {
*
* isr_table_clr();
* isr_ptr_table[0]= <an ISR>;
* isr_ptr_table[1]= ...
* ...
* irq_set_mask(0x03); //Enable used IRQs ...
* irq_enable();
* ...
* }
*
* @author Mathias Kreider <m.kreider@gsi.de>
*
* @bug None!
*
*******************************************************************************
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library. If not, see <http://www.gnu.org/licenses/>.
*******************************************************************************
*/
#ifndef __IRQ_H_
#define __IRQ_H_
typedef struct
{
unsigned int msg;
unsigned int src;
unsigned int sel;
} msi;
//ISR function pointer table
typedef void (*isr_ptr_t)(void);
isr_ptr_t isr_ptr_table[32];
//Global containing last processed MSI message
volatile msi global_msi;
inline void irq_pop_msi( unsigned int irq_no);
inline unsigned int irq_get_mask(void);
inline void irq_set_mask( unsigned int im);
inline void irq_disable(void);
inline void irq_enable(void);
inline void irq_clear( unsigned int mask);
inline void isr_table_clr(void);
inline void irq_process(void);
#endif
/*
* Simulator Link script for Lattice Mico32.
* Contributed by Jon Beniston <jon@beniston.com>
*
* 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.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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.
*/
OUTPUT_FORMAT("elf32-lm32")
ENTRY(_start)
/*INPUT() */
GROUP(-lgcc -lc)
MEMORY
{
ram : ORIGIN = 0x00000000, LENGTH = 0x10000 /* 64K */
ram :
ORIGIN = 0x00000000,
LENGTH = 65536 - 8192 - 8192
stack :
ORIGIN = 65536 - 8192,
LENGTH = 8192
shared :
ORIGIN = 65536 - 8192 - 8192,
LENGTH = 8192
}
SECTIONS
{
.boot : { *(.boot) } > ram
.text : { *(.text .text.*) } > ram =0
.rodata : { *(.rodata .rodata.*) } > ram
.data : {
*(.data .data.*)
_gp = ALIGN(16) + 0x7ff0;
} > ram
.bss : {
_fbss = .;
*(.bss .bss.*)
*(COMMON)
_ebss = .;
} > ram
.shared_mem : { *(.shared_mem) } > shared
.boot : { *(.boot) } > ram
/* Code */
.text :
{
. = ALIGN(4);
_ftext = .;
_ftext_rom = LOADADDR(.text);
*(.text .stub .text.* .gnu.linkonce.t.*)
*(.gnu.warning)
KEEP (*(.init))
KEEP (*(.fini))
/* Constructors and destructors */
KEEP (*crtbegin*.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend*.o ) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
KEEP (*crtbegin*.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend*.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
KEEP (*(.jcr))
_etext = .;
} > ram =0
PROVIDE(_startshared = ORIGIN(shared));
PROVIDE(_endshared = ORIGIN(shared) + LENGTH(shared) - 4);
/* Exception handlers */
.eh_frame_hdr : { *(.eh_frame_hdr) } > ram
.eh_frame : { KEEP (*(.eh_frame)) } > ram
.gcc_except_table : { *(.gcc_except_table) *(.gcc_except_table.*) } > ram
/* Read-only data */
.rodata :
{
. = ALIGN(4);
_frodata = .;
_frodata_rom = LOADADDR(.rodata);
*(.rodata .rodata.* .gnu.linkonce.r.*)
*(.rodata1)
_erodata = .;
} > ram
/* Data */
.data :
{
. = ALIGN(4);
_fdata = .;
_fdata_rom = LOADADDR(.data);
*(.data .data.* .gnu.linkonce.d.*)
*(.data1)
SORT(CONSTRUCTORS)
_gp = ALIGN(16) + 0x7ff0;
*(.sdata .sdata.* .gnu.linkonce.s.*)
_edata = .;
} > ram
/* BSS */
.bss :
{
. = ALIGN(4);
_fbss = .;
*(.dynsbss)
*(.sbss .sbss.* .gnu.linkonce.sb.*)
*(.scommon)
*(.dynbss)
*(.bss .bss.* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = .;
_end = .;
PROVIDE (end = .);
} > ram
/* First location in stack is highest address in RAM */
PROVIDE(_fstack = ORIGIN(ram) + LENGTH(ram) - 4);
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
PROVIDE(_endram = ORIGIN(stack));
PROVIDE(_fstack = ORIGIN(stack) + LENGTH(stack) - 4);
}
PROVIDE(mprintf = pp_printf);
#include <stdio.h>
#include "display.h"
#include "irq.h"
#include <string.h>
#include <inttypes.h>
#include <stdint.h>
#include "mprintf.h"
#include "mini_sdb.h"
#include "ebm.h"
#include "aux.h"
#include "dbg.h"
unsigned int cpuId, cpuQty, heapCap;
volatile unsigned int* display = (unsigned int*)0x02900000;
volatile unsigned int* irq_slave = (unsigned int*)0x02000d00;
volatile unsigned int* ebm = (unsigned int*)0x01000000;
char* mat_sprinthex(char* buffer, unsigned long val)
{
unsigned char i,ascii;
const unsigned long mask = 0x0000000F;
for(i=0; i<8;i++)
{
ascii= (val>>(i<<2)) & mask;
if(ascii > 9) ascii = ascii - 10 + 'A';
else ascii = ascii + '0';
buffer[7-i] = ascii;
}
buffer[8] = 0x00;
return buffer;
}
void show_msi()
{
char buffer[12];
disp_put_str("D ");
disp_put_str(mat_sprinthex(buffer, global_msi.msg));
disp_put_c('\n');
disp_put_str("A ");
disp_put_str(mat_sprinthex(buffer, global_msi.src));
disp_put_c('\n');
mprintf(" Msg:\t%08x\nAdr:\t%08x\nSel:\t%01x\n", global_msi.msg, global_msi.adr, global_msi.sel);
disp_put_str("S ");
disp_put_str(mat_sprinthex(buffer, (unsigned long)global_msi.sel));
disp_put_c('\n');
}
void isr0()
{
unsigned int j;
disp_put_str("ISR0\n");
show_msi();
for (j = 0; j < 125000000; ++j) {
asm("# noop"); /* no-op the compiler can't optimize away */
}
disp_put_c('\f');
mprintf("ISR0\n");
show_msi();
}
void isr1()
{
unsigned int j;
disp_put_str("ISR1\n");
show_msi();
for (j = 0; j < 125000000; ++j) {
asm("# noop"); /* no-op the compiler can't optimize away */
}
disp_put_c('\f');
mprintf("ISR1\n");
show_msi();
}
void _irq_entry(void) {
disp_put_c('\f');
disp_put_str("IRQ_ENTRY\n");
irq_process();
void ebmInit()
{
ebm_init();
ebm_config_if(LOCAL, "hw/cb:a9:87:65:43:21/udp/192.168.191.250/port/60000");
ebm_config_if(REMOTE, "hw/ff:ff:ff:ff:ff:ff/udp/192.168.191.255/port/60000");
ebm_config_meta(1500, 0x11, 255, 0x00000000 );
}
void init()
{
discoverPeriphery();
uart_init_hw();
ebmInit();
cpuId = getCpuIdx();
isr_table_clr();
isr_ptr_table[0] = isr0; //timer
isr_ptr_table[1] = isr1;
irq_set_mask(0x03);
irq_enable();
}
const char mytext[] = "Hallo Welt!...\n\n";
void main(void) {
isr_table_clr();
isr_ptr_table[0]= isr0;
isr_ptr_table[1]= isr1;
irq_set_mask(0x03);
irq_enable();
void main(void) {
int j;
uint32_t inc = 0;
init();
for (j = 0; j < (125000000/4); ++j) { asm("nop"); }
int i, j, xinc, yinc, x, y;
unsigned int time = 0;
unsigned int addr_raw_off;
char color = 0xFF;
x = 0;
y = 9;
yinc = -1;
xinc = 1;
addr_raw_off = 0;
disp_reset();
disp_put_c('\f');
disp_put_str(mytext);
///////////////////////////////////////////////////////////////////////////////////
//Init EB Master
ebm_config_if(LOCAL, "hw/08:00:30:e3:b0:5a/udp/192.168.191.254/port/60368");
ebm_config_if(REMOTE, "hw/bc:30:5b:e2:b0:88/udp/192.168.191.131/port/60368");
ebm_config_meta(80, 0x11, 16, 0x00000000 );
while (1) {
//Send packet heartbeat
if(time++ > 50) {
//create WB cycle
ebm_op(0x55000333, 0xDEADBEEF, WRITE);
ebm_op(0x22000333, 0xCAFEBABE, READ);
//send
ebm_flush();
}
///////////////////////////////////////////////////////////////////////////////////
/* Each loop iteration takes 4 cycles.
* It runs at 125MHz.
* Sleep 0.2 second.
*/
while (1) {
atomic_on();
ebm_clr();
ebm_udp_start();
for (j = 0; j < 10; ++j) ebm_udp(0xCAFE0000 + inc++);
ebm_udp_end();
atomic_off();
for (j = 0; j < (125000000/4); ++j) { asm("nop"); }
}
// disp_put_raw( get_pixcol_val((unsigned char)y), get_pixcol_addr((unsigned char)x, (unsigned char)y), color);
for (j = 0; j < 62500000/160; ++j) {
asm("# noop"); /* no-op the compiler can't optimize away */
}
if(x == 63) xinc = -1;
if(x == 0) xinc = 1;
if(y == 47) yinc = -1;
if(y == 0) yinc = 1;
x += xinc;
y += yinc;
if(time++ > 500) {time = 0; color = ~color; }
}
}
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment