OpenCores
URL https://opencores.org/ocsvn/uart_fifo_cpu_if_sv_testbench/uart_fifo_cpu_if_sv_testbench/trunk

Subversion Repositories uart_fifo_cpu_if_sv_testbench

Compare Revisions

  • This comparison shows the changes necessary to convert path
    /
    from Rev 1 to Rev 2
    Reverse comparison

Rev 1 → Rev 2

/uart_fifo_cpu_if_sv_testbench/trunk/bench/uart_tb.sv
0,0 → 1,358
//////////////////////////////////////////////////////////////////////
//// ////
//// Testbench for uart.vhd ////
//// ////
//// This file is part of the XXX project ////
//// http://www.opencores.org/cores/xxx/ ////
//// ////
//// Description ////
//// Self checking testbench for uart.vhd. SV class implements a serial UART driver and monitor.
//// The driver accepts byte transactions and converts the byte to a serial stream.
//// The monitor converts serial UART bitstream to byte transactions.
//// ////
//// To Do: ////
//// - ////
//// ////
//// Author(s): ////
//// - Andrew Bridger, andrew.bridger@gmail.com ////
//// ////
//////////////////////////////////////////////////////////////////////
//// ////
//// Copyright (C) 2001 Authors and OPENCORES.ORG ////
//// ////
//// This source file may be used and distributed without ////
//// restriction provided that this copyright statement is not ////
//// removed from the file and that any derivative work contains ////
//// the original copyright notice and the associated disclaimer. ////
//// ////
//// This source file 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 2.1 of the License, or (at your option) any ////
//// later version. ////
//// ////
//// This source 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 source; if not, download it ////
//// from http://www.opencores.org/lgpl.shtml ////
//// ////
//////////////////////////////////////////////////////////////////////
//
// CVS Revision History
//
// $Log$
//
 
timeunit 1ns;
timeprecision 1ps;
 
import std_defs::*;
 
interface uart_if ();
logic txd = 0; //from testbench driver
logic rxd = 0; //to testbench monitor
endinterface : uart_if
 
typedef logic[11:0] cpu_addr_t;
typedef logic[7:0] cpu_data_t;
 
 
 
module uart_tb();
 
`define BAUD_RATE 115200 //baud rate to test.
`define UART_FIFO_SIZE 32 //DUT FIFO size.
//Instantiate the DUT interfaces;
uart_if uart_();
//Keep Testbench simple for the CPU register interface - use tasks for bus functional model, so don't require SV i/f.
cpu_addr_t cpu_addr;
cpu_data_t cpu_data_in;
cpu_data_t cpu_data_out;
logic cpu_we;
logic cpu_rd;
logic clk, reset;
//DUT
\work.uart(rtl) vhdl_module (
.clk (clk),
.reset (reset),
//Serial UART
.i_rxd (uart_.txd),
.o_txd (uart_.rxd),
//Cpu register interface
.i_addr (cpu_addr),
.i_write_enable (cpu_we),
.i_read_enable (cpu_rd),
.i_data (cpu_data_in),
.o_data (cpu_data_out) );
//Takes byte transactions and generates serial data on TXD. No parity, 8 data bits, 1 stop bit.
class uart_driver;
virtual uart_if uart_;
mailbox #(uint8) mbx;
bit verbose = false;
uint16 baud_rate;
 
function new( virtual uart_if uart_, uint16 baud_rate, mailbox #(uint8) mbx );
uart_ = uart_;
baud_rate = baud_rate;
mbx = mbx;
endfunction
 
//Main driver thread. Empty the mailbox by looking for transactions, and driving them out onto TXD.
task automatic run();
//spawn processes required for this driver.
fork begin
uint8 data;
logic[7:0] data_bits;
 
forever begin
mbx.get( data ); //block if no transactions waiting.
data_bits = data;
//start bit
uart_.txd = 0;
#(1/baud_rate)s;
//8 bits of data
for(uint8 i=0; i<8; i++) begin
uart_.txd = data_bits[7-i];
#(1/baud_rate)s;
end
//1 stop bit
uart_.txd = 1;
#(1/baud_rate)s;
end
end
join_none
endtask
endclass
//Looks for serial bytes on RXD, and converts them into byte transactions into a mailbox.
class uart_monitor;
virtual uart_if uart_;
mailbox #(uint8) mbx;
bit verbose = false;
uint16 baud_rate;
 
function new( virtual uart_if uart_, uint16 baud_rate, mailbox #(uint8) mbx );
uart_ = uart_;
baud_rate = baud_rate;
mbx = mbx;
endfunction
 
//Main monitor thread.
task automatic run();
fork begin
forever begin
//Look for a valid start bit. Must be at least 1/2 bit period duration.
@(negedge uart_.rxd);
#(0.5 * 1/baud_rate)s;
if ( uart_.rxd == 0 ) begin
logic[7:0] data_bits;
uint32 bit_count = 7;
//read in 8 data bits, MSBit first, sampling in the center of the bit period.
repeat(8) begin
#( 1/baud_rate )s;
data_bits[ bit_count-- ] = uart_.rxd;
end
//check stop bit.
#( 1/baud_rate )s;
if ( uart_.rxd != 1 ) begin
$display("Monitor: Invalid stop bit.");
end
else begin
//valid stop bit so generate transaction.
uint8 data;
data = data_bits;
mbx.put( data );
end
end
end
end
join_none
endtask
endclass
 
task automatic cpu_init();
cpu_addr = 0;
cpu_data_in = 0;
cpu_we = 0;
cpu_rd = 0;
endtask
//Read a register.
task automatic cpu_read( cpu_addr_t addr, cpu_data_t data );
@(negedge clk); //setup on falling edge. DUT reads on rising edge.
cpu_addr = addr;
cpu_rd = 1;
cpu_we = 0;
@(negedge clk);
cpu_rd = 0;
@(negedge clk); //uart returns data maximum of 2 clocks after read enable.
data = cpu_data_out;
endtask
 
//Write a register.
task automatic cpu_write( cpu_addr_t addr, cpu_data_t data );
@(negedge clk); //setup on falling edge. DUT reads on rising edge.
cpu_addr = addr;
cpu_rd = 0;
cpu_we = 1;
cpu_data_in = data;
@(negedge clk);
endtask
 
//System clock
initial
begin
clk = 0;
forever #20ns clk <= ~clk;
end
 
//Main sim process.
initial
begin
$display("%t << Starting the simulation >>", $time);
cpu_init();
//ok, now run some tests.
test_cpu_interface();
test_serial_facing_loopback(); //This one is also a good test for the testbench UART monitor/driver classes.
test_cpu_to_txd();
test_rxd_to_cpu();
$display("%m: %t << Simulation ran to completion >>", $time);
// $stop(0); //stop the simulation
end
task automatic dut_reset();
reset <= 1;
repeat(16) @(negedge clk);
reset <= 0;
endtask
uart_driver Uart_driver;
uart_monitor Uart_monitor;
task automatic build_test_harness( mailbox #(uint8) uart_driver_mbx, mailbox #(uint8) uart_monitor_mbx);
//transaction mailboxes for comms between driver/monitor and main testbench thread.
uart_driver_mbx = new(0); //unbounded
uart_monitor_mbx = new(0); //unbounded
//construct UART monitor and driver.
Uart_driver = new( uart_, `BAUD_RATE, uart_driver_mbx );
Uart_monitor = new( uart_, `BAUD_RATE, uart_monitor_mbx );
 
//start them up.
Uart_driver.run();
Uart_monitor.run();
endtask
task automatic test_cpu_interface();
cpu_data_t readval;
$display("Testing cpu register interface...");
 
dut_reset();
//test read/write baud rate register
cpu_write( 'h002, 'h55 );
cpu_write( 'h003, 'hAA );
cpu_read( 'h002, readval );
assert (readval == 'h55) else $display("Failed to readback register 2 correctly.");
cpu_read( 'h003, readval );
assert (readval == 'hAA) else $display("Failed to readback register 2 correctly.");
endtask
 
task automatic test_serial_facing_loopback();
//This loopback is right at the UART txd/rxd pins.
mailbox #(uint8) sent_data_mbx;
mailbox #(uint8) uart_driver_mbx;
mailbox #(uint8) uart_monitor_mbx;
build_test_harness( uart_driver_mbx, uart_monitor_mbx);
dut_reset();
 
$display("Testing serial facing loopback...");
cpu_write( 'h002, 'h80 ); //enable the loopback.
 
//Send a bunch of serial UART bytes.
repeat(1000) begin
uint8 data;
data = $random();
uart_driver_mbx.put( data );
sent_data_mbx.put( data );
end
 
//Gives some time for any remaining transactions to propagate through the DUT.
#( `UART_FIFO_SIZE * (12 * 1/`BAUD_RATE))s; //10 bits/ baud, but allow for 12.
 
//Check the sent data comes back error free.
compare_mailbox_data( sent_data_mbx, uart_monitor_mbx );
endtask
task automatic test_cpu_to_txd();
mailbox #(uint8) sent_data_mbx;
 
mailbox #(uint8) uart_driver_mbx;
mailbox #(uint8) uart_monitor_mbx;
build_test_harness( uart_driver_mbx, uart_monitor_mbx);
dut_reset();
sent_data_mbx = new(0);
$display("Testing cpu to UART serial TXD interface...");
//Using the UART's cpu interface, write a bunch of data in. Make sure we don't overflow the uart tx FIFO by
//always reading the FIFO full flag prior to writing. Check all data is correctly received by the monitor.
repeat(1000) begin
uint8 readval;
uint8 data;
data = $random();
//check uart tx fifo is not full
cpu_read( 'h001, readval );
if ((readval & 'h08) == 0) begin
cpu_write( 'h000, data );
sent_data_mbx.put(data);
end
end
 
//Gives some time for any remaining transactions to propagate through the DUT.
#( `UART_FIFO_SIZE * (12 * 1/`BAUD_RATE))s; //10 bits/ baud, but allow for 12.
//Check the sent and received data is the same.
compare_mailbox_data( sent_data_mbx, uart_monitor_mbx );
endtask
 
//Check all reference mailbox items against dut mailbox items. Expected to be identical, report differences.
function automatic void compare_mailbox_data( mailbox #(uint8) ref_mbx, mailbox #(uint8) dut_mbx );
uint32 error = 0;
uint32 good = 0;
repeat( ref_mbx.size() ) begin
uint8 dut_data;
uint8 ref_data;
uint32 tryget_result;
ref_mbx.get( ref_data );
//try to get dut data, may not be there if dut swallowed it.
tryget_result = dut_mbx.try_get( dut_data );
if (tryget_result) begin
if (ref_data != dut_data) begin
error++;
end
else begin
good++;
end
break; //no more DUT data
end
end
$display("Good: %2d, Errored: %2d, Excess reference %2d, Excess DUT %2d",
good, error, ref_mbx.size(), dut_mbx.size());
endfunction
endmodule
 
 
 
/uart_fifo_cpu_if_sv_testbench/trunk/rtl/uart.vhd
0,0 → 1,411
----------------------------------------------------------------------
---- ----
---- UART and FIFO cpu interface ----
---- ----
---- This file is part of the xxx project ----
---- http://www.opencores.org/cores/xxx/ ----
---- ----
---- Description ----
-- Serial UART with byte wide register interface for control/status, data, and baud rate.
-- Transmit(Tx) and Receive(Rx) data is FIFO buffered. Tx and Rx FIFO size configurable independently.
-- Currently only supports no parity, 8 data bits, 1 stop bit (N81).
-- Data is sent most significant bit first.
-- Baud rate divisor set via 16 bit register, allowing a wide range of baud rates and system clocks.
--
-- Future:
-- - insertion and checking of parity bit
-- - data bit order configurable
-- - number of data bits configurable
-- - cts/rts
-- - interrupt on rx data ready and/or tx fifo empty
--
--Registers: 0x00: Data:
-- Write this register to push data into the transmit FIFO. The UART
-- empties the FIFO and transmits data at the specified baud rate.
-- If the FIFO is full, writes are ignored.
-- Read this register to pull data from the receive FIFO. If the FIFO
-- is empty, reading returns the previously read value.
-- 0x01: Control/Status:
-- bit0: Rx FIFO data ready: High when data waiting in the rx FIFO.
-- bit1: Rx FIFO overflow flag: High if overflow occurs. Write 0 to clear.
-- bit2: Rx stop bit error flag: High if invalid stop bit. Write 0 to clear.
-- bit3: Tx FIFO full: High when the tx FIFO is full.
-- bit4: Tx FIFO overflow flag: High if overflow occurs. Write 0 to clear.
-- bit5: unused
-- bit6: Cpu interface facing loopback enable: loopback is at serial txd/rxd pins
-- bit7: Txd/rxd pin facing loopback enable: loopback is at txd/rxd pins
-- (both loopbacks can be enabled at the same time)
--
-- 0x02: Baud Rate Divisor LSB: baud rate = System clock / (baud rate divisor+1)
-- 0x03: Baud Rate Divisor MSB: e.g. set to 433 to get 115200 with a 50MHz
-- system clock. Error is < 0.01%.
--
-- Fmax and resource use data:
--
---- To Do: ----
---- - ----
---- ----
---- Author(s): ----
---- - Andrew Bridger, andrew.bridger@gmail.org ----
---- ----
----------------------------------------------------------------------
---- ----
---- Copyright (C) 2001 Authors and OPENCORES.ORG ----
---- ----
---- This source file may be used and distributed without ----
---- restriction provided that this copyright statement is not ----
---- removed from the file and that any derivative work contains ----
---- the original copyright notice and the associated disclaimer. ----
---- ----
---- This source file 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 2.1 of the License, or (at your option) any ----
---- later version. ----
---- ----
---- This source 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 source; if not, download it ----
---- from http://www.opencores.org/lgpl.shtml ----
---- ----
----------------------------------------------------------------------
--
-- CVS Revision History
--
-- $Log$
--
 
library ieee;
use ieee.std_logic_1164.all;
use ieee.numeric_std.all;
 
entity uart is
generic(
BASE_ADDR : natural := 0; --Uart registers are offset from
-- this base address.
TX_FIFO_ADDR_LENGTH : natural := 5; --5 length addr => 32 byte deep FIFO
RX_FIFO_ADDR_LENGTH : natural := 5
);
port(
clk : in std_logic; --all inputs(except rxd) MUST be synchronous to clk.
reset : in std_logic; --synchronous reset
--Serial UART
i_rxd : in std_logic; --receive serial data (asynchronous)
o_txd : out std_logic; --transmit serial data
--Cpu register interface
i_addr : in std_logic_vector(15 downto 0); --highest index is msb of address.
i_write_enable : in std_logic; --high for 1 clk period for a write
i_read_enable : in std_logic; --high for 1 clk period for a read
i_data : in std_logic_vector(7 downto 0);
o_data : out std_logic_vector(7 downto 0) --data returned up to 2 clock cycles after read_enable
);
end uart;
 
architecture rtl of uart is
 
signal rxd_d1, rxd_clean : std_logic;
 
--FIFO from/to main process communication.
signal tx_fifo_write_data, tx_fifo_read_data : std_logic_vector(7 downto 0);
signal tx_fifo_write_request, tx_fifo_read_request : std_logic;
signal rx_fifo_write_data, rx_fifo_read_data : std_logic_vector(7 downto 0);
signal rx_fifo_write_request, rx_fifo_read_request : std_logic;
signal rx_fifo_read_request_d1 : std_logic;
signal tx_fifo_full_flag : std_logic;
signal tx_fifo_overflow : std_logic;
signal tx_fifo_empty, tx_fifo_data_waiting : std_logic;
signal rx_fifo_overflow : std_logic;
signal rx_fifo_empty : std_logic;
signal rx_fifo_data_ready_flag : std_logic;
 
--Cpu regs/bits
signal rx_fifo_overflow_flag : std_logic;
signal tx_fifo_overflow_flag : std_logic;
signal rx_stop_bit_invalid_flag : std_logic;
 
signal cpu_facing_loopback_enable : std_logic;
signal serial_facing_loopback_enable : std_logic;
--Baud rate divisor for 50MHz system clock and 115200 baud rate.
constant BAUD_RATE_DIVISOR_50M_115200 : std_logic_vector(15 downto 0) := std_logic_vector(to_unsigned(433, 16));
signal baud_rate_divisor_slv : std_logic_vector(15 downto 0);
--cpu register addresses and bit indexes
constant DATA_REG : std_logic_vector(1 downto 0) := "00";
constant CONTROL_STATUS_REG : std_logic_vector(1 downto 0) := "01";
constant BAUD_RATE_DIVISOR_LSB_REG : std_logic_vector(1 downto 0) := "10";
constant BAUD_RATE_DIVISOR_MSB_REG : std_logic_vector(1 downto 0) := "11";
constant BASE_ADDR_SLV : std_logic_vector(i_addr'length-1 downto 0)
:= std_logic_vector(to_unsigned(BASE_ADDR, i_addr'length));
begin
 
main : process(clk)
type uart_state_t is (IDLE, START, DATA, STOP);
variable tx_state, rx_state : uart_state_t;
subtype baud_rate_t is natural range 0 to (2**16)-1;
variable baud_rate_divisor : baud_rate_t;
variable tx_baud_rate_count : baud_rate_t;
variable rx_baud_rate_count : baud_rate_t;
variable tx_data_count : natural range 0 to 7;
variable rx_data_count : natural range 0 to 7;
variable rx_bit_enable : boolean;
variable tx_bit_enable : boolean;
variable chip_select : boolean;
variable rxd, txd : std_logic;
variable addr : std_logic_vector(i_addr'length-1 downto 0);
begin
if rising_edge(clk) then
if reset = '1' then
--Keep uart serial lines high during reset. Don't want any glitches at startup.
rxd_d1 <= '1';
rxd_clean <= '1';
rxd := '1';
txd := '1';
o_txd <= '1';
--Put UART rx/tx FSMs and counters into a known state at reset.
tx_state := IDLE;
rx_state := IDLE;
tx_baud_rate_count := 0;
rx_baud_rate_count := 0;
tx_fifo_write_request <= '0';
tx_fifo_read_request <= '0';
rx_fifo_write_request <= '0';
rx_fifo_read_request <= '0';
--Power up state for registers
baud_rate_divisor_slv <= BAUD_RATE_DIVISOR_50M_115200; --set default for 115200
rx_fifo_overflow_flag <= '0';
rx_stop_bit_invalid_flag <= '0';
tx_fifo_overflow_flag <= '0';
cpu_facing_loopback_enable <= '0';
serial_facing_loopback_enable <= '0';
--Check base addr on x4 byte boundary.
--Only check during reset so no burden on sim speed. (Synplicity doesn't honour this assert unfortunately.)
assert BASE_ADDR_SLV(1 downto 0) = "00" report "UART Base address must be 32 bit aligned. I.e. 2 LSBs must be 00"
severity failure;
else
------[CPU Interface]------
--CPU interface side of rx and tx fifos. Including the registers directly within this module means
--this is a self-contained module.
addr := i_addr; --ensure addr is in "downto" form.
chip_select := (addr(addr'high downto 2) = BASE_ADDR_SLV(BASE_ADDR_SLV'high downto 2));
if chip_select then
--Cpu register write.
if i_write_enable = '1' then
case i_addr(1 downto 0) is
when DATA_REG =>
tx_fifo_write_data <= i_data;
tx_fifo_write_request <= '1';
when CONTROL_STATUS_REG =>
--Some bits are only write zero to clear.
if i_data(1) = '0' then
rx_fifo_overflow_flag <= '0';
end if;
if i_data(2) = '0' then
rx_stop_bit_invalid_flag <= '0';
end if;
if i_data(4) = '0' then
tx_fifo_overflow_flag <= '0';
end if;
--Standard read/write control bits
cpu_facing_loopback_enable <= i_data(6);
serial_facing_loopback_enable <= i_data(7);
 
when BAUD_RATE_DIVISOR_LSB_REG => baud_rate_divisor_slv(7 downto 0) <= i_data;
when BAUD_RATE_DIVISOR_MSB_REG => baud_rate_divisor_slv(15 downto 8) <= i_data;
when others => null;
end case;
end if;
--Cpu register read.
if i_read_enable = '1' then
case i_addr(1 downto 0) is
when DATA_REG => rx_fifo_read_request <= '1';
when CONTROL_STATUS_REG => o_data <= serial_facing_loopback_enable &
cpu_facing_loopback_enable &
'0' & --unused
tx_fifo_overflow_flag &
tx_fifo_full_flag &
rx_stop_bit_invalid_flag &
rx_fifo_overflow_flag &
rx_fifo_data_ready_flag;
when BAUD_RATE_DIVISOR_LSB_REG => o_data <= baud_rate_divisor_slv(7 downto 0);
when BAUD_RATE_DIVISOR_MSB_REG => o_data <= baud_rate_divisor_slv(15 downto 8);
when others => null;
end case;
end if;
end if;
--Takes 1 clock to read data out of rx fifo.
rx_fifo_read_request_d1 <= rx_fifo_read_request;
if rx_fifo_read_request_d1 = '1' then
o_data <= rx_fifo_read_data;
end if;
--type conversion for baud rate divisor.
baud_rate_divisor := to_integer( unsigned( baud_rate_divisor_slv ));
 
------[UART Transmit (tx) FSM]------
tx_fifo_read_request <= '0'; --default
case tx_state is
when IDLE =>
txd := '1';
if tx_fifo_data_waiting = '1' then
tx_state := START;
tx_fifo_read_request <= '1';
end if;
--output 1 start bit
when START =>
if tx_bit_enable then
txd := '0';
tx_state := DATA;
tx_data_count := 7;
end if;
--output 8 data bits
when DATA =>
if tx_bit_enable then
txd := tx_fifo_read_data(tx_data_count);
if tx_data_count = 0 then
tx_state := STOP;
else
tx_data_count := tx_data_count - 1;
end if;
end if;
--output 1 stop bit
when STOP =>
if tx_bit_enable then
txd := '1';
tx_state := IDLE;
end if;
end case;
 
--transmit baud rate "clk" (enable)
if tx_baud_rate_count = 0 then
tx_baud_rate_count := baud_rate_divisor;
tx_bit_enable := true;
else
tx_baud_rate_count := tx_baud_rate_count - 1;
tx_bit_enable := false;
end if;
 
------[UART Receive (rx) FSM]------
rx_fifo_write_request <= '0';
case rx_state is
when IDLE =>
if rxd = '0' then
rx_state := START;
rx_baud_rate_count := baud_rate_divisor/2; --setup baud rate counter so we sample
--at middle of bit period
end if;
--look for a start bit that is continuously low for at least 1/2 the nominal bit
--period. This helps to filter short duration glitches. And gets us sampling
--rxd at the center of a bit period.
when START =>
if rxd /= '0' then
--start bit has not stayed low for longer than 1/2 a bit period.
rx_state := IDLE;
elsif rx_bit_enable then
rx_state := DATA;
rx_data_count := 7;
end if;
--read in 8 data bits.
when DATA =>
if rx_bit_enable then
rx_fifo_write_data(rx_data_count) <= rxd;
if rx_data_count = 0 then
rx_state := STOP;
else
rx_data_count := rx_data_count - 1;
end if;
end if;
--check stop bit is '1'. If not, set the rx error flag.
when STOP =>
if rx_bit_enable then
if rxd = '1' then
--Valid stop bit, so attempt to write the received byte to the rx fifo.
rx_fifo_write_request <= '1';
else
--Invalid stop bit.
rx_stop_bit_invalid_flag <= '1';
end if;
rx_state := IDLE;
end if;
end case;
 
--receive baud rate "clk" (enable)
if rx_baud_rate_count = 0 then
rx_baud_rate_count := baud_rate_divisor;
rx_bit_enable := true;
else
rx_baud_rate_count := rx_baud_rate_count - 1;
rx_bit_enable := false;
end if;
 
------[Latch FIFO overflow bits]------
if tx_fifo_overflow = '1' then
tx_fifo_overflow_flag <= '1';
end if;
if rx_fifo_overflow = '1' then
rx_fifo_overflow_flag <= '1';
end if;
 
------[Loopbacks and Rxd Retime]------
--rxd is an asynchronous input so retime it onto the system clock domain.
rxd_d1 <= i_rxd;
rxd_clean <= rxd_d1;
if cpu_facing_loopback_enable = '0' then
--normal operation.
rxd := rxd_clean;
else
--loopback enabled.
rxd := txd;
end if;
if serial_facing_loopback_enable = '0' then
--normal operation.
o_txd <= txd;
else
--loopback enabled.
o_txd <= rxd_clean;
end if;
end if;
end if;
end process;
 
tx_fifo : entity work.synchronous_FIFO(rtl)
generic map (
ADDR_LENGTH => TX_FIFO_ADDR_LENGTH,
DATA_WIDTH => 8)
port map (
clk => clk,
reset => reset,
write_data => tx_fifo_write_data,
write_request => tx_fifo_write_request,
full => tx_fifo_full_flag,
overflow => tx_fifo_overflow,
read_data => tx_fifo_read_data,
read_request => tx_fifo_read_request,
empty => tx_fifo_empty,
underflow => open,
half_full => open);
 
tx_fifo_data_waiting <= not tx_fifo_empty;
 
rx_fifo : entity work.synchronous_FIFO(rtl)
generic map (
ADDR_LENGTH => RX_FIFO_ADDR_LENGTH,
DATA_WIDTH => 8)
port map (
clk => clk,
reset => reset,
write_data => rx_fifo_write_data,
write_request => rx_fifo_write_request,
full => open,
overflow => rx_fifo_overflow,
read_data => rx_fifo_read_data,
read_request => rx_fifo_read_request,
empty => rx_fifo_empty,
underflow => open,
half_full => open);
 
rx_fifo_data_ready_flag <= not rx_fifo_empty;
end rtl;

powered by: WebSVN 2.1.0

© copyright 1999-2024 OpenCores.org, equivalent to Oliscience, all rights reserved. OpenCores®, registered trademark.