Updating examples to Board changes, adding irq driver demo

This commit is contained in:
Carlos Camargo 2010-06-11 08:06:13 -05:00
parent c8b70e5307
commit 5041c0eb60
41 changed files with 2263 additions and 145 deletions

View File

@ -1,6 +1,7 @@
NET clk LOC = "P38";
NET reset LOC = "P71"; #WARNING change to another pin
NET led LOC = "P44";
NET clk LOC = "P38";
NET reset LOC = "P30"; #WARNING change to another pin
NET led LOC = "P44";
NET irq_pin LOC = "P71";
#ADDRESS BUS
NET "addr<12>" LOC = "P90";

View File

@ -1,13 +1,14 @@
`timescale 1ns / 1ps
module ADC(clk, sram_data, addr, nwe, ncs, noe, reset, led, ADC_EOC,
ADC_SCLK, ADC_SDIN, ADC_SDOUT, ADC_CS, ADC_CSTART);
ADC_SCLK, ADC_SDIN, ADC_SDOUT, ADC_CS, ADC_CSTART, irq_pin);
parameter B = (7);
parameter B = (7);
input clk, addr, nwe, ncs, noe, reset, ADC_EOC;
inout [B:0] sram_data;
output led, ADC_CS, ADC_CSTART, ADC_SCLK;
inout ADC_SDIN, ADC_SDOUT;
inout ADC_SDIN, ADC_SDOUT;
input irq_pin;
// Internal conection
@ -32,7 +33,7 @@ module ADC(clk, sram_data, addr, nwe, ncs, noe, reset, led, ADC_EOC,
// Test : LED blinking
always @(posedge clk) begin
if (reset)
if (~reset)
counter <= {25{1'b0}};
else
counter <= counter + 1;
@ -54,7 +55,7 @@ module ADC(clk, sram_data, addr, nwe, ncs, noe, reset, led, ADC_EOC,
// write access cpu to bram
always @(posedge clk)
if(reset) {w_st, we, wrBus} <= 0;
if(~reset) {w_st, we, wrBus} <= 0;
else begin
wrBus <= buffer_data;
case (w_st)
@ -89,7 +90,7 @@ module ADC(clk, sram_data, addr, nwe, ncs, noe, reset, led, ADC_EOC,
// Peripheral instantiation
ADC_peripheral P1(
.clk(clk),
.reset(reset),
.reset(~reset),
.cs(csN[0]),
.ADC_EOC(ADC_EOC),
.ADC_CS(ADC_CS),

View File

@ -1,5 +1,5 @@
NET clk LOC = "P38";
NET reset LOC = "P71";
NET reset LOC = "P30";
NET led LOC = "P44";
#ADDRESS BUS

View File

@ -5,7 +5,7 @@ module blink(clk, reset, led);
reg [24:0] counter;
always @(posedge clk) begin
if (reset)
if (~reset)
counter <= {25{1'b0}};
else
counter <= counter + 1;

View File

@ -0,0 +1,23 @@
EXTRA_CFLAGS += -Wall
CC = mipsel-openwrt-linux-gcc
OPENWRT_BASE = /home/cain/Embedded/ingenic/sakc/build/openwrt-xburst
KERNEL_SRC = $(OPENWRT_BASE)/build_dir/linux-xburst_qi_lb60/linux-2.6.32.10/
CROSS_COMPILE = mipsel-openwrt-linux-
obj-m += irq.o
all: driver irq_main
driver:
make -C $(KERNEL_SRC) M=$(PWD) ARCH=mips CROSS_COMPILE=$(CROSS_COMPILE) modules
clean:
make -C $(KERNEL_SRC) M=$(PWD) ARCH=mips CROSS_COMPILE=$(CROSS_COMPILE) clean
rm -rf *.o main.o main irq.ko Modules.symvers irq_main
main: main.o
PREPROCESS.c = $(CC) $(CFLAGS) $(TARGET_ARCH) -E -Wp,-C,-dD,-dI
%.pp : %.c FORCE
$(PREPROCESS.c) $< > $@

175
Examples/drivers/IRQ/irq.c Normal file
View File

@ -0,0 +1,175 @@
/*
* Interrupt device driver demo
*
* Author: Andres Calderon
* Created: September 16, 2005
* Copyright: (C) 2005 emQbit Ltda
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
*/
#include <linux/module.h> /* Needed by all modules */
#include <linux/kernel.h> /* Needed for KERN_INFO */
#include <linux/ioport.h>
#include <linux/device.h>
#include <linux/interrupt.h> /* We want an interrupt */
#include <linux/irq.h> /* We want an interrupt */
#include <linux/platform_device.h>
#include <linux/fs.h>
#include <asm/delay.h>
#include <asm/uaccess.h>
#include <asm/io.h>
#include <linux/gpio.h>
#include <asm/mach-jz4740/gpio.h>
#define FPGA_IRQ_PIN JZ_GPIO_PORTC(15)
#define FPGA_BASE 0x15000000 //FPGA_BASE (FPGA) 0x14000000 - 0x17FFFFFF //
#define SUCCESS 0
#define DEVICE_NAME "irq" /* Dev name as it appears in /proc/devices */
#define BUF_LEN 80 /* Max length of the message from the device */
static int device_open(struct inode *, struct file *);
static int device_release(struct inode *, struct file *);
static ssize_t device_read(struct file *, char *, size_t, loff_t *);
static ssize_t device_write(struct file *, const char *, size_t, loff_t *);
static int irq_enabled = 0;
static int is_device_open = 0; /* Is device open? Used to prevent multiple access to device */
static int Major;
void __iomem *ioaddress;
static unsigned int interrupt_counter = 0;
static DECLARE_WAIT_QUEUE_HEAD(wq);
struct file_operations fops = {
.owner = THIS_MODULE,
.read = device_read,
.write = device_write,
.open = device_open,
.release = device_release
};
static irqreturn_t irq_handler(int irq, void *dev_id)
{
if(irq_enabled)
{
interrupt_counter++;
printk(KERN_INFO "interrupt_counter=%d\n",interrupt_counter);
wake_up_interruptible(&wq);
}
return IRQ_HANDLED;
}
static int __init qem_init(void)
{
int res, irq;
printk(KERN_INFO "FPGA module is Up.\n");
interrupt_counter = 0;
Major = register_chrdev(0, DEVICE_NAME, &fops);
if (Major < 0) {
printk(KERN_ALERT "Registering char device failed with %d\n", Major);
return Major;
}
printk(KERN_ALERT "I was assigned major number %d. To talk to\n", Major);
printk(KERN_ALERT "the driver, create a dev file with\n");
printk(KERN_ALERT "'mknod /dev/%s c %d 0'.\n", DEVICE_NAME, Major);
/* Set up the FGPA irq line */
irq = gpio_to_irq(FPGA_IRQ_PIN);
res = request_irq(irq, irq_handler, IRQF_DISABLED | IRQF_TRIGGER_RISING, "FPGA - IRQ", NULL); // IRQF_TRIGGER_FALLING
ioaddress = ioremap(FPGA_BASE, 0x4000);
return 0;
}
static void __exit qem_exit(void)
{
// int ret;
/*Tho order for free_irq, iounmap & unregister is very important */
free_irq(FPGA_IRQ_PIN, NULL);
iounmap(ioaddress);
unregister_chrdev(Major, DEVICE_NAME);
printk(KERN_INFO "FPGA driver is down...\n");
}
static int device_open(struct inode *inode, struct file *file)
{
if (is_device_open)
return -EBUSY;
is_device_open = 1;
try_module_get(THIS_MODULE);
return SUCCESS;
}
static int device_release(struct inode *inode, struct file *file)
{
is_device_open = 0;
module_put(THIS_MODULE);
return 0;
}
static ssize_t device_read(struct file *filp, /* see include/linux/fs.h */
char *buffer, /* buffer to fill with data */
size_t count, /* length of the buffer */
loff_t *offset)
{
wait_event_interruptible(wq, interrupt_counter!=0);
return copy_to_user(buffer, &interrupt_counter, sizeof(interrupt_counter)) ? -EFAULT : 0;
}
static ssize_t
device_write(struct file *filp, const char *buff, size_t count, loff_t * off)
{
const char cmd = buff[0];
if(cmd=='Q')
{
irq_enabled = 1;
printk(KERN_INFO "FPGA irq_enabled...\n");
}
else
if(cmd=='S'){
irq_enabled = 0;
printk(KERN_INFO "FPGA irq disabled.\n");
}
return 1;
}
module_init(qem_init);
module_exit(qem_exit);
MODULE_LICENSE("GPL");
MODULE_AUTHOR("Andres Calderon <andresn@emqbit.com>");
MODULE_DESCRIPTION("FPGA' IRQ driver");
MODULE_VERSION("1:0.1");

View File

@ -0,0 +1,53 @@
/*******************************************************************************
*
* Filename: irq_main.c
* Author: Carlos Camargo
* Created: June 10, 2010
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
******************************************************************************/
#include "stdio.h"
#include "sys/types.h"
#include "sys/stat.h"
#include "fcntl.h"
#include <unistd.h>
#include <stdlib.h>
int main(int argc, char **argv) {
int fileNum, bytes;
unsigned char buf[40];
size_t nbytes;
ssize_t bytes_read;
if(argc != 2){
fprintf(stderr,"\nUsage: %s enable|disable|read \n",argv[0]);
}
nbytes = sizeof(int);
fileNum = open("/dev/irq", O_RDWR);
if (fileNum < 0) {
printf(" Unable to open device\n");
exit(1);
}
printf("Device opened successfully \n");
if(!strcmp(argv[1], "enable"))
write(fileNum, "Q", 1);
if(!strcmp(argv[1], "disable"))
write(fileNum, "S", 1);
if(!strcmp(argv[1], "read")){
read(fileNum, buf, nbytes);
printf("Interrupts = %d \n", *((int*)(buf)));
}
if( (strcmp(argv[1], "read") != 0 ) & (strcmp(argv[1], "disable") != 0) & (strcmp(argv[1], "enable") != 0) )
fprintf(stderr,"\nUsage: %s enable|disable|read \n",argv[0]);
close(fileNum);
return (0);
}

View File

@ -1,7 +1,6 @@
OBJS := start.o main.o jz_serial.o
CROSS := mipsel-elf-
CROSS := mipsel-openwrt-linux-
CFLAGS := -O2 -G 0 -mno-abicalls -fno-pic -mips32 -Iinclude
AFLAGS = -D__ASSEMBLY__ $(CFLAGS)

View File

@ -1,2 +0,0 @@
sudo usbboot -f ./usbboot_2gb_nand.cfg -c "boot"
sudo usbboot -f ./usbboot_2gb_nand.cfg -c "nprog 0 openwrt-xburst-u-boot.bin 0 0 -n"

View File

@ -1,25 +0,0 @@
OBJS := start.o main.o jz_serial.o
CROSS := mipsel-elf-
CFLAGS := -O2 -G 0 -mno-abicalls -fno-pic -mips32 -Iinclude
AFLAGS = -D__ASSEMBLY__ $(CFLAGS)
LDFLAGS := -T ld.script -nostdlib -EL
.c.o:
$(CROSS)gcc $(CFLAGS) -c $< -o $@
.S.o:
$(CROSS)gcc $(AFLAGS) -c $< -o $@
jz_xloader.bin: jz_xloader
$(CROSS)objdump -D jz_xloader $< > jz_xloader.dump
$(CROSS)objcopy -O binary $< $@
jz_xloader: $(OBJS)
$(CROSS)ld $(LDFLAGS) $^ -o $@
upload:
usbtool 1
clean:
rm -fr *.o jz_xloader jz_xloader.bin jz_xloader.dump

View File

@ -1,7 +1,7 @@
OBJS := start.o main.o jz_serial.o
CROSS := mipsel-elf-
CROSS := mipsel-openwrt-linux-
CFLAGS := -O2 -G 0 -mno-abicalls -fno-pic -mips32 -Iinclude
AFLAGS = -D__ASSEMBLY__ $(CFLAGS)

View File

@ -1,6 +1,7 @@
NET clk LOC = "P38";
NET reset LOC = "P71";
NET led LOC = "P44";
NET clk LOC = "P38";
NET reset LOC = "P30";
NET led LOC = "P44";
NET irq_pin LOC = "P71";
#ADDRESS BUS
NET "addr<12>" LOC = "P90";

View File

@ -1,11 +1,12 @@
`timescale 1ns / 1ps
module sram_bus(clk, sram_data, addr, nwe, ncs, noe, reset, led);
module sram_bus(clk, sram_data, addr, nwe, ncs, noe, reset, led, irq_pin);
parameter B = (7);
input clk, nwe, ncs, noe, reset;
input [12:0] addr;
inout [B:0] sram_data;
output led;
input irq_pin;
// synchronize signals
reg sncs, snwe;
@ -39,7 +40,7 @@ module sram_bus(clk, sram_data, addr, nwe, ncs, noe, reset, led);
// write access cpu to bram
always @(posedge clk)
if(reset) {w_st, we, wdBus} <= 0;
if(~reset) {w_st, we, wdBus} <= 0;
else begin
wdBus <= buffer_data;
case (w_st)
@ -71,7 +72,7 @@ RAMB16_S2 ba3( .CLK(~clk), .EN(1'b1), .SSR(1'b0), .ADDR(buffer_addr),
reg [24:0] counter;
always @(posedge clk) begin
if (reset)
if (~reset)
counter <= {25{1'b0}};
else
counter <= counter + 1;

View File

@ -1,6 +1,6 @@
CC = mipsel-openwrt-linux-gcc
all: jz_init_sram jz_test_gpio enable_rx
all: jz_init_sram jz_test_gpio enable_rx enable_irq
DEBUG = -O3 -g0
@ -29,6 +29,9 @@ jz_test_gpio: $(COMMON_OBJECTS)
enable_rx: $(COMMON_OBJECTS)
$(CC) $(LDFLAGS) $(COMMON_OBJECTS) enable_rx.c -o enable_rx
enable_irq: $(COMMON_OBJECTS)
$(CC) $(LDFLAGS) $(COMMON_OBJECTS) enable_irq.c -o enable_irq
.c.o:
$(CC) -c $(CCFLAGS) $< -o $@
@ -36,7 +39,7 @@ upload: jz_init_sram jz_test_gpio
scp jz_test_gpio jz_init_sram root@$(NANO_IP):
clean:
rm -f *.o jz_init_sram jz_test_gpio enable_rx ${EXEC} *~
rm -f *.o jz_init_sram jz_test_gpio enable_rx ${EXEC} *~ enable_irq
indent:
indent -bad -bap -nbc -bl -nce -i2 --no-tabs --line-length120 $(COMMON_SOURCES) $(H_SOURCES)

View File

@ -43,6 +43,14 @@ jz_gpio_as_input (JZ_PIO * pio, unsigned int o)
pio->PXDIRC = (1 << (o));
}
void
jz_gpio_as_irq (JZ_PIO * pio, unsigned int o)
{
pio->PXFUNC = (1 << (o));
pio->PXSELS = (1 << (o));
pio->PXDIRC = (1 << (o));
}
void
jz_gpio_set_pin (JZ_PIO * pio, unsigned int o)
{

@ -0,0 +1 @@
Subproject commit 0219d98a994a35c46d700460caa78f84c971b9af

View File

@ -0,0 +1,232 @@
/*
* PS2 Interface
* Copyright (C) 2009 Takeshi Matsuya
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module ps2 #(
parameter csr_addr = 4'h0,
parameter clk_freq = 100000000
) (
input sys_rst,
input sys_clk,
input [13:0] csr_a,
input csr_we,
input [31:0] csr_di,
output reg [31:0] csr_do,
inout ps2_clk,
inout ps2_data,
output reg irq
);
/* CSR interface */
wire csr_selected = csr_a[13:10] == csr_addr;
reg tx_busy;
//-----------------------------------------------------------------
// divisor
//-----------------------------------------------------------------
reg [9:0] enable_counter;
wire enable;
assign enable = (enable_counter == 10'd0);
parameter divisor = clk_freq/12800/16;
always @(posedge sys_clk) begin
if(sys_rst)
enable_counter <= divisor - 10'd1;
else begin
enable_counter <= enable_counter - 10'd1;
if(enable)
enable_counter <= divisor - 10'd1;
end
end
//-----------------------------------------------------------------
// Synchronize ps2 clock and data
//-----------------------------------------------------------------
reg ps2_clk_1;
reg ps2_data_1;
reg ps2_clk_2;
reg ps2_data_2;
reg ps2_clk_out;
reg ps2_data_out1, ps2_data_out2;
always @(posedge sys_clk) begin
ps2_clk_1 <= ps2_clk;
ps2_data_1 <= ps2_data;
ps2_clk_2 <= ps2_clk_1;
ps2_data_2 <= ps2_data_1;
end
/* PS2 */
reg [7:0] kcode;
reg rx_clk_data;
reg [5:0] rx_clk_count;
reg [4:0] rx_bitcount;
reg [10:0] rx_data;
reg [10:0] tx_data;
reg we_reg;
/* FSM */
reg [2:0] state;
reg [2:0] next_state;
parameter RECEIVE = 3'd0;
parameter WAIT_READY = 3'd1;
parameter CLOCK_LOW = 3'd2;
parameter CLOCK_HIGH = 3'd3;
parameter CLOCK_HIGH1 = 3'd4;
parameter CLOCK_HIGH2 = 3'd5;
parameter WAIT_CLOCK_LOW = 3'd6;
parameter TRANSMIT = 3'd7;
assign state_receive = state == RECEIVE;
assign state_transmit = state == TRANSMIT;
always @(posedge sys_clk) begin
if(sys_rst)
state = RECEIVE;
else begin
state = next_state;
end
end
/* ps2 clock falling edge 100us counter */
//parameter divisor_100us = clk_freq/10000;
parameter divisor_100us = 1;
reg [16:0] watchdog_timer;
wire watchdog_timer_done;
assign watchdog_timer_done = (watchdog_timer == 17'd0);
always @(sys_clk) begin
if(sys_rst||ps2_clk_out)
watchdog_timer <= divisor_100us - 1;
else if(~watchdog_timer_done)
watchdog_timer <= watchdog_timer - 1;
end
always @(*) begin
ps2_clk_out = 1'b1;
ps2_data_out1 = 1'b1;
tx_busy = 1'b1;
next_state = state;
case(state)
RECEIVE: begin
tx_busy = 1'b0;
if(we_reg) begin
next_state = WAIT_READY;
end
end
WAIT_READY: begin
if(rx_bitcount == 5'd0) begin
ps2_clk_out = 1'b0;
next_state = CLOCK_LOW;
end
end
CLOCK_LOW: begin
ps2_clk_out = 1'b0;
if(watchdog_timer_done) begin
next_state = CLOCK_HIGH;
end
end
CLOCK_HIGH: begin
next_state = CLOCK_HIGH1;
end
CLOCK_HIGH1: begin
next_state = CLOCK_HIGH2;
end
CLOCK_HIGH2: begin
ps2_data_out1 = 1'b0;
next_state = WAIT_CLOCK_LOW;
end
WAIT_CLOCK_LOW: begin
ps2_data_out1 = 1'b0;
if(ps2_clk_2 == 1'b0) begin
next_state = TRANSMIT;
end
end
TRANSMIT: begin
if(rx_bitcount == 5'd10) begin
next_state = RECEIVE;
end
end
endcase
end
//-----------------------------------------------------------------
// PS2 RX/TX Logic
//-----------------------------------------------------------------
always @(posedge sys_clk) begin
if(sys_rst) begin
rx_clk_data <= 1'd1;
rx_clk_count <= 5'd0;
rx_bitcount <= 5'd0;
rx_data <= 11'b11111111111;
irq <= 1'd0;
csr_do <= 32'd0;
we_reg <= 1'b0;
ps2_data_out2 <= 1'b1;
end else begin
irq <= 1'b0;
we_reg <= 1'b0;
csr_do <= 32'd0;
if(csr_selected) begin
case(csr_a[0])
1'b0: csr_do <= kcode;
1'b1: csr_do <= tx_busy;
endcase
if(csr_we && csr_a[0] == 1'b0) begin
tx_data <= {2'b11, ~(^csr_di[7:0]), csr_di[7:0]}; // STOP+PARITY+DATA
we_reg <= 1'b1;
end
end
if(enable) begin
if(rx_clk_data == ps2_clk_2) begin
rx_clk_count <= rx_clk_count + 5'd1;
end else begin
rx_clk_count <= 5'd0;
rx_clk_data <= ps2_clk_2;
end
if(state_receive && rx_clk_data == 1'b0 && rx_clk_count == 5'd4) begin
rx_data <= {ps2_data_2, rx_data[10:1]};
rx_bitcount <= rx_bitcount + 5'd1;
if(rx_bitcount == 5'd10) begin
irq <= 1'b1;
kcode <= rx_data[9:2];
end
end
if(state_transmit && rx_clk_data == 1'b0 && rx_clk_count == 5'd0) begin
ps2_data_out2 <= tx_data[rx_bitcount];
rx_bitcount <= rx_bitcount + 5'd1;
if(rx_bitcount == 5'd10) begin
ps2_data_out2 <= 1'b1;
end
end
if(rx_clk_count == 5'd16) begin
rx_bitcount <= 5'd0;
rx_data <= 11'b11111111111;
end
end
end
end
assign ps2_clk = ps2_clk_out ? 1'hz : 1'b0;
assign ps2_data = ps2_data_out1 & ps2_data_out2 ? 1'hz : 1'b0;
endmodule

View File

@ -0,0 +1,23 @@
TEX=uart.tex
DVI=$(TEX:.tex=.dvi)
PS=$(TEX:.tex=.ps)
PDF=$(TEX:.tex=.pdf)
AUX=$(TEX:.tex=.aux)
LOG=$(TEX:.tex=.log)
all: $(PDF)
%.dvi: %.tex
latex $<
%.ps: %.dvi
dvips $<
%.pdf: %.ps
ps2pdf $<
clean:
rm -f $(DVI) $(PS) $(PDF) $(AUX) $(LOG)
.PHONY: clean

View File

@ -0,0 +1,57 @@
\documentclass[a4paper,11pt]{article}
\usepackage{fullpage}
\usepackage[latin1]{inputenc}
\usepackage[T1]{fontenc}
\usepackage[normalem]{ulem}
\usepackage[english]{babel}
\usepackage{listings,babel}
\lstset{breaklines=true,basicstyle=\ttfamily}
\usepackage{graphicx}
\usepackage{moreverb}
\usepackage{amsmath}
\usepackage{url}
\usepackage{tabularx}
\title{Simple UART}
\author{S\'ebastien Bourdeauducq}
\date{December 2009}
\begin{document}
\setlength{\parindent}{0pt}
\setlength{\parskip}{5pt}
\maketitle{}
\section{Specifications}
The UART is based on a very simple design from Das Labor. Its purpose is basically to provide a debug console.
The UART operates with 8 bits per character, no parity, and 1 stop bit. The default baudrate is configured during synthesis and can be modified at runtime using the divisor register.
The divisor is computed as follows :
\begin{equation*}
\text{divisor} = \frac{\text{Clock frequency (Hz)}}{16 \cdot \text{Bitrate (bps)}}
\end{equation*}
\section{Registers}
\begin{tabularx}{\textwidth}{|l|l|l|X|}
\hline
\bf{Offset} & \bf{Read/Write} & \bf{Default} & \bf{Description} \\
\hline
0x0 & RW & 0x00 & Data register. Received bytes and bytes to transmit are read/written from/to this register. \\
\hline
0x4 & RW & for default bitrate & Divisor register (for bitrate selection). \\
\hline
\end{tabularx}\\
\section{Interrupts}
The core has two active-high edge-sensitive interrupts outputs.
The ``RX'' interrupt is sent whenever a new character is received. The CPU should then read the data register immediately. If a new character is sent before the CPU has had time to read it, the first character will be lost.
The ``TX'' interrupt is sent as soon as the UART finished transmitting a character. When the CPU has written to the data register, it must wait for the interrupt before writing again.
\section{Using the core}
Connect the CSR signals and the interrupts to the system bus and the interrupt controller. The \verb!uart_txd! and \verb!uart_rxd! signals should go to the FPGA pads. You must also provide the desired default baudrate and the system clock frequency in Hz using the parameters.
\section*{Copyright notice}
Copyright \copyright 2007-2009 S\'ebastien Bourdeauducq. \\
Permission is granted to copy, distribute and/or modify this document under the terms of the GNU Free Documentation License, Version 1.3; with no Invariant Sections, no Front-Cover Texts, and no Back-Cover Texts. A copy of the license is included in the LICENSE.FDL file at the root of the Milkymist source distribution.
\end{document}

View File

@ -0,0 +1,87 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module uart #(
parameter csr_addr = 4'h0,
parameter clk_freq = 100000000,
parameter baud = 115200
) (
input sys_clk,
input sys_rst,
input [13:0] csr_a,
input csr_we,
input [31:0] csr_di,
output reg [31:0] csr_do,
output rx_irq,
output tx_irq,
input uart_rxd,
output uart_txd
);
reg [15:0] divisor;
wire [7:0] rx_data;
wire [7:0] tx_data;
wire tx_wr;
uart_transceiver transceiver(
.sys_clk(sys_clk),
.sys_rst(sys_rst),
.uart_rxd(uart_rxd),
.uart_txd(uart_txd),
.divisor(divisor),
.rx_data(rx_data),
.rx_done(rx_irq),
.tx_data(tx_data),
.tx_wr(tx_wr),
.tx_done(tx_irq)
);
/* CSR interface */
wire csr_selected = csr_a[13:10] == csr_addr;
assign tx_data = csr_di[7:0];
assign tx_wr = csr_selected & csr_we & (csr_a[0] == 1'b0);
parameter default_divisor = clk_freq/baud/16;
always @(posedge sys_clk) begin
if(sys_rst) begin
divisor <= default_divisor;
csr_do <= 32'd0;
end else begin
csr_do <= 32'd0;
if(csr_selected) begin
case(csr_a[0])
1'b0: csr_do <= rx_data;
1'b1: csr_do <= divisor;
endcase
if(csr_we) begin
if(csr_a[0] == 1'b1)
divisor <= csr_di[15:0];
end
end
end
end
endmodule

View File

@ -0,0 +1,157 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
* Copyright (C) 2007 Das Labor
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module uart_transceiver(
input sys_rst,
input sys_clk,
input uart_rxd,
output reg uart_txd,
input [15:0] divisor,
output reg [7:0] rx_data,
output reg rx_done,
input [7:0] tx_data,
input tx_wr,
output reg tx_done
);
//-----------------------------------------------------------------
// enable16 generator
//-----------------------------------------------------------------
reg [15:0] enable16_counter;
wire enable16;
assign enable16 = (enable16_counter == 16'd0);
always @(posedge sys_clk) begin
if(sys_rst)
enable16_counter <= divisor - 16'b1;
else begin
enable16_counter <= enable16_counter - 16'd1;
if(enable16)
enable16_counter <= divisor - 16'b1;
end
end
//-----------------------------------------------------------------
// Synchronize uart_rxd
//-----------------------------------------------------------------
reg uart_rxd1;
reg uart_rxd2;
always @(posedge sys_clk) begin
uart_rxd1 <= uart_rxd;
uart_rxd2 <= uart_rxd1;
end
//-----------------------------------------------------------------
// UART RX Logic
//-----------------------------------------------------------------
reg rx_busy;
reg [3:0] rx_count16;
reg [3:0] rx_bitcount;
reg [7:0] rxd_reg;
always @(posedge sys_clk) begin
if(sys_rst) begin
rx_done <= 1'b0;
rx_busy <= 1'b0;
rx_count16 <= 4'd0;
rx_bitcount <= 4'd0;
end else begin
rx_done <= 1'b0;
if(enable16) begin
if(~rx_busy) begin // look for start bit
if(~uart_rxd2) begin // start bit found
rx_busy <= 1'b1;
rx_count16 <= 4'd7;
rx_bitcount <= 4'd0;
end
end else begin
rx_count16 <= rx_count16 + 4'd1;
if(rx_count16 == 4'd0) begin // sample
rx_bitcount <= rx_bitcount + 4'd1;
if(rx_bitcount == 4'd0) begin // verify startbit
if(uart_rxd2)
rx_busy <= 1'b0;
end else if(rx_bitcount == 4'd9) begin
rx_busy <= 1'b0;
if(uart_rxd2) begin // stop bit ok
rx_data <= rxd_reg;
rx_done <= 1'b1;
end // ignore RX error
end else
rxd_reg <= {uart_rxd2, rxd_reg[7:1]};
end
end
end
end
end
//-----------------------------------------------------------------
// UART TX Logic
//-----------------------------------------------------------------
reg tx_busy;
reg [3:0] tx_bitcount;
reg [3:0] tx_count16;
reg [7:0] txd_reg;
always @(posedge sys_clk) begin
if(sys_rst) begin
tx_done <= 1'b0;
tx_busy <= 1'b0;
uart_txd <= 1'b1;
end else begin
tx_done <= 1'b0;
if(tx_wr) begin
txd_reg <= tx_data;
tx_bitcount <= 4'd0;
tx_count16 <= 4'd1;
tx_busy <= 1'b1;
uart_txd <= 1'b0;
`ifdef SIMULATION
$display("UART: %c", tx_data);
`endif
end else if(enable16 && tx_busy) begin
tx_count16 <= tx_count16 + 4'd1;
if(tx_count16 == 4'd0) begin
tx_bitcount <= tx_bitcount + 4'd1;
if(tx_bitcount == 4'd8) begin
uart_txd <= 1'b1;
end else if(tx_bitcount == 4'd9) begin
uart_txd <= 1'b1;
tx_busy <= 1'b0;
tx_done <= 1'b1;
end else begin
uart_txd <= txd_reg[0];
txd_reg <= {1'b0, txd_reg[7:1]};
end
end
end
end
end
endmodule

View File

@ -0,0 +1,23 @@
TEX=vgafb.tex
DVI=$(TEX:.tex=.dvi)
PS=$(TEX:.tex=.ps)
PDF=$(TEX:.tex=.pdf)
AUX=$(TEX:.tex=.aux)
LOG=$(TEX:.tex=.log)
all: $(PDF)
%.dvi: %.tex
latex $<
%.ps: %.dvi
dvips $<
%.pdf: %.ps
ps2pdf $<
clean:
rm -f $(DVI) $(PS) $(PDF) $(AUX) $(LOG)
.PHONY: clean

View File

@ -0,0 +1,74 @@
\documentclass[a4paper,11pt]{article}
\usepackage{fullpage}
\usepackage[latin1]{inputenc}
\usepackage[T1]{fontenc}
\usepackage[normalem]{ulem}
\usepackage[english]{babel}
\usepackage{listings,babel}
\lstset{breaklines=true,basicstyle=\ttfamily}
\usepackage{graphicx}
\usepackage{moreverb}
\usepackage{url}
\usepackage{amsmath}
\title{VGA framebuffer}
\author{S\'ebastien Bourdeauducq}
\date{December 2009}
\begin{document}
\setlength{\parindent}{0pt}
\setlength{\parskip}{5pt}
\maketitle{}
\section{Specifications}
The VGA framebuffer core enables a system-on-chip to support a VGA video output with the picture read from a memory framebuffer.
The core directly drives a 3-channel 8-bit digital to analog converter and the horizontal and vertical synchronization signals.
The framebuffer is read with a 4x64 FastMemoryLink (FML) master; and a CSR interface is implemented for configuring the video output.
\section{Registers}
\subsection{Control register, offset 0x00}
This register enables or disables the video output by setting or clearing the reset bit 0. At reset, the default value is 0x1.
\subsection{Horizontal video parameters, offsets 0x04, 0x08, 0x0c and 0x10}
Those registers set respectively:
\begin{itemize}
\item the horizontal size of the active video area (the horizontal resolution)
\item the position of the beginning of the horizontal sync pulse in the scan line, in pixel clocks
\item the position of the end of the horizontal sync pulse in the scan line, in pixel clocks
\item the total length of the horizontal scan line minus one, in pixels
\end{itemize}
The default values are for the standard VGA resolution of 640x480 at 60Hz with a 25MHz pixel clock.
\subsection{Vertical video parameters, offsets 0x14, 0x18, 0x1c and 0x20}
Those registers set respectively:
\begin{itemize}
\item the vertical size of the active video area (the vertical resolution)
\item the position of the beginning of the vertical sync pulse. The unit is the horizontal scan line.
\item the position of the end of the vertical sync pulse. Same unit as above.
\item the total count of horizontal scan lines minus one. Same unit as above.
\end{itemize}
The default values are for the standard VGA resolution of 640x480 at 60Hz with a 25MHz pixel clock.
\subsection{DMA control registers, offsets 0x24, 0x28 and 0x2c}
The register 0x24 defines the base address of the framebuffer. That framebuffer is basic progressive scan buffer using the RGB565 pixel format.
When register 0x24 is written, the framebuffer address is not updated immediately. Instead, the VGA core waits for the end of the vertical active video area and only starts fetching data from the new framebuffer at the beginning of the next frame. This enables the use of multiple framebuffers without any tearing or flickering artifacts. The address from which the core is currently reading data is available in register 0x28.
When registers 0x24 and 0x28 have different values, a framebuffer address change is pending. When they have the same values, the frame being displayed is the latest that was asked for.
The framebuffer must be aligned to the start of a FML burst ($\frac{4 \cdot 64}{8}$ bytes).
Register 0x2c defines the number of FML bursts required to fill a complete screen. This is typically set to:
\[
\frac{\text{horizontal resolution} \cdot \text{vertical resolution} \cdot 16}{4 \cdot 64}
\]
The screen resolution must be set so that this number is integer. This is the case with common VGA resolutions.
\section{Connections}
The pixel clock is not generated internally and must be fed to the core using the \verb!vga_clk! port. No relationship is expected with the system clock (the two domains are entirely independent). That pixel clock should also be fed to the synchronous DAC.
The other ports should be self-explanatory.
\section*{Copyright notice}
Copyright \copyright 2007-2009 S\'ebastien Bourdeauducq. \\
Permission is granted to copy, distribute and/or modify this document under the terms of the GNU Free Documentation License, Version 1.3; with no Invariant Sections, no Front-Cover Texts, and no Back-Cover Texts. A copy of the license is included in the LICENSE.FDL file at the root of the Milkymist source distribution.
\end{document}

View File

@ -0,0 +1,229 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009, 2010 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module vgafb #(
parameter csr_addr = 4'h0,
parameter fml_depth = 26
) (
input sys_clk,
input sys_rst,
/* Configuration interface */
input [13:0] csr_a,
input csr_we,
input [31:0] csr_di,
output [31:0] csr_do,
/* Framebuffer FML 4x64 interface */
output [fml_depth-1:0] fml_adr,
output fml_stb,
input fml_ack,
input [63:0] fml_di,
/* VGA pixel clock */
input vga_clk,
/* VGA signal pads */
output vga_psave_n,
output reg vga_hsync_n,
output reg vga_vsync_n,
output vga_sync_n,
output vga_blank_n,
output reg [7:0] vga_r,
output reg [7:0] vga_g,
output reg [7:0] vga_b,
output [1:0] vga_clk_sel
);
/*
* Control interface
*/
wire vga_rst;
wire [10:0] hres;
wire [10:0] hsync_start;
wire [10:0] hsync_end;
wire [10:0] hscan;
wire [10:0] vres;
wire [10:0] vsync_start;
wire [10:0] vsync_end;
wire [10:0] vscan;
wire [fml_depth-1:0] baseaddress;
wire baseaddress_ack;
wire [17:0] nbursts;
vgafb_ctlif #(
.csr_addr(csr_addr),
.fml_depth(fml_depth)
) ctlif (
.sys_clk(sys_clk),
.sys_rst(sys_rst),
.csr_a(csr_a),
.csr_we(csr_we),
.csr_di(csr_di),
.csr_do(csr_do),
.vga_rst(vga_rst),
.hres(hres),
.hsync_start(hsync_start),
.hsync_end(hsync_end),
.hscan(hscan),
.vres(vres),
.vsync_start(vsync_start),
.vsync_end(vsync_end),
.vscan(vscan),
.baseaddress(baseaddress),
.baseaddress_ack(baseaddress_ack),
.nbursts(nbursts),
.vga_clk_sel(vga_clk_sel)
);
/*
* Generate signal data
*/
reg hsync_n;
reg vsync_n;
wire pixel_valid;
wire [15:0] pixel_fb;
wire pixel_ack;
wire [15:0] pixel;
wire fifo_full;
reg hactive;
reg vactive;
wire active = hactive & vactive;
assign pixel = active ? pixel_fb : 16'h0000;
wire generate_en;
reg [10:0] hcounter;
reg [10:0] vcounter;
always @(posedge sys_clk) begin
if(vga_rst) begin
hcounter <= 10'd0;
vcounter <= 10'd0;
hactive <= 1'b0;
hsync_n <= 1'b1;
vactive <= 1'b0;
vsync_n <= 1'b1;
end else begin
if(generate_en) begin
hcounter <= hcounter + 10'd1;
if(hcounter == 10'd0) hactive <= 1'b1;
if(hcounter == hres) hactive <= 1'b0;
if(hcounter == hsync_start) hsync_n <= 1'b0;
if(hcounter == hsync_end) hsync_n <= 1'b1;
if(hcounter == hscan) begin
hcounter <= 10'd0;
if(vcounter == vscan)
vcounter <= 10'd0;
else
vcounter <= vcounter + 10'd1;
end
if(vcounter == 10'd0) vactive <= 1'b1;
if(vcounter == vres) vactive <= 1'b0;
if(vcounter == vsync_start) vsync_n <= 1'b0;
if(vcounter == vsync_end) vsync_n <= 1'b1;
end
end
end
assign generate_en = ~fifo_full & (~active | pixel_valid);
assign pixel_ack = ~fifo_full & active & pixel_valid;
vgafb_pixelfeed #(
.fml_depth(fml_depth)
) pixelfeed (
.sys_clk(sys_clk),
.sys_rst(sys_rst),
.vga_rst(vga_rst),
.nbursts(nbursts),
.baseaddress(baseaddress),
.baseaddress_ack(baseaddress_ack),
.fml_adr(fml_adr),
.fml_stb(fml_stb),
.fml_ack(fml_ack),
.fml_di(fml_di),
.pixel_valid(pixel_valid),
.pixel(pixel_fb),
.pixel_ack(pixel_ack)
);
/*
* System clock to VGA clock domain crossing is
* acheived by an asynchronous FIFO.
*
* Bits 0-15 are RGB565 pixel data
* Bit 16 is negated Horizontal Sync
* Bit 17 is negated Verical Sync
*/
wire [17:0] fifo_do;
vgafb_asfifo #(
.DATA_WIDTH(18),
.ADDRESS_WIDTH(6)
) fifo (
.Data_out(fifo_do),
.Empty_out(),
.ReadEn_in(1'b1),
.RClk(vga_clk),
.Data_in({vsync_n, hsync_n, pixel}),
.Full_out(fifo_full),
.WriteEn_in(generate_en),
.WClk(sys_clk),
.Clear_in(vga_rst)
);
/*
* Drive the VGA pads.
* RGB565 -> RGB888 color space conversion is also performed here
* by bit shifting and replicating the most significant bits of
* the input into the least significant bits of the output left
* undefined by the shifting.
*/
assign vga_sync_n = 1'b0; /* Sync-on-Green is not implemented */
assign vga_psave_n = 1'b1;
assign vga_blank_n = 1'b1;
always @(posedge vga_clk) begin
vga_vsync_n <= fifo_do[17];
vga_hsync_n <= fifo_do[16];
vga_r <= {fifo_do[15:11], fifo_do[15:13]};
vga_g <= {fifo_do[10:5], fifo_do[10:9]};
vga_b <= {fifo_do[4:0], fifo_do[4:2]};
end
endmodule

View File

@ -0,0 +1,116 @@
//==========================================
// Function : Asynchronous FIFO (w/ 2 asynchronous clocks).
// Coder : Alex Claros F.
// Date : 15/May/2005.
// Notes : This implementation is based on the article
// 'Asynchronous FIFO in Virtex-II FPGAs'
// writen by Peter Alfke. This TechXclusive
// article can be downloaded from the
// Xilinx website. It has some minor modifications.
//=========================================
`timescale 1ns / 1ps
module vgafb_asfifo
#(parameter DATA_WIDTH = 8,
ADDRESS_WIDTH = 4,
FIFO_DEPTH = (1 << ADDRESS_WIDTH))
//Reading port
(output wire [DATA_WIDTH-1:0] Data_out,
output reg Empty_out,
input wire ReadEn_in,
input wire RClk,
//Writing port.
input wire [DATA_WIDTH-1:0] Data_in,
output reg Full_out,
input wire WriteEn_in,
input wire WClk,
input wire Clear_in);
/////Internal connections & variables//////
reg [DATA_WIDTH-1:0] Mem [FIFO_DEPTH-1:0];
wire [ADDRESS_WIDTH-1:0] pNextWordToWrite, pNextWordToRead;
wire EqualAddresses;
wire NextWriteAddressEn, NextReadAddressEn;
wire Set_Status, Rst_Status;
reg Status;
wire PresetFull, PresetEmpty;
//////////////Code///////////////
//Data ports logic:
//(Uses a dual-port RAM).
//'Data_out' logic:
assign Data_out = Mem[pNextWordToRead];
// always @ (posedge RClk)
// if (!PresetEmpty)
// Data_out <= Mem[pNextWordToRead];
// if (ReadEn_in & !Empty_out)
//'Data_in' logic:
always @ (posedge WClk)
if (WriteEn_in & !Full_out)
Mem[pNextWordToWrite] <= Data_in;
//Fifo addresses support logic:
//'Next Addresses' enable logic:
assign NextWriteAddressEn = WriteEn_in & ~Full_out;
assign NextReadAddressEn = ReadEn_in & ~Empty_out;
//Addreses (Gray counters) logic:
vgafb_graycounter #(
.COUNTER_WIDTH( ADDRESS_WIDTH )
) GrayCounter_pWr (
.GrayCount_out(pNextWordToWrite),
.Enable_in(NextWriteAddressEn),
.Clear_in(Clear_in),
.Clk(WClk)
);
vgafb_graycounter #(
.COUNTER_WIDTH( ADDRESS_WIDTH )
) GrayCounter_pRd (
.GrayCount_out(pNextWordToRead),
.Enable_in(NextReadAddressEn),
.Clear_in(Clear_in),
.Clk(RClk)
);
//'EqualAddresses' logic:
assign EqualAddresses = (pNextWordToWrite == pNextWordToRead);
//'Quadrant selectors' logic:
assign Set_Status = (pNextWordToWrite[ADDRESS_WIDTH-2] ~^ pNextWordToRead[ADDRESS_WIDTH-1]) &
(pNextWordToWrite[ADDRESS_WIDTH-1] ^ pNextWordToRead[ADDRESS_WIDTH-2]);
assign Rst_Status = (pNextWordToWrite[ADDRESS_WIDTH-2] ^ pNextWordToRead[ADDRESS_WIDTH-1]) &
(pNextWordToWrite[ADDRESS_WIDTH-1] ~^ pNextWordToRead[ADDRESS_WIDTH-2]);
//'Status' latch logic:
always @ (Set_Status, Rst_Status, Clear_in) //D Latch w/ Asynchronous Clear & Preset.
if (Rst_Status | Clear_in)
Status = 0; //Going 'Empty'.
else if (Set_Status)
Status = 1; //Going 'Full'.
//'Full_out' logic for the writing port:
assign PresetFull = Status & EqualAddresses; //'Full' Fifo.
always @ (posedge WClk, posedge PresetFull) //D Flip-Flop w/ Asynchronous Preset.
if (PresetFull)
Full_out <= 1;
else
Full_out <= 0;
//'Empty_out' logic for the reading port:
assign PresetEmpty = ~Status & EqualAddresses; //'Empty' Fifo.
always @ (posedge RClk, posedge PresetEmpty) //D Flip-Flop w/ Asynchronous Preset.
if (PresetEmpty)
Empty_out <= 1;
else
Empty_out <= 0;
endmodule

View File

@ -0,0 +1,93 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009, 2010 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/* FIXME: this module does not work. Find out why. */
module vgafb_asfifo #(
/* NB: those are fixed in this implementation */
parameter DATA_WIDTH = 18,
parameter ADDRESS_WIDTH = 11
) (
/* Reading port */
output [17:0] Data_out,
output Empty_out,
input ReadEn_in,
input RClk,
/* Writing port */
input [17:0] Data_in,
output Full_out,
input WriteEn_in,
input WClk,
input Clear_in
);
wire full;
wire empty;
FIFO16 #(
.DATA_WIDTH(9),
.FIRST_WORD_FALL_THROUGH("TRUE")
) fifo_lo (
.ALMOSTEMPTY(),
.ALMOSTFULL(),
.DO(Data_out[7:0]),
.DOP(Data_out[8]),
.EMPTY(empty),
.FULL(full),
.RDCOUNT(),
.RDERR(),
.WRCOUNT(),
.WRERR(),
.DI(Data_in[7:0]),
.DIP(Data_in[8]),
.RDCLK(RClk),
.RDEN(ReadEn_in & ~empty & ~Clear_in),
.RST(Clear_in),
.WRCLK(WClk),
.WREN(WriteEn_in & ~full & ~Clear_in)
);
assign Empty_out = empty;
assign Full_out = full;
FIFO16 #(
.DATA_WIDTH(9),
.FIRST_WORD_FALL_THROUGH("TRUE")
) fifo_hi (
.ALMOSTEMPTY(),
.ALMOSTFULL(),
.DO(Data_out[16:9]),
.DOP(Data_out[17]),
.EMPTY(),
.FULL(),
.RDCOUNT(),
.RDERR(),
.WRCOUNT(),
.WRERR(),
.DI(Data_in[16:9]),
.DIP(Data_in[17]),
.RDCLK(RClk),
.RDEN(ReadEn_in & ~empty & ~Clear_in),
.RST(Clear_in),
.WRCLK(WClk),
.WREN(WriteEn_in & ~full & ~Clear_in)
);
endmodule

View File

@ -0,0 +1,121 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module vgafb_ctlif #(
parameter csr_addr = 4'h0,
parameter fml_depth = 26
) (
input sys_clk,
input sys_rst,
input [13:0] csr_a,
input csr_we,
input [31:0] csr_di,
output reg [31:0] csr_do,
output reg vga_rst,
output reg [10:0] hres,
output reg [10:0] hsync_start,
output reg [10:0] hsync_end,
output reg [10:0] hscan,
output reg [10:0] vres,
output reg [10:0] vsync_start,
output reg [10:0] vsync_end,
output reg [10:0] vscan,
output reg [fml_depth-1:0] baseaddress,
input baseaddress_ack,
output reg [17:0] nbursts,
output reg [1:0] vga_clk_sel
);
reg [fml_depth-1:0] baseaddress_act;
always @(posedge sys_clk) begin
if(sys_rst)
baseaddress_act <= {fml_depth{1'b0}};
else if(baseaddress_ack)
baseaddress_act <= baseaddress;
end
wire csr_selected = csr_a[13:10] == csr_addr;
always @(posedge sys_clk) begin
if(sys_rst) begin
csr_do <= 32'd0;
vga_rst <= 1'b1;
hres <= 10'd640;
hsync_start <= 10'd656;
hsync_end <= 10'd752;
hscan <= 10'd799;
vres <= 10'd480;
vsync_start <= 10'd491;
vsync_end <= 10'd493;
vscan <= 10'd523;
baseaddress <= {fml_depth{1'b0}};
nbursts <= 18'd19200;
vga_clk_sel <= 2'd00;
end else begin
csr_do <= 32'd0;
if(csr_selected) begin
if(csr_we) begin
case(csr_a[3:0])
4'd0: vga_rst <= csr_di[0];
4'd1: hres <= csr_di[10:0];
4'd2: hsync_start <= csr_di[10:0];
4'd3: hsync_end <= csr_di[10:0];
4'd4: hscan <= csr_di[10:0];
4'd5: vres <= csr_di[10:0];
4'd6: vsync_start <= csr_di[10:0];
4'd7: vsync_end <= csr_di[10:0];
4'd8: vscan <= csr_di[10:0];
4'd9: baseaddress <= csr_di[fml_depth-1:0];
// 10: baseaddress_act is read-only for Wishbone
4'd11: nbursts <= csr_di[17:0];
4'd12: vga_clk_sel <= csr_di[1:0];
endcase
end
case(csr_a[3:0])
4'd0: csr_do <= vga_rst;
4'd1: csr_do <= hres;
4'd2: csr_do <= hsync_start;
4'd3: csr_do <= hsync_end;
4'd4: csr_do <= hscan;
4'd5: csr_do <= vres;
4'd6: csr_do <= vsync_start;
4'd7: csr_do <= vsync_end;
4'd8: csr_do <= vscan;
4'd9: csr_do <= baseaddress;
4'd10: csr_do <= baseaddress_act;
4'd11: csr_do <= nbursts;
4'd12: csr_do <= vga_clk_sel;
endcase
end
end
end
endmodule

View File

@ -0,0 +1,75 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module vgafb_fifo64to16(
input sys_clk,
input vga_rst,
input stb,
input [63:0] di,
output do_valid,
output reg [15:0] do,
input next /* should only be asserted when do_valid = 1 */
);
/*
* FIFO can hold 4 64-bit words
* that is 16 16-bit words.
*/
reg [63:0] storage[0:3];
reg [1:0] produce; /* in 64-bit words */
reg [3:0] consume; /* in 16-bit words */
/*
* 16-bit words stored in the FIFO, 0-16 (17 possible values)
*/
reg [4:0] level;
wire [63:0] do64;
assign do64 = storage[consume[3:2]];
always @(*) begin
case(consume[1:0])
2'd0: do <= do64[63:48];
2'd1: do <= do64[47:32];
2'd2: do <= do64[31:16];
2'd3: do <= do64[15:0];
endcase
end
always @(posedge sys_clk) begin
if(vga_rst) begin
produce = 2'd0;
consume = 4'd0;
level = 5'd0;
end else begin
if(stb) begin
storage[produce] = di;
produce = produce + 2'd1;
level = level + 5'd4;
end
if(next) begin /* next should only be asserted when do_valid = 1 */
consume = consume + 4'd1;
level = level - 5'd1;
end
end
end
assign do_valid = ~(level == 5'd0);
endmodule

View File

@ -0,0 +1,35 @@
//==========================================
// Function : Code Gray counter.
// Coder : Alex Claros F.
// Date : 15/May/2005.
//=======================================
`timescale 1ns/1ps
module vgafb_graycounter
#(parameter COUNTER_WIDTH = 2)
(output reg [COUNTER_WIDTH-1:0] GrayCount_out, //'Gray' code count output.
input wire Enable_in, //Count enable.
input wire Clear_in, //Count reset.
input wire Clk);
/////////Internal connections & variables///////
reg [COUNTER_WIDTH-1:0] BinaryCount;
/////////Code///////////////////////
always @ (posedge Clk)
if (Clear_in) begin
BinaryCount <= {COUNTER_WIDTH{1'b 0}} + 1; //Gray count begins @ '1' with
GrayCount_out <= {COUNTER_WIDTH{1'b 0}}; // first 'Enable_in'.
end
else if (Enable_in) begin
BinaryCount <= BinaryCount + 1;
GrayCount_out <= {BinaryCount[COUNTER_WIDTH-1],
BinaryCount[COUNTER_WIDTH-2:0] ^ BinaryCount[COUNTER_WIDTH-1:1]};
end
endmodule

View File

@ -0,0 +1,182 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module vgafb_pixelfeed #(
parameter fml_depth = 26
) (
input sys_clk,
/* We must take into account both resets :
* VGA reset should not interrupt a pending FML request
* but system reset should.
*/
input sys_rst,
input vga_rst,
input [17:0] nbursts,
input [fml_depth-1:0] baseaddress,
output baseaddress_ack,
output reg [fml_depth-1:0] fml_adr,
output reg fml_stb,
input fml_ack,
input [63:0] fml_di,
output pixel_valid,
output [15:0] pixel,
input pixel_ack
);
/* FIFO that stores the 64-bit bursts and slices it in 16-bit words */
reg fifo_stb;
wire fifo_valid;
vgafb_fifo64to16 fifo64to16(
.sys_clk(sys_clk),
.vga_rst(vga_rst),
.stb(fifo_stb),
.di(fml_di),
.do_valid(fifo_valid),
.do(pixel),
.next(pixel_ack)
);
assign pixel_valid = fifo_valid;
/* BURST COUNTER */
reg sof;
wire counter_en;
reg [17:0] bcounter;
always @(posedge sys_clk) begin
if(vga_rst) begin
bcounter <= 18'd1;
sof <= 1'b1;
end else begin
if(counter_en) begin
if(bcounter == nbursts) begin
bcounter <= 18'd1;
sof <= 1'b1;
end else begin
bcounter <= bcounter + 18'd1;
sof <= 1'b0;
end
end
end
end
/* FML ADDRESS GENERATOR */
wire next_address;
assign baseaddress_ack = sof & next_address;
always @(posedge sys_clk) begin
if(sys_rst) begin
fml_adr <= {fml_depth{1'b0}};
end else begin
if(next_address) begin
if(sof)
fml_adr <= baseaddress;
else
fml_adr <= fml_adr + {{fml_depth-6{1'b0}}, 6'd32};
end
end
end
/* CONTROLLER */
reg [2:0] state;
reg [2:0] next_state;
parameter IDLE = 3'd0;
parameter WAIT = 3'd1;
parameter FETCH2 = 3'd2;
parameter FETCH3 = 3'd3;
parameter FETCH4 = 3'd4;
always @(posedge sys_clk) begin
if(sys_rst)
state <= IDLE;
else
state <= next_state;
end
/*
* Do not put spurious data into the FIFO if the VGA reset
* is asserted and released during the FML access. Getting
* the FIFO out of sync would result in distorted pictures
* we really want to avoid.
*/
reg ignore;
reg ignore_clear;
always @(posedge sys_clk) begin
if(vga_rst)
ignore <= 1'b1;
else if(ignore_clear)
ignore <= 1'b0;
end
reg next_burst;
assign counter_en = next_burst;
assign next_address = next_burst;
always @(*) begin
next_state = state;
fifo_stb = 1'b0;
next_burst = 1'b0;
fml_stb = 1'b0;
ignore_clear = 1'b0;
case(state)
IDLE: begin
if(~fifo_valid & ~vga_rst) begin
/* We're in need of pixels ! */
next_burst = 1'b1;
ignore_clear = 1'b1;
next_state = WAIT;
end
end
WAIT: begin
fml_stb = 1'b1;
if(fml_ack) begin
if(~ignore) fifo_stb = 1'b1;
next_state = FETCH2;
end
end
FETCH2: begin
if(~ignore) fifo_stb = 1'b1;
next_state = FETCH3;
end
FETCH3: begin
if(~ignore) fifo_stb = 1'b1;
next_state = FETCH4;
end
FETCH4: begin
if(~ignore) fifo_stb = 1'b1;
next_state = IDLE;
end
endcase
end
endmodule

View File

@ -0,0 +1,11 @@
SOURCES_PIXELFEED=tb_pixelfeed.v ../rtl/vgafb_pixelfeed.v ../rtl/vgafb_fifo64to16.v
all: pixelfeed
pixelfeed: $(SOURCES_PIXELFEED)
cver $(SOURCES_PIXELFEED)
clean:
rm -f verilog.log
.PHONY: clean pixelfeed

View File

@ -0,0 +1,61 @@
/*
* Milkymist VJ SoC
* Copyright (C) 2007, 2008, 2009 Sebastien Bourdeauducq
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, version 3 of the License.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
module tb_pixelfeed();
reg sys_clk;
initial sys_clk = 1'b0;
always #5 sys_clk = ~sys_clk;
reg sys_rst;
reg vga_rst;
wire pixel_valid;
wire fml_stb;
wire [25:0] fml_adr;
initial begin
sys_rst = 1'b1;
vga_rst = 1'b1;
#20 sys_rst = 1'b0;
#20 vga_rst = 1'b0;
end
vgafb_pixelfeed dut(
.sys_clk(sys_clk),
.sys_rst(sys_rst),
.vga_rst(vga_rst),
.nbursts(18'd100),
.baseaddress(26'd1024),
.baseaddress_ack(),
.fml_adr(fml_adr),
.fml_stb(fml_stb),
.fml_ack(fml_stb),
.fml_di(64'hcafebabedeadbeef),
.pixel_valid(pixel_valid),
.pixel(),
.pixel_ack(pixel_valid)
);
always @(posedge sys_clk) $display("%x", fml_adr);
initial #600 $finish;
endmodule

View File

@ -51,8 +51,8 @@ initial begin
$dumpvars(-1, dut);
// reset
#0 rst <= 1;
#80 rst <= 0;
#0 rst <= 0;
#80 rst <= 1;
#(tck*10000) $finish;
end

Binary file not shown.

View File

@ -425,6 +425,7 @@ package mlite_pack is
nwe : in std_logic;
noe : in std_logic;
ncs : in std_logic;
irq_pin : in std_logic;
led : out std_logic);
end component; --plasma

View File

@ -1,8 +1,9 @@
NET clk LOC = "P38";
NET clk_in LOC = "P38";
NET rst_in LOC = "P30";
NET uart_write LOC = "P67";
NET uart_read LOC = "P68";
NET led LOC = "P44";
NET led LOC = "P44";
NET irq_pin LOC = "P71";
#ADDRESS BUS
NET "addr<12>" LOC = "P90";

View File

@ -41,6 +41,7 @@ entity plasma is
nwe : in std_logic;
noe : in std_logic;
ncs : in std_logic;
irq_pin : in std_logic;
led : out std_logic
);
end; --entity plasma
@ -147,6 +148,9 @@ begin
variable bus_dec : std_logic_vector(6 downto 0);
begin
bus_dec := cpu_address(30 downto 28) & cpu_address(7 downto 4);
-- if cpu_address(30 downto 28) = "000" then
-- cpu_data_r <= ram_data_r;
-- else
case bus_dec is
when "000----" => cpu_data_r <= ram_data_r;
when "0100000" => cpu_data_r <= ZERO(31 downto 8) & data_read_uart;
@ -158,6 +162,7 @@ begin
when "0100110" => cpu_data_r <= ZERO;
when others => cpu_data_r <= ZERO;
end case;
-- end if;
end process;
--%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

View File

@ -28,8 +28,8 @@ architecture logic of tbench is
signal nwe : std_logic;
signal noe : std_logic;
signal ncs : std_logic;
signal irq_pin : std_logic;
signal led : std_logic;
signal TxD : std_logic;
signal RxD : std_logic;
@ -51,6 +51,7 @@ begin --architecture
nwe => nwe,
noe => noe,
ncs => ncs,
irq_pin => irq_pin,
led => led
);

176
plasma/logic/ram.vhd Normal file
View File

@ -0,0 +1,176 @@
---------------------------------------------------------------------
-- TITLE: Random Access Memory
-- AUTHOR: Steve Rhoads (rhoadss@yahoo.com)
-- DATE CREATED: 4/21/01
-- FILENAME: ram.vhd
-- PROJECT: Plasma CPU core
-- COPYRIGHT: Software placed into the public domain by the author.
-- Software 'as is' without warranty. Author liable for nothing.
-- DESCRIPTION:
-- Implements the RAM, reads the executable from either "code.txt",
-- or for Altera "code[0-3].hex".
-- Modified from "The Designer's Guide to VHDL" by Peter J. Ashenden
---------------------------------------------------------------------
library ieee;
use ieee.std_logic_1164.all;
use ieee.std_logic_misc.all;
use ieee.std_logic_arith.all;
use ieee.std_logic_unsigned.all;
use ieee.std_logic_textio.all;
use std.textio.all;
use work.mlite_pack.all;
entity ram is
generic(memory_type : string := "DEFAULT");
port(clk : in std_logic;
enable : in std_logic;
write_byte_enable : in std_logic_vector(3 downto 0);
address : in std_logic_vector(31 downto 2);
data_write : in std_logic_vector(31 downto 0);
data_read : out std_logic_vector(31 downto 0));
end; --entity ram
architecture logic of ram is
constant ADDRESS_WIDTH : natural := 13;
begin
generic_ram:
if memory_type /= "ALTERA_LPM" generate
begin
--Simulate a synchronous RAM
ram_proc: process(clk, enable, write_byte_enable,
address, data_write) --mem_write, mem_sel
variable mem_size : natural := 2 ** ADDRESS_WIDTH;
variable data : std_logic_vector(31 downto 0);
subtype word is std_logic_vector(data_write'length-1 downto 0);
type storage_array is
array(natural range 0 to mem_size/4 - 1) of word;
variable storage : storage_array;
variable index : natural := 0;
file load_file : text open read_mode is "code.txt";
variable hex_file_line : line;
begin
--Load in the ram executable image
if index = 0 then
while not endfile(load_file) loop
--The following two lines had to be commented out for synthesis
readline(load_file, hex_file_line);
hread(hex_file_line, data);
storage(index) := data;
index := index + 1;
end loop;
end if;
if rising_edge(clk) then
index := conv_integer(address(ADDRESS_WIDTH-1 downto 2));
data := storage(index);
if enable = '1' then
if write_byte_enable(0) = '1' then
data(7 downto 0) := data_write(7 downto 0);
end if;
if write_byte_enable(1) = '1' then
data(15 downto 8) := data_write(15 downto 8);
end if;
if write_byte_enable(2) = '1' then
data(23 downto 16) := data_write(23 downto 16);
end if;
if write_byte_enable(3) = '1' then
data(31 downto 24) := data_write(31 downto 24);
end if;
end if;
if write_byte_enable /= "0000" then
storage(index) := data;
end if;
end if;
data_read <= data;
end process;
end generate; --generic_ram
altera_ram:
if memory_type = "ALTERA_LPM" generate
signal byte_we : std_logic_vector(3 downto 0);
begin
byte_we <= write_byte_enable when enable = '1' else "0000";
lpm_ram_io_component0 : lpm_ram_dq
GENERIC MAP (
intended_device_family => "UNUSED",
lpm_width => 8,
lpm_widthad => ADDRESS_WIDTH-2,
lpm_indata => "REGISTERED",
lpm_address_control => "REGISTERED",
lpm_outdata => "UNREGISTERED",
lpm_file => "code0.hex",
use_eab => "ON",
lpm_type => "LPM_RAM_DQ")
PORT MAP (
data => data_write(31 downto 24),
address => address(ADDRESS_WIDTH-1 downto 2),
inclock => clk,
we => byte_we(3),
q => data_read(31 downto 24));
lpm_ram_io_component1 : lpm_ram_dq
GENERIC MAP (
intended_device_family => "UNUSED",
lpm_width => 8,
lpm_widthad => ADDRESS_WIDTH-2,
lpm_indata => "REGISTERED",
lpm_address_control => "REGISTERED",
lpm_outdata => "UNREGISTERED",
lpm_file => "code1.hex",
use_eab => "ON",
lpm_type => "LPM_RAM_DQ")
PORT MAP (
data => data_write(23 downto 16),
address => address(ADDRESS_WIDTH-1 downto 2),
inclock => clk,
we => byte_we(2),
q => data_read(23 downto 16));
lpm_ram_io_component2 : lpm_ram_dq
GENERIC MAP (
intended_device_family => "UNUSED",
lpm_width => 8,
lpm_widthad => ADDRESS_WIDTH-2,
lpm_indata => "REGISTERED",
lpm_address_control => "REGISTERED",
lpm_outdata => "UNREGISTERED",
lpm_file => "code2.hex",
use_eab => "ON",
lpm_type => "LPM_RAM_DQ")
PORT MAP (
data => data_write(15 downto 8),
address => address(ADDRESS_WIDTH-1 downto 2),
inclock => clk,
we => byte_we(1),
q => data_read(15 downto 8));
lpm_ram_io_component3 : lpm_ram_dq
GENERIC MAP (
intended_device_family => "UNUSED",
lpm_width => 8,
lpm_widthad => ADDRESS_WIDTH-2,
lpm_indata => "REGISTERED",
lpm_address_control => "REGISTERED",
lpm_outdata => "UNREGISTERED",
lpm_file => "code3.hex",
use_eab => "ON",
lpm_type => "LPM_RAM_DQ")
PORT MAP (
data => data_write(7 downto 0),
address => address(ADDRESS_WIDTH-1 downto 2),
inclock => clk,
we => byte_we(0),
q => data_read(7 downto 0));
end generate; --altera_ram
--For XILINX see ram_xilinx.vhd
end; --architecture logic

View File

@ -45,27 +45,27 @@ INIT_00 => X"afafafafafafafafafafafafafafafaf2308000c241400ac273c243c243c273c",
INIT_01 => X"8f8f8f8f8f8f8f8f8f8f8f8f8f8f8f8f8f230c008c8c3caf00af00af2340afaf",
INIT_02 => X"acacacac0003373cac038cac8cac8cac8c243c40034040033423038f038f8f8f",
INIT_03 => X"000300ac0300000034038c8c8c8c8c8c8c8c8c8c8c8c3403acacacacacacacac",
INIT_04 => X"3c34ac343c34a42434a42434a42434a02434a02434a02434a02434a024343c27",
INIT_05 => X"8cac343caf008c34a730009434a330009034af008ca730009434a3300090ac34",
INIT_06 => X"82240c00142400100080afafaf270003ac3c1030008c343c0008af008c34af00",
INIT_07 => X"26240c2608240c00102c3002242400afafafaf2727038f8f8f0000140082260c",
INIT_08 => X"2703008f8c3c10000caf2730038c343c2703008f240caf2727038f8f8f8f0216",
INIT_09 => X"000000000000000000000000000000000024038c001424ac00008c243c3c243c",
INIT_0A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0C => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0D => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0E => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0F => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_10 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_11 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_12 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_13 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_14 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_15 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_16 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_17 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_18 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_04 => X"1c24001030008c24ac24ac9424003c00180003241c24a4248c0018ac2400003c",
INIT_05 => X"a00024241028302400a03c24243c3c0003001030008cacac242400003c000300",
INIT_06 => X"100010000c00102a0200260c24af08af2424240000afafafafaf270103001424",
INIT_07 => X"240c001a001427038f8f8f8f8f8f8f02240c240c000824102c24142c24142e24",
INIT_08 => X"008c34ac3c3c24240c3c240c3caf0cafafafafafafafafaf270008260c24240c",
INIT_09 => X"3c240c3c240c3c240c3c3c3c3c3c3c003c3c0c003c240c3c3c1430248c3c1030",
INIT_0A => X"0000142c2400000c240c3c270c260c260c260c260c240c3c240c3c240c3c240c",
INIT_0B => X"000c000c00000c240c3c3c08240c3c000c000c8e0000008c0024003c3c102c26",
INIT_0C => X"0200000010000c240c3c3c080002a208000c000c00000c240c3c0008923c08ae",
INIT_0D => X"000010000c240c3c3c080216a002260c00000010000c240c3c3c080216260c90",
INIT_0E => X"260c8c02240c3c00000010000c240c3c3c08240c000c000c0014002490020000",
INIT_0F => X"120008a23c243c3c08240c3c021402240c000c260c8c021032021002240c000c",
INIT_10 => X"3c083c0c003c000c0014343c000c240c3c3c0800003c0016260c262610000c3c",
INIT_11 => X"008c343c3c08240c000c000c2608240c3c000c020c240c3c00000c240c3c020c",
INIT_12 => X"82000c2682000c241400100082260c00240800100080afafaf270003ac001030",
INIT_13 => X"038f8f8f8f0216260c2424142c3002242400afafafaf272703008f8f8f001400",
INIT_14 => X"038c0014ac00248c3c24243c3c2703008f8c3c10000caf2730038c343c240827",
INIT_15 => X"6531006e706e724f303030206e6569612020740a00616d20423a20616f430a24",
INIT_16 => X"617965613673647475350a62697965340079617965330a7769796532006f6179",
INIT_17 => X"0a3d6541206820720a3e00616f446f42316f4600753900736838006979656137",
INIT_18 => X"00000000000000000000000000000000000037336820660a0d786e6e0a786e75",
INIT_19 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1B => X"0000000000000000000000000000000000000000000000000000000000000000",
@ -122,28 +122,28 @@ INIT_00 => X"b8afaeadacabaaa9a8a7a6a5a4a3a2a1bd000000a560a4a0bd1d8404a5059c1c",
INIT_01 => X"b9b8afaeadacabaaa9a8a7a6a5a4a3a2a1a50086c6c406bb00bb00ba5a1abfb9",
INIT_02 => X"9392919000405a1a06e0a606a606a606a6a50584e0029b401bbd60bb60bbbabf",
INIT_03 => X"00e000c4e0000085a2e09f9d9c9e979695949392919002e09f9d9c9e97969594",
INIT_04 => X"026482420264820264820264820264a2026582026482026482026482026403bd",
INIT_05 => X"62624202a2004262a242004262a242004262a20082a242004262a24200a28242",
INIT_06 => X"04040000511180400082b0b1bfbd00e044024042006243020000a2006263a200",
INIT_07 => X"108400100084000040824412111080b0b1b2bfbdbde0b0b1bf00004000021000",
INIT_08 => X"bde000bf4202400000bfbd42e0424202bde000bf0400bfbdbde0b0b1b2bf1211",
INIT_09 => X"000000000000000000040000802400800042e0a2006463404500624402054302",
INIT_0A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0C => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0D => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0E => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0F => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_10 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_11 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_12 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_13 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_14 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_15 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_16 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_17 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_18 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_19 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_04 => X"c0c60040420062636284658205620205c000e084c0a582c6a200c0a202a20502",
INIT_05 => X"c2e5070740a285634040036642020300e000404200828283020382040200e000",
INIT_06 => X"54405300000040220312310090b000bf1514130000b1b2b3b4b5bd00e004c3c6",
INIT_07 => X"040000208095bde0b0b1b2b3b4b5bf4004000400000090404282404282400250",
INIT_08 => X"00434283020403840004840004b000b1b2b3b4b5b6b7bebfbd12003100040400",
INIT_09 => X"024400024400024400021e171615144002060000048400041543420382146063",
INIT_0A => X"0000404242400000440002c400e400c400a40084004400024400024400024400",
INIT_0B => X"4000400040000044000202004400024000000044008000444383030402406203",
INIT_0C => X"4200004040000044000202000040500040004000400000440002000044020050",
INIT_0D => X"0040400000440002020000136251100000004040000044000202000011100044",
INIT_0E => X"300044504400020000404000004400020200040040000000a0a683a543420000",
INIT_0F => X"1100005013111202004400020060130400400030004450400200601304004000",
INIT_10 => X"0200060000040000004363030000440002020000400240535200101040000002",
INIT_11 => X"0062a30502000400400000000300440002400040004400024000004400020000",
INIT_12 => X"02400010020000045100400002100040110080400082b1bfb0bd00e0a4004042",
INIT_13 => X"e0b0b1b2bf12111000646440624312111080bfb0b1b2bdbde000b0b1bf004000",
INIT_14 => X"e0a20083404584820563440302bde000bf6203400000bfbd42e06263030400bd",
INIT_15 => X"6d2e007374752074303078616b206d7262666957007320666f0a006474205342",
INIT_16 => X"64206d772e73646f6d2e007974206d2e007464206d2e006f74206d2e00726420",
INIT_17 => X"56207364006569654120007320526d2032702e006d2e0075652e0074206d772e",
INIT_18 => X"0000000000000000000000000000000000003834207769430a3e2074433e2065",
INIT_19 => X"0000000000000000000000000000000000000004000080240080000000000000",
INIT_1A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1C => X"0000000000000000000000000000000000000000000000000000000000000000",
@ -195,32 +195,32 @@ INIT_3F => X"0000000000000000000000000000000000000000000000000000000000000000")
RAMB16_S9_inst2 : RAMB16_S9
generic map (
INIT_00 => X"00000000000000000000000000000000ff00000000ff18000600060004008400",
INIT_01 => X"000000000000000000000000000000000000012000002000d800d800ff700000",
INIT_00 => X"00000000000000000000000000000000ff00000100ff18000e000e000c008c00",
INIT_01 => X"000000000000000000000000000000000000022000002000d800d800ff700000",
INIT_02 => X"0000000000000010000000000000000000010060006060000000000000000000",
INIT_03 => X"0000000000201000000000000000000000000000000000000000000000000000",
INIT_04 => X"31030030300300220200210200200200000400000400000400000400000420ff",
INIT_05 => X"000055550000000300ff000002000000000400000000ff000002000000000031",
INIT_06 => X"00000000000080000000000000ff10000020ff00000000200000000000000000",
INIT_07 => X"ff0000ff0100000000000010ff009000000000ff00000000001000ff00000000",
INIT_08 => X"000000000020ff000100ff000000002000000000000000ff00000000000010ff",
INIT_09 => X"000000000000000000200000002028000000000000ff00001000000400100400",
INIT_0A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0C => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0D => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0E => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0F => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_10 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_11 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_12 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_13 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_14 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_15 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_16 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_17 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_18 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_19 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_04 => X"ffff00ff00000000000000000018301800000000ff0000ff0000000000282830",
INIT_05 => X"001000000000000c4000000c0c0000000000ff00000000000000202030000000",
INIT_06 => X"002000000200000090190002ff00000000000088900000000000ff100021ffff",
INIT_07 => X"0002000080ff00000000000000000010000200020000ff0000ffff00ffff00ff",
INIT_08 => X"000000002030000a02000a02000002000000000000000000ff9100ff02000002",
INIT_09 => X"000a02000a02000a02000000000000f810000028100a02000000ff3c00000000",
INIT_0A => X"90000000ff8000020b02000b020b020b020b020b020b02000b02000b02000b02",
INIT_0B => X"200280002000000b020000010b0200200200000000000000100c100000ff00ff",
INIT_0C => X"10108088ff00000c0200000100f80001200280002000000b0200000100000100",
INIT_0D => X"28300000000c0200000188ff00180002888098ff00000c0200000110ff000200",
INIT_0E => X"000000100c02008880980000000c0200000100022002000010ff200000101020",
INIT_0F => X"0080020010271000010c020088ff180002200200000010ff0088001800022002",
INIT_10 => X"000100002810200000ff561200000c0200000100f81080ff0002ff00ff000210",
INIT_11 => X"000000200001000220022000ff010b0200200220000b02009000000b02002002",
INIT_12 => X"0020020000000200ff00000000000220000280000000000000ff00000010ff00",
INIT_13 => X"000000000010ffff02000000000010ff009000000000ff00001000000000ff00",
INIT_14 => X"000000ff00100000100c0c0000000000000020ff000200ff0000000020000200",
INIT_15 => X"6f20003a69204d680a303174656c6179696f6e61006866726f0000656c624100",
INIT_16 => X"0a726f20200a72207020007465776f20006520726f20007265776f2000642072",
INIT_17 => X"6100736400786e736400006866202066387920007020006d63200065776f2020",
INIT_18 => X"0404040404070404070606060606060505003e353169726f002068206f206820",
INIT_19 => X"0000000000000000000000000000000000000020000000202800000804040404",
INIT_1A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1C => X"0000000000000000000000000000000000000000000000000000000000000000",
@ -272,32 +272,32 @@ INIT_3F => X"0000000000000000000000000000000000000000000000000000000000000000")
RAMB16_S9_inst3 : RAMB16_S9
generic map (
INIT_00 => X"4c4844403c3834302c2824201c181410980e008004fd2a00c800e000dc00d001",
INIT_01 => X"504c4844403c3834302c2824201c18141000082410200060125c1058fc005450",
INIT_00 => X"4c4844403c3834302c2824201c181410980e000704fd2a00b800d000b400b001",
INIT_01 => X"504c4844403c3834302c2824201c18141000812410200060125c1058fc005450",
INIT_02 => X"0c08040000083c0048080c440840043c006000000800000801681360115c5854",
INIT_03 => X"00080c000810121900082c2824201c1814100c08040000082c2824201c181410",
INIT_04 => X"31340030303000221400211200201000141400131300121200111100101000f8",
INIT_05 => X"000055550400003802ff00001800ff00001804000002ff00001600ff00000031",
INIT_06 => X"000dc800030a210d0000101418e021080000fc020000200000c6040000200400",
INIT_07 => X"fc57c8fc0030c800050a0f06fc1c211014181ce020081014182100f6000001c8",
INIT_08 => X"180800100000fd001010e801080020001808001049c810e820081014181c06f4",
INIT_09 => X"000000000000000000001010200000207084080000fa0400210000dc0000bc00",
INIT_0A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0C => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0D => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0E => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_0F => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_10 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_11 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_12 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_13 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_14 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_15 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_16 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_17 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_18 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_19 => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_04 => X"f4fe00fc80000004000200004021004011000802fb0400fe00000700ff214000",
INIT_05 => X"00213037020a0fbf210800c7c00000000800fc8000000000d020214000000800",
INIT_06 => X"0c210e00880012102100013cc910db28080d0a212114181c2024d0210802f7ff",
INIT_07 => X"083c000821d930081014181c202428210a3c0d3c00d4a9111a9fed1abff10ad0",
INIT_08 => X"000050000000ff984600844600109314181c2024282c3034c802d8ff3c08203c",
INIT_09 => X"00f84600e04600b0460000000000000900028021009c4600000cff1c00001001",
INIT_0A => X"2100c20ad0210088d84600b446a846984680466c465846004046002846001046",
INIT_0B => X"214621b12100c5fc46000037244600214600b10000080000213c800000d416cf",
INIT_0C => X"212121219a00c50c4600003700090036214621b12100c5fc4600006d00003700",
INIT_0D => X"21217600c50c4600003721fb002101882121218900c50c4600003721fb013c00",
INIT_0E => X"04b100211c46002121211e00c50c460000370a3c214600b121fb210100212121",
INIT_0F => X"0b21010010100000371c460021f42b203c214604b10021f00f210e2b203c2146",
INIT_10 => X"0037028f210021a3001f783400c5204600003700090021f30188ff01fb008300",
INIT_11 => X"0000200000370a3c214621b1cf61244600214621b1f046002100c5dc4600213c",
INIT_12 => X"00213c0100003c0df8000d0000013c210a5721160000141810e000080021fc02",
INIT_13 => X"081014181c06f8fc3c5730020a0f06fc1c211c101418e020082110141800f500",
INIT_14 => X"080000fb0021040000b4940000180800100000fd008310e80108002000493c20",
INIT_15 => X"724d000a6f4f656500303020646967206e726769000a6c6f740000726f6f4b84",
INIT_16 => X"0065726d52006561204a00652072724d000a6265724d00642072724d000a7765",
INIT_17 => X"6c002072003e20736400000a6c7444724b2043000a44000a6b43000a72726d52",
INIT_18 => X"d8d8d8d8d8e4d8d840e09c5848180cd8b000203632746d6e0000656975006569",
INIT_19 => X"0000000000000000000000000000000000000000101020000020703cd8d8d8d8",
INIT_1A => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1B => X"0000000000000000000000000000000000000000000000000000000000000000",
INIT_1C => X"0000000000000000000000000000000000000000000000000000000000000000",

119
plasma/logic/tbench.vhd Normal file
View File

@ -0,0 +1,119 @@
---------------------------------------------------------------------
-- TITLE: Test Bench
-- AUTHOR: Steve Rhoads (rhoadss@yahoo.com)
-- DATE CREATED: 4/21/01
-- FILENAME: tbench.vhd
-- PROJECT: Plasma CPU core
-- COPYRIGHT: Software placed into the public domain by the author.
-- Software 'as is' without warranty. Author liable for nothing.
-- DESCRIPTION:
-- This entity provides a test bench for testing the Plasma CPU core.
---------------------------------------------------------------------
library ieee;
use ieee.std_logic_1164.all;
use work.mlite_pack.all;
use ieee.std_logic_unsigned.all;
entity tbench is
end; --entity tbench
architecture logic of tbench is
constant memory_type : string :=
"TRI_PORT_X";
-- "DUAL_PORT_";
-- "ALTERA_LPM";
-- "XILINX_16X";
constant log_file : string :=
-- "UNUSED";
"output.txt";
signal clk : std_logic := '1';
signal reset : std_logic := '1';
signal interrupt : std_logic := '0';
signal mem_write : std_logic;
signal address : std_logic_vector(31 downto 2);
signal data_write : std_logic_vector(31 downto 0);
signal data_read : std_logic_vector(31 downto 0);
signal pause1 : std_logic := '0';
signal pause2 : std_logic := '0';
signal pause : std_logic;
signal no_ddr_start: std_logic;
signal no_ddr_stop : std_logic;
signal byte_we : std_logic_vector(3 downto 0);
signal uart_write : std_logic;
signal gpioA_in : std_logic_vector(31 downto 0) := (others => '0');
begin --architecture
--Uncomment the line below to test interrupts
interrupt <= '1' after 20 us when interrupt = '0' else '0' after 445 ns;
clk <= not clk after 50 ns;
reset <= '0' after 500 ns;
pause1 <= '1' after 700 ns when pause1 = '0' else '0' after 200 ns;
pause2 <= '1' after 300 ns when pause2 = '0' else '0' after 200 ns;
pause <= pause1 or pause2;
gpioA_in(20) <= not gpioA_in(20) after 200 ns; --E_RX_CLK
gpioA_in(19) <= not gpioA_in(19) after 20 us; --E_RX_DV
gpioA_in(18 downto 15) <= gpioA_in(18 downto 15) + 1 after 400 ns; --E_RX_RXD
gpioA_in(14) <= not gpioA_in(14) after 200 ns; --E_TX_CLK
u1_plasma: plasma
generic map (memory_type => memory_type,
ethernet => '1',
use_cache => '1',
log_file => log_file)
PORT MAP (
clk => clk,
reset => reset,
uart_read => uart_write,
uart_write => uart_write,
address => address,
byte_we => byte_we,
data_write => data_write,
data_read => data_read,
mem_pause_in => pause,
no_ddr_start => no_ddr_start,
no_ddr_stop => no_ddr_stop,
gpio0_out => open,
gpioA_in => gpioA_in);
dram_proc: process(clk, address, byte_we, data_write, pause)
constant ADDRESS_WIDTH : natural := 16;
type storage_array is
array(natural range 0 to (2 ** ADDRESS_WIDTH) / 4 - 1) of
std_logic_vector(31 downto 0);
variable storage : storage_array;
variable data : std_logic_vector(31 downto 0);
variable index : natural := 0;
begin
index := conv_integer(address(ADDRESS_WIDTH-1 downto 2));
data := storage(index);
if byte_we(0) = '1' then
data(7 downto 0) := data_write(7 downto 0);
end if;
if byte_we(1) = '1' then
data(15 downto 8) := data_write(15 downto 8);
end if;
if byte_we(2) = '1' then
data(23 downto 16) := data_write(23 downto 16);
end if;
if byte_we(3) = '1' then
data(31 downto 24) := data_write(31 downto 24);
end if;
if rising_edge(clk) then
if address(30 downto 28) = "001" and byte_we /= "0000" then
storage(index) := data;
end if;
end if;
if pause = '0' then
data_read <= data;
end if;
end process;
end; --architecture logic