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

Subversion Repositories openmsp430

Compare Revisions

  • This comparison shows the changes necessary to convert path
    /openmsp430/trunk/core/rtl/verilog
    from Rev 151 to Rev 154
    Reverse comparison

Rev 151 → Rev 154

/omsp_dbg_i2c.v
0,0 → 1,466
//----------------------------------------------------------------------------
// Copyright (C) 2009 , Olivier Girard
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the authors nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
// OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF
// THE POSSIBILITY OF SUCH DAMAGE
//
//----------------------------------------------------------------------------
//
// *File Name: omsp_dbg_i2c.v
//
// *Module Description:
// Debug I2C Slave communication interface
//
// *Author(s):
// - Olivier Girard, olgirard@gmail.com
//
//----------------------------------------------------------------------------
// $Rev: 103 $
// $LastChangedBy: olivier.girard $
// $LastChangedDate: 2011-03-05 15:44:48 +0100 (Sat, 05 Mar 2011) $
//----------------------------------------------------------------------------
`ifdef OMSP_NO_INCLUDE
`else
`include "openMSP430_defines.v"
`endif
 
module omsp_dbg_i2c (
 
// OUTPUTs
dbg_addr, // Debug register address
dbg_din, // Debug register data input
dbg_i2c_sda_out, // Debug interface: I2C SDA OUT
dbg_rd, // Debug register data read
dbg_wr, // Debug register data write
 
// INPUTs
dbg_clk, // Debug unit clock
dbg_dout, // Debug register data output
dbg_i2c_addr, // Debug interface: I2C ADDRESS
dbg_i2c_broadcast, // Debug interface: I2C Broadcast Address (for multicore systems)
dbg_i2c_scl, // Debug interface: I2C SCL
dbg_i2c_sda_in, // Debug interface: I2C SDA IN
dbg_rd_rdy, // Debug register data is ready for read
dbg_rst, // Debug unit reset
mem_burst, // Burst on going
mem_burst_end, // End TX/RX burst
mem_burst_rd, // Start TX burst
mem_burst_wr, // Start RX burst
mem_bw // Burst byte width
);
 
// OUTPUTs
//=========
output [5:0] dbg_addr; // Debug register address
output [15:0] dbg_din; // Debug register data input
output dbg_i2c_sda_out; // Debug interface: I2C SDA OUT
output dbg_rd; // Debug register data read
output dbg_wr; // Debug register data write
 
// INPUTs
//=========
input dbg_clk; // Debug unit clock
input [15:0] dbg_dout; // Debug register data output
input [6:0] dbg_i2c_addr; // Debug interface: I2C ADDRESS
input [6:0] dbg_i2c_broadcast; // Debug interface: I2C Broadcast Address (for multicore systems)
input dbg_i2c_scl; // Debug interface: I2C SCL
input dbg_i2c_sda_in; // Debug interface: I2C SDA IN
input dbg_rd_rdy; // Debug register data is ready for read
input dbg_rst; // Debug unit reset
input mem_burst; // Burst on going
input mem_burst_end; // End TX/RX burst
input mem_burst_rd; // Start TX burst
input mem_burst_wr; // Start RX burst
input mem_bw; // Burst byte width
 
 
//=============================================================================
// 1) I2C RECEIVE LINE SYNCHRONIZTION & FILTERING
//=============================================================================
 
// Synchronize SCL/SDA inputs
//--------------------------------
 
wire scl_sync_n;
omsp_sync_cell sync_cell_i2c_scl (
.data_out (scl_sync_n),
.data_in (~dbg_i2c_scl),
.clk (dbg_clk),
.rst (dbg_rst)
);
wire scl_sync = ~scl_sync_n;
 
wire sda_in_sync_n;
omsp_sync_cell sync_cell_i2c_sda (
.data_out (sda_in_sync_n),
.data_in (~dbg_i2c_sda_in),
.clk (dbg_clk),
.rst (dbg_rst)
);
wire sda_in_sync = ~sda_in_sync_n;
 
// SCL/SDA input buffers
//--------------------------------
 
reg [1:0] scl_buf;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) scl_buf <= 2'h3;
else scl_buf <= {scl_buf[0], scl_sync};
 
reg [1:0] sda_in_buf;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) sda_in_buf <= 2'h3;
else sda_in_buf <= {sda_in_buf[0], sda_in_sync};
 
 
// SCL/SDA Majority decision
//------------------------------
 
wire scl = (scl_sync & scl_buf[0]) |
(scl_sync & scl_buf[1]) |
(scl_buf[0] & scl_buf[1]);
wire sda_in = (sda_in_sync & sda_in_buf[0]) |
(sda_in_sync & sda_in_buf[1]) |
(sda_in_buf[0] & sda_in_buf[1]);
 
 
// SCL/SDA Edge detection
//------------------------------
 
// SDA Edge detection
reg sda_in_dly;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) sda_in_dly <= 1'b1;
else sda_in_dly <= sda_in;
 
wire sda_in_fe = sda_in_dly & ~sda_in;
wire sda_in_re = ~sda_in_dly & sda_in;
wire sda_in_edge = sda_in_dly ^ sda_in;
 
// SCL Edge detection
reg scl_dly;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) scl_dly <= 1'b1;
else scl_dly <= scl;
 
wire scl_fe = scl_dly & ~scl;
wire scl_re = ~scl_dly & scl;
wire scl_edge = scl_dly ^ scl;
 
 
// Delayed SCL Rising-Edge for SDA data sampling
reg [1:0] scl_re_dly;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) scl_re_dly <= 2'b00;
else scl_re_dly <= {scl_re_dly[0], scl_re};
 
wire scl_sample = scl_re_dly[1];
 
//=============================================================================
// 2) I2C START & STOP CONDITION DETECTION
//=============================================================================
 
//-----------------
// Start condition
//-----------------
 
wire start_detect = sda_in_fe & scl;
 
//-----------------
// Stop condition
//-----------------
 
wire stop_detect = sda_in_re & scl;
//-----------------
// I2C Slave Active
//-----------------
// The I2C logic will be activated whenever a start condition
// is detected and will be disactivated if the slave address
// doesn't match or if a stop condition is detected.
 
wire i2c_addr_not_valid;
 
reg i2c_active_seq;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) i2c_active_seq <= 1'b0;
else if (start_detect) i2c_active_seq <= 1'b1;
else if (stop_detect || i2c_addr_not_valid) i2c_active_seq <= 1'b0;
 
wire i2c_active = i2c_active_seq & ~stop_detect;
wire i2c_init = ~i2c_active | start_detect;
 
//=============================================================================
// 3) I2C STATE MACHINE
//=============================================================================
 
// State register/wires
reg [2:0] i2c_state;
reg [2:0] i2c_state_nxt;
 
// Utility signals
reg [8:0] shift_buf;
wire shift_rx_done;
wire shift_tx_done;
reg dbg_rd;
// State machine definition
parameter RX_ADDR = 3'h0;
parameter RX_ADDR_ACK = 3'h1;
parameter RX_DATA = 3'h2;
parameter RX_DATA_ACK = 3'h3;
parameter TX_DATA = 3'h4;
parameter TX_DATA_ACK = 3'h5;
 
// State transition
always @(i2c_state or i2c_init or shift_rx_done or i2c_addr_not_valid or shift_tx_done or scl_fe or shift_buf or sda_in)
case (i2c_state)
RX_ADDR : i2c_state_nxt = i2c_init ? RX_ADDR :
~shift_rx_done ? RX_ADDR :
i2c_addr_not_valid ? RX_ADDR :
RX_ADDR_ACK;
 
RX_ADDR_ACK : i2c_state_nxt = i2c_init ? RX_ADDR :
~scl_fe ? RX_ADDR_ACK :
shift_buf[0] ? TX_DATA :
RX_DATA;
 
RX_DATA : i2c_state_nxt = i2c_init ? RX_ADDR :
~shift_rx_done ? RX_DATA :
RX_DATA_ACK;
 
RX_DATA_ACK : i2c_state_nxt = i2c_init ? RX_ADDR :
~scl_fe ? RX_DATA_ACK :
RX_DATA;
 
TX_DATA : i2c_state_nxt = i2c_init ? RX_ADDR :
~shift_tx_done ? TX_DATA :
TX_DATA_ACK;
 
TX_DATA_ACK : i2c_state_nxt = i2c_init ? RX_ADDR :
~scl_fe ? TX_DATA_ACK :
~sda_in ? TX_DATA :
RX_ADDR;
// pragma coverage off
default : i2c_state_nxt = RX_ADDR;
// pragma coverage on
endcase
// State machine
always @(posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) i2c_state <= RX_ADDR;
else i2c_state <= i2c_state_nxt;
 
 
//=============================================================================
// 4) I2C SHIFT REGISTER (FOR RECEIVING & TRANSMITING)
//=============================================================================
 
wire shift_rx_en = ((i2c_state==RX_ADDR) | (i2c_state ==RX_DATA) | (i2c_state ==RX_DATA_ACK));
wire shift_tx_en = (i2c_state ==TX_DATA) | (i2c_state ==TX_DATA_ACK);
wire shift_tx_en_pre = (i2c_state_nxt==TX_DATA) | (i2c_state_nxt==TX_DATA_ACK);
 
assign shift_rx_done = shift_rx_en & scl_fe & shift_buf[8];
assign shift_tx_done = shift_tx_en & scl_fe & (shift_buf==9'h100);
 
wire shift_buf_rx_init = i2c_init | ((i2c_state==RX_ADDR_ACK) & scl_fe & ~shift_buf[0]) |
((i2c_state==RX_DATA_ACK) & scl_fe);
wire shift_buf_rx_en = shift_rx_en & scl_sample;
 
wire shift_buf_tx_init = ((i2c_state==RX_ADDR_ACK) & scl_re & shift_buf[0]) |
((i2c_state==TX_DATA_ACK) & scl_re);
wire shift_buf_tx_en = shift_tx_en_pre & scl_fe & (shift_buf!=9'h100);
 
wire [7:0] shift_tx_val;
wire [8:0] shift_buf_nxt = shift_buf_rx_init ? 9'h001 : // RX Init
shift_buf_tx_init ? {shift_tx_val, 1'b1} : // TX Init
shift_buf_rx_en ? {shift_buf[7:0], sda_in} : // RX Shift
shift_buf_tx_en ? {shift_buf[7:0], 1'b0} : // TX Shift
shift_buf[8:0]; // Hold
 
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) shift_buf <= 9'h001;
else shift_buf <= shift_buf_nxt;
 
// Detect when the received I2C device address is not valid
assign i2c_addr_not_valid = (i2c_state == RX_ADDR) && shift_rx_done && (
`ifdef DBG_I2C_BROADCAST
(shift_buf[7:1] != dbg_i2c_broadcast[6:0]) &&
`endif
(shift_buf[7:1] != dbg_i2c_addr[6:0]));
 
// Utility signals
wire shift_rx_data_done = shift_rx_done & (i2c_state==RX_DATA);
wire shift_tx_data_done = shift_tx_done;
 
 
//=============================================================================
// 5) I2C TRANSMIT BUFFER
//=============================================================================
 
reg dbg_i2c_sda_out;
 
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_i2c_sda_out <= 1'b1;
else if (scl_fe) dbg_i2c_sda_out <= ~((i2c_state_nxt==RX_ADDR_ACK) ||
(i2c_state_nxt==RX_DATA_ACK) ||
(shift_buf_tx_en & ~shift_buf[8]));
//=============================================================================
// 6) DEBUG INTERFACE STATE MACHINE
//=============================================================================
 
// State register/wires
reg [2:0] dbg_state;
reg [2:0] dbg_state_nxt;
 
// Utility signals
reg dbg_bw;
 
// State machine definition
parameter RX_CMD = 3'h0;
parameter RX_BYTE_LO = 3'h1;
parameter RX_BYTE_HI = 3'h2;
parameter TX_BYTE_LO = 3'h3;
parameter TX_BYTE_HI = 3'h4;
 
// State transition
always @(dbg_state or shift_rx_data_done or shift_tx_data_done or shift_buf or dbg_bw or
mem_burst_wr or mem_burst_rd or mem_burst or mem_burst_end or mem_bw)
case (dbg_state)
RX_CMD : dbg_state_nxt = mem_burst_wr ? RX_BYTE_LO :
mem_burst_rd ? TX_BYTE_LO :
~shift_rx_data_done ? RX_CMD :
shift_buf[7] ? RX_BYTE_LO :
TX_BYTE_LO;
 
RX_BYTE_LO : dbg_state_nxt = (mem_burst & mem_burst_end) ? RX_CMD :
~shift_rx_data_done ? RX_BYTE_LO :
(mem_burst & ~mem_burst_end) ?
(mem_bw ? RX_BYTE_LO :
RX_BYTE_HI) :
dbg_bw ? RX_CMD :
RX_BYTE_HI;
 
RX_BYTE_HI : dbg_state_nxt = ~shift_rx_data_done ? RX_BYTE_HI :
(mem_burst & ~mem_burst_end) ? RX_BYTE_LO :
RX_CMD;
 
TX_BYTE_LO : dbg_state_nxt = ~shift_tx_data_done ? TX_BYTE_LO :
( mem_burst & mem_bw) ? TX_BYTE_LO :
( mem_burst & ~mem_bw) ? TX_BYTE_HI :
~dbg_bw ? TX_BYTE_HI :
RX_CMD;
 
TX_BYTE_HI : dbg_state_nxt = ~shift_tx_data_done ? TX_BYTE_HI :
mem_burst ? TX_BYTE_LO :
RX_CMD;
 
// pragma coverage off
default : dbg_state_nxt = RX_CMD;
// pragma coverage on
endcase
// State machine
always @(posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_state <= RX_CMD;
else dbg_state <= dbg_state_nxt;
 
// Utility signals
wire cmd_valid = (dbg_state==RX_CMD) & shift_rx_data_done;
wire rx_lo_valid = (dbg_state==RX_BYTE_LO) & shift_rx_data_done;
wire rx_hi_valid = (dbg_state==RX_BYTE_HI) & shift_rx_data_done;
 
 
//=============================================================================
// 7) REGISTER READ/WRITE ACCESS
//=============================================================================
 
parameter MEM_DATA = 6'h06;
 
// Debug register address & bit width
reg [5:0] dbg_addr;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst)
begin
dbg_bw <= 1'b0;
dbg_addr <= 6'h00;
end
else if (cmd_valid)
begin
dbg_bw <= shift_buf[6];
dbg_addr <= shift_buf[5:0];
end
else if (mem_burst)
begin
dbg_bw <= mem_bw;
dbg_addr <= MEM_DATA;
end
 
 
// Debug register data input
reg [7:0] dbg_din_lo;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_din_lo <= 8'h00;
else if (rx_lo_valid) dbg_din_lo <= shift_buf[7:0];
 
reg [7:0] dbg_din_hi;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_din_hi <= 8'h00;
else if (rx_lo_valid) dbg_din_hi <= 8'h00;
else if (rx_hi_valid) dbg_din_hi <= shift_buf[7:0];
assign dbg_din = {dbg_din_hi, dbg_din_lo};
 
 
// Debug register data write command
reg dbg_wr;
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_wr <= 1'b0;
else dbg_wr <= (mem_burst & mem_bw) ? rx_lo_valid :
(mem_burst & ~mem_bw) ? rx_hi_valid :
dbg_bw ? rx_lo_valid :
rx_hi_valid;
 
 
// Debug register data read command
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_rd <= 1'b0;
else dbg_rd <= (mem_burst & mem_bw) ? (shift_tx_data_done & (dbg_state==TX_BYTE_LO)) :
(mem_burst & ~mem_bw) ? (shift_tx_data_done & (dbg_state==TX_BYTE_HI)) :
cmd_valid ? ~shift_buf[7] :
1'b0;
 
 
// Debug register data read value
assign shift_tx_val = (dbg_state==TX_BYTE_HI) ? dbg_dout[15:8] :
dbg_dout[7:0];
 
endmodule
omsp_dbg_i2c.v Property changes : Added: svn:eol-style ## -0,0 +1 ## +native \ No newline at end of property Index: omsp_sfr.v =================================================================== --- omsp_sfr.v (revision 151) +++ omsp_sfr.v (revision 154) @@ -58,6 +58,8 @@ wdtifg_sw_set, // Watchdog-timer interrupt flag software set // INPUTs + cpu_nr_inst, // Current oMSP instance number + cpu_nr_total, // Total number of oMSP instances-1 mclk, // Main system clock nmi, // Non-maskable interrupt (asynchronous) nmi_acc, // Non-Maskable interrupt request accepted @@ -83,6 +85,8 @@ // INPUTs //========= +input [7:0] cpu_nr_inst; // Current oMSP instance number +input [7:0] cpu_nr_total; // Total number of oMSP instances-1 input mclk; // Main system clock input nmi; // Non-maskable interrupt (asynchronous) input nmi_acc; // Non-Maskable interrupt request accepted @@ -104,13 +108,14 @@ parameter [14:0] BASE_ADDR = 15'h0000; // Decoder bit width (defines how many bits are considered for address decoding) -parameter DEC_WD = 3; +parameter DEC_WD = 4; // Register addresses offset parameter [DEC_WD-1:0] IE1 = 'h0, IFG1 = 'h2, CPU_ID_LO = 'h4, - CPU_ID_HI = 'h6; + CPU_ID_HI = 'h6, + CPU_NR = 'h8; // Register one-hot decoder utilities parameter DEC_SZ = (1 << DEC_WD); @@ -120,7 +125,8 @@ parameter [DEC_SZ-1:0] IE1_D = (BASE_REG << IE1), IFG1_D = (BASE_REG << IFG1), CPU_ID_LO_D = (BASE_REG << CPU_ID_LO), - CPU_ID_HI_D = (BASE_REG << CPU_ID_HI); + CPU_ID_HI_D = (BASE_REG << CPU_ID_HI), + CPU_NR_D = (BASE_REG << CPU_NR); //============================================================================ @@ -137,7 +143,8 @@ wire [DEC_SZ-1:0] reg_dec = (IE1_D & {DEC_SZ{(reg_addr==(IE1 >>1))}}) | (IFG1_D & {DEC_SZ{(reg_addr==(IFG1 >>1))}}) | (CPU_ID_LO_D & {DEC_SZ{(reg_addr==(CPU_ID_LO >>1))}}) | - (CPU_ID_HI_D & {DEC_SZ{(reg_addr==(CPU_ID_HI >>1))}}); + (CPU_ID_HI_D & {DEC_SZ{(reg_addr==(CPU_ID_HI >>1))}}) | + (CPU_NR_D & {DEC_SZ{(reg_addr==(CPU_NR >>1))}}); // Read/Write probes wire reg_lo_write = per_we[0] & reg_sel; @@ -248,6 +255,17 @@ cpu_version}; +// CPU_NR Register (READ ONLY) +//----------------------------- +// ------------------------------------------------------------------- +// | 15 14 13 12 11 10 9 8 | 7 6 5 4 3 2 1 0 | +// |---------------------------------+---------------------------------| +// | CPU_TOTAL_NR | CPU_INST_NR | +// ------------------------------------------------------------------- + +wire [15:0] cpu_nr = {cpu_nr_total, cpu_nr_inst}; + + //============================================================================ // 4) DATA OUTPUT GENERATION //============================================================================ @@ -257,11 +275,13 @@ wire [15:0] ifg1_rd = {8'h00, (ifg1 & {8{reg_rd[IFG1]}})} << (8 & {4{IFG1[0]}}); wire [15:0] cpu_id_lo_rd = cpu_id[15:0] & {16{reg_rd[CPU_ID_LO]}}; wire [15:0] cpu_id_hi_rd = cpu_id[31:16] & {16{reg_rd[CPU_ID_HI]}}; +wire [15:0] cpu_nr_rd = cpu_nr & {16{reg_rd[CPU_NR]}}; wire [15:0] per_dout = ie1_rd | ifg1_rd | cpu_id_lo_rd | - cpu_id_hi_rd; + cpu_id_hi_rd | + cpu_nr_rd; //=============================================================================
/omsp_dbg.v
48,73 → 48,87
module omsp_dbg (
 
// OUTPUTs
dbg_freeze, // Freeze peripherals
dbg_halt_cmd, // Halt CPU command
dbg_mem_addr, // Debug address for rd/wr access
dbg_mem_dout, // Debug unit data output
dbg_mem_en, // Debug unit memory enable
dbg_mem_wr, // Debug unit memory write
dbg_reg_wr, // Debug unit CPU register write
dbg_cpu_reset, // Reset CPU from debug interface
dbg_uart_txd, // Debug interface: UART TXD
dbg_cpu_reset, // Reset CPU from debug interface
dbg_freeze, // Freeze peripherals
dbg_halt_cmd, // Halt CPU command
dbg_i2c_sda_out, // Debug interface: I2C SDA OUT
dbg_mem_addr, // Debug address for rd/wr access
dbg_mem_dout, // Debug unit data output
dbg_mem_en, // Debug unit memory enable
dbg_mem_wr, // Debug unit memory write
dbg_reg_wr, // Debug unit CPU register write
dbg_uart_txd, // Debug interface: UART TXD
// INPUTs
cpu_en_s, // Enable CPU code execution (synchronous)
cpu_id, // CPU ID
dbg_clk, // Debug unit clock
dbg_en_s, // Debug interface enable (synchronous)
dbg_halt_st, // Halt/Run status from CPU
dbg_mem_din, // Debug unit Memory data input
dbg_reg_din, // Debug unit CPU register data input
dbg_rst, // Debug unit reset
dbg_uart_rxd, // Debug interface: UART RXD (asynchronous)
decode_noirq, // Frontend decode instruction
eu_mab, // Execution-Unit Memory address bus
eu_mb_en, // Execution-Unit Memory bus enable
eu_mb_wr, // Execution-Unit Memory bus write transfer
eu_mdb_in, // Memory data bus input
eu_mdb_out, // Memory data bus output
exec_done, // Execution completed
fe_mb_en, // Frontend Memory bus enable
fe_mdb_in, // Frontend Memory data bus input
pc, // Program counter
puc_pnd_set // PUC pending set for the serial debug interface
cpu_en_s, // Enable CPU code execution (synchronous)
cpu_id, // CPU ID
cpu_nr_inst, // Current oMSP instance number
cpu_nr_total, // Total number of oMSP instances-1
dbg_clk, // Debug unit clock
dbg_en_s, // Debug interface enable (synchronous)
dbg_halt_st, // Halt/Run status from CPU
dbg_i2c_addr, // Debug interface: I2C Address
dbg_i2c_broadcast, // Debug interface: I2C Broadcast Address (for multicore systems)
dbg_i2c_scl, // Debug interface: I2C SCL
dbg_i2c_sda_in, // Debug interface: I2C SDA IN
dbg_mem_din, // Debug unit Memory data input
dbg_reg_din, // Debug unit CPU register data input
dbg_rst, // Debug unit reset
dbg_uart_rxd, // Debug interface: UART RXD (asynchronous)
decode_noirq, // Frontend decode instruction
eu_mab, // Execution-Unit Memory address bus
eu_mb_en, // Execution-Unit Memory bus enable
eu_mb_wr, // Execution-Unit Memory bus write transfer
eu_mdb_in, // Memory data bus input
eu_mdb_out, // Memory data bus output
exec_done, // Execution completed
fe_mb_en, // Frontend Memory bus enable
fe_mdb_in, // Frontend Memory data bus input
pc, // Program counter
puc_pnd_set // PUC pending set for the serial debug interface
);
 
// OUTPUTs
//=========
output dbg_freeze; // Freeze peripherals
output dbg_halt_cmd; // Halt CPU command
output [15:0] dbg_mem_addr; // Debug address for rd/wr access
output [15:0] dbg_mem_dout; // Debug unit data output
output dbg_mem_en; // Debug unit memory enable
output [1:0] dbg_mem_wr; // Debug unit memory write
output dbg_reg_wr; // Debug unit CPU register write
output dbg_cpu_reset; // Reset CPU from debug interface
output dbg_uart_txd; // Debug interface: UART TXD
output dbg_cpu_reset; // Reset CPU from debug interface
output dbg_freeze; // Freeze peripherals
output dbg_halt_cmd; // Halt CPU command
output dbg_i2c_sda_out; // Debug interface: I2C SDA OUT
output [15:0] dbg_mem_addr; // Debug address for rd/wr access
output [15:0] dbg_mem_dout; // Debug unit data output
output dbg_mem_en; // Debug unit memory enable
output [1:0] dbg_mem_wr; // Debug unit memory write
output dbg_reg_wr; // Debug unit CPU register write
output dbg_uart_txd; // Debug interface: UART TXD
 
// INPUTs
//=========
input cpu_en_s; // Enable CPU code execution (synchronous)
input [31:0] cpu_id; // CPU ID
input dbg_clk; // Debug unit clock
input dbg_en_s; // Debug interface enable (synchronous)
input dbg_halt_st; // Halt/Run status from CPU
input [15:0] dbg_mem_din; // Debug unit Memory data input
input [15:0] dbg_reg_din; // Debug unit CPU register data input
input dbg_rst; // Debug unit reset
input dbg_uart_rxd; // Debug interface: UART RXD (asynchronous)
input decode_noirq; // Frontend decode instruction
input [15:0] eu_mab; // Execution-Unit Memory address bus
input eu_mb_en; // Execution-Unit Memory bus enable
input [1:0] eu_mb_wr; // Execution-Unit Memory bus write transfer
input [15:0] eu_mdb_in; // Memory data bus input
input [15:0] eu_mdb_out; // Memory data bus output
input exec_done; // Execution completed
input fe_mb_en; // Frontend Memory bus enable
input [15:0] fe_mdb_in; // Frontend Memory data bus input
input [15:0] pc; // Program counter
input puc_pnd_set; // PUC pending set for the serial debug interface
input cpu_en_s; // Enable CPU code execution (synchronous)
input [31:0] cpu_id; // CPU ID
input [7:0] cpu_nr_inst; // Current oMSP instance number
input [7:0] cpu_nr_total; // Total number of oMSP instances-1
input dbg_clk; // Debug unit clock
input dbg_en_s; // Debug interface enable (synchronous)
input dbg_halt_st; // Halt/Run status from CPU
input [6:0] dbg_i2c_addr; // Debug interface: I2C Address
input [6:0] dbg_i2c_broadcast; // Debug interface: I2C Broadcast Address (for multicore systems)
input dbg_i2c_scl; // Debug interface: I2C SCL
input dbg_i2c_sda_in; // Debug interface: I2C SDA IN
input [15:0] dbg_mem_din; // Debug unit Memory data input
input [15:0] dbg_reg_din; // Debug unit CPU register data input
input dbg_rst; // Debug unit reset
input dbg_uart_rxd; // Debug interface: UART RXD (asynchronous)
input decode_noirq; // Frontend decode instruction
input [15:0] eu_mab; // Execution-Unit Memory address bus
input eu_mb_en; // Execution-Unit Memory bus enable
input [1:0] eu_mb_wr; // Execution-Unit Memory bus write transfer
input [15:0] eu_mdb_in; // Memory data bus input
input [15:0] eu_mdb_out; // Memory data bus output
input exec_done; // Execution completed
input fe_mb_en; // Frontend Memory bus enable
input [15:0] fe_mdb_in; // Frontend Memory data bus input
input [15:0] pc; // Program counter
input puc_pnd_set; // PUC pending set for the serial debug interface
 
 
//=============================================================================
148,7 → 162,7
wire [15:0] brk3_dout;
// Number of registers
parameter NR_REG = 24;
parameter NR_REG = 25;
 
// Register addresses
parameter CPU_ID_LO = 6'h00;
183,6 → 197,7
parameter BRK3_ADDR0 = 6'h16;
parameter BRK3_ADDR1 = 6'h17;
`endif
parameter CPU_NR = 6'h18;
 
// Register one-hot decoder
parameter BASE_D = {{NR_REG-1{1'b0}}, 1'b1};
218,6 → 233,7
parameter BRK3_ADDR0_D = (BASE_D << BRK3_ADDR0);
parameter BRK3_ADDR1_D = (BASE_D << BRK3_ADDR1);
`endif
parameter CPU_NR_D = (BASE_D << CPU_NR);
 
 
//============================================================================
263,6 → 279,7
BRK3_ADDR0: reg_dec = BRK3_ADDR0_D;
BRK3_ADDR1: reg_dec = BRK3_ADDR1_D;
`endif
CPU_NR : reg_dec = CPU_NR_D;
// pragma coverage off
default: reg_dec = {NR_REG{1'b0}};
// pragma coverage on
296,6 → 313,17
// This register is assigned in the SFR module
 
 
// CPU_NR Register
//-----------------
// -------------------------------------------------------------------
// | 15 14 13 12 11 10 9 8 | 7 6 5 4 3 2 1 0 |
// |---------------------------------+---------------------------------|
// | CPU_TOTAL_NR | CPU_INST_NR |
// -------------------------------------------------------------------
 
wire [15:0] cpu_nr = {cpu_nr_total, cpu_nr_inst};
 
 
// CPU_CTL Register
//-----------------------------------------------------------------------------
// 7 6 5 4 3 2 1 0
614,6 → 642,7
wire [15:0] mem_data_rd = mem_data & {16{reg_rd[MEM_DATA]}};
wire [15:0] mem_addr_rd = mem_addr & {16{reg_rd[MEM_ADDR]}};
wire [15:0] mem_cnt_rd = mem_cnt & {16{reg_rd[MEM_CNT]}};
wire [15:0] cpu_nr_rd = cpu_nr & {16{reg_rd[CPU_NR]}};
 
wire [15:0] dbg_dout = cpu_id_lo_rd |
cpu_id_hi_rd |
626,9 → 655,10
brk0_dout |
brk1_dout |
brk2_dout |
brk3_dout;
brk3_dout |
cpu_nr_rd;
 
// Tell UART/JTAG interface that the data is ready to be read
// Tell UART/I2C interface that the data is ready to be read
always @ (posedge dbg_clk or posedge dbg_rst)
if (dbg_rst) dbg_rd_rdy <= 1'b0;
else if (mem_burst | mem_burst_rd) dbg_rd_rdy <= (dbg_reg_rd | dbg_mem_rd_dly);
703,7 → 733,7
else if (mem_burst_start) mem_burst <= 1'b1;
else if (mem_burst_end) mem_burst <= 1'b0;
 
// Control signals for UART/JTAG interface
// Control signals for UART/I2C interface
assign mem_burst_rd = (mem_burst_start & ~mem_ctl[1]);
assign mem_burst_wr = (mem_burst_start & mem_ctl[1]);
 
783,43 → 813,70
omsp_dbg_uart dbg_uart_0 (
 
// OUTPUTs
.dbg_addr (dbg_addr), // Debug register address
.dbg_din (dbg_din), // Debug register data input
.dbg_rd (dbg_rd), // Debug register data read
.dbg_uart_txd (dbg_uart_txd), // Debug interface: UART TXD
.dbg_wr (dbg_wr), // Debug register data write
.dbg_addr (dbg_addr), // Debug register address
.dbg_din (dbg_din), // Debug register data input
.dbg_rd (dbg_rd), // Debug register data read
.dbg_uart_txd (dbg_uart_txd), // Debug interface: UART TXD
.dbg_wr (dbg_wr), // Debug register data write
// INPUTs
.dbg_clk (dbg_clk), // Debug unit clock
.dbg_dout (dbg_dout), // Debug register data output
.dbg_rd_rdy (dbg_rd_rdy), // Debug register data is ready for read
.dbg_rst (dbg_rst), // Debug unit reset
.dbg_uart_rxd (dbg_uart_rxd), // Debug interface: UART RXD
.mem_burst (mem_burst), // Burst on going
.mem_burst_end(mem_burst_end), // End TX/RX burst
.mem_burst_rd (mem_burst_rd), // Start TX burst
.mem_burst_wr (mem_burst_wr), // Start RX burst
.mem_bw (mem_bw) // Burst byte width
.dbg_clk (dbg_clk), // Debug unit clock
.dbg_dout (dbg_dout), // Debug register data output
.dbg_rd_rdy (dbg_rd_rdy), // Debug register data is ready for read
.dbg_rst (dbg_rst), // Debug unit reset
.dbg_uart_rxd (dbg_uart_rxd), // Debug interface: UART RXD
.mem_burst (mem_burst), // Burst on going
.mem_burst_end (mem_burst_end), // End TX/RX burst
.mem_burst_rd (mem_burst_rd), // Start TX burst
.mem_burst_wr (mem_burst_wr), // Start RX burst
.mem_bw (mem_bw) // Burst byte width
);
 
`else
assign dbg_addr = 6'h00;
assign dbg_din = 16'h0000;
assign dbg_rd = 1'b0;
assign dbg_uart_txd = 1'b0;
assign dbg_wr = 1'b0;
assign dbg_uart_txd = 1'b1;
`ifdef DBG_I2C
`else
assign dbg_addr = 6'h00;
assign dbg_din = 16'h0000;
assign dbg_rd = 1'b0;
assign dbg_wr = 1'b0;
`endif
`endif
 
//=============================================================================
// 10) JTAG COMMUNICATION
// 10) I2C COMMUNICATION
//=============================================================================
`ifdef DBG_JTAG
JTAG INTERFACE IS NOT SUPPORTED YET
`ifdef DBG_I2C
omsp_dbg_i2c dbg_i2c_0 (
 
// OUTPUTs
.dbg_addr (dbg_addr), // Debug register address
.dbg_din (dbg_din), // Debug register data input
.dbg_i2c_sda_out (dbg_i2c_sda_out), // Debug interface: I2C SDA OUT
.dbg_rd (dbg_rd), // Debug register data read
.dbg_wr (dbg_wr), // Debug register data write
 
// INPUTs
.dbg_clk (dbg_clk), // Debug unit clock
.dbg_dout (dbg_dout), // Debug register data output
.dbg_i2c_addr (dbg_i2c_addr), // Debug interface: I2C Address
.dbg_i2c_broadcast (dbg_i2c_broadcast), // Debug interface: I2C Broadcast Address (for multicore systems)
.dbg_i2c_scl (dbg_i2c_scl), // Debug interface: I2C SCL
.dbg_i2c_sda_in (dbg_i2c_sda_in), // Debug interface: I2C SDA IN
.dbg_rd_rdy (dbg_rd_rdy), // Debug register data is ready for read
.dbg_rst (dbg_rst), // Debug unit reset
.mem_burst (mem_burst), // Burst on going
.mem_burst_end (mem_burst_end), // End TX/RX burst
.mem_burst_rd (mem_burst_rd), // Start TX burst
.mem_burst_wr (mem_burst_wr), // Start RX burst
.mem_bw (mem_bw) // Burst byte width
);
 
`else
assign dbg_i2c_sda_out = 1'b1;
`endif
 
endmodule // dbg
endmodule // omsp_dbg
 
`ifdef OMSP_NO_INCLUDE
`else
/openMSP430_defines.v
205,6 → 205,29
//============================================================================
 
//-------------------------------------------------------
// Select serial debug interface protocol
//-------------------------------------------------------
// DBG_UART -> Enable UART (8N1) debug interface
// DBG_I2C -> Enable I2C debug interface
//-------------------------------------------------------
`define DBG_UART
//`define DBG_I2C
 
 
//-------------------------------------------------------
// Enable the I2C broadcast address
//-------------------------------------------------------
// For multicore systems, a common I2C broadcast address
// can be given to all oMSP cores in order to
// synchronously RESET, START, STOP, or STEP all CPUs
// at once with a single I2C command.
// If you have a single openMSP430 in your system,
// this option can stay commented-out.
//-------------------------------------------------------
//`define DBG_I2C_BROADCAST
 
 
//-------------------------------------------------------
// Number of hardware breakpoint/watchpoint units
// (each unit contains two hardware addresses available
// for breakpoints or watchpoints):
249,7 → 272,7
 
// Custom Program memory (enabled with PMEM_SIZE_CUSTOM)
`define PMEM_CUSTOM_AWIDTH 10
`define PMEM_CUSTOM_SIZE 2028
`define PMEM_CUSTOM_SIZE 2048
 
// Custom Data memory (enabled with DMEM_SIZE_CUSTOM)
`define DMEM_CUSTOM_AWIDTH 6
775,13 → 798,6
`define DBG_DCO_FREQ 20000000
`define DBG_UART_CNT ((`DBG_DCO_FREQ/`DBG_UART_BAUD)-1)
 
// Debug interface selection
// `define DBG_UART -> Enable UART (8N1) debug interface
// `define DBG_JTAG -> DON'T UNCOMMENT, NOT SUPPORTED
//
`define DBG_UART
//`define DBG_JTAG
 
// Debug interface input synchronizer
`define SYNC_DBG_UART_RXD
 
798,14 → 814,13
// Check configuration
`ifdef DBG_EN
`ifdef DBG_UART
`ifdef DBG_JTAG
CONFIGURATION ERROR: JTAG AND UART DEBUG INTERFACE ARE BOTH ENABLED
`ifdef DBG_I2C
CONFIGURATION ERROR: I2C AND UART DEBUG INTERFACE ARE BOTH ENABLED
`endif
`else
`ifdef DBG_JTAG
CONFIGURATION ERROR: JTAG INTERFACE NOT SUPPORTED
`ifdef DBG_I2C
`else
CONFIGURATION ERROR: JTAG OR UART DEBUG INTERFACE SHOULD BE ENABLED
CONFIGURATION ERROR: I2C OR UART DEBUG INTERFACE SHOULD BE ENABLED
`endif
`endif
`endif
/openMSP430.v
48,94 → 48,109
module openMSP430 (
 
// OUTPUTs
aclk, // ASIC ONLY: ACLK
aclk_en, // FPGA ONLY: ACLK enable
dbg_freeze, // Freeze peripherals
dbg_uart_txd, // Debug interface: UART TXD
dco_enable, // ASIC ONLY: Fast oscillator enable
dco_wkup, // ASIC ONLY: Fast oscillator wake-up (asynchronous)
dmem_addr, // Data Memory address
dmem_cen, // Data Memory chip enable (low active)
dmem_din, // Data Memory data input
dmem_wen, // Data Memory write enable (low active)
irq_acc, // Interrupt request accepted (one-hot signal)
lfxt_enable, // ASIC ONLY: Low frequency oscillator enable
lfxt_wkup, // ASIC ONLY: Low frequency oscillator wake-up (asynchronous)
mclk, // Main system clock
per_addr, // Peripheral address
per_din, // Peripheral data input
per_we, // Peripheral write enable (high active)
per_en, // Peripheral enable (high active)
pmem_addr, // Program Memory address
pmem_cen, // Program Memory chip enable (low active)
pmem_din, // Program Memory data input (optional)
pmem_wen, // Program Memory write enable (low active) (optional)
puc_rst, // Main system reset
smclk, // ASIC ONLY: SMCLK
smclk_en, // FPGA ONLY: SMCLK enable
aclk, // ASIC ONLY: ACLK
aclk_en, // FPGA ONLY: ACLK enable
dbg_freeze, // Freeze peripherals
dbg_i2c_sda_out, // Debug interface: I2C SDA OUT
dbg_uart_txd, // Debug interface: UART TXD
dco_enable, // ASIC ONLY: Fast oscillator enable
dco_wkup, // ASIC ONLY: Fast oscillator wake-up (asynchronous)
dmem_addr, // Data Memory address
dmem_cen, // Data Memory chip enable (low active)
dmem_din, // Data Memory data input
dmem_wen, // Data Memory write enable (low active)
irq_acc, // Interrupt request accepted (one-hot signal)
lfxt_enable, // ASIC ONLY: Low frequency oscillator enable
lfxt_wkup, // ASIC ONLY: Low frequency oscillator wake-up (asynchronous)
mclk, // Main system clock
per_addr, // Peripheral address
per_din, // Peripheral data input
per_we, // Peripheral write enable (high active)
per_en, // Peripheral enable (high active)
pmem_addr, // Program Memory address
pmem_cen, // Program Memory chip enable (low active)
pmem_din, // Program Memory data input (optional)
pmem_wen, // Program Memory write enable (low active) (optional)
puc_rst, // Main system reset
smclk, // ASIC ONLY: SMCLK
smclk_en, // FPGA ONLY: SMCLK enable
 
// INPUTs
cpu_en, // Enable CPU code execution (asynchronous and non-glitchy)
dbg_en, // Debug interface enable (asynchronous and non-glitchy)
dbg_uart_rxd, // Debug interface: UART RXD (asynchronous)
dco_clk, // Fast oscillator (fast clock)
dmem_dout, // Data Memory data output
irq, // Maskable interrupts
lfxt_clk, // Low frequency oscillator (typ 32kHz)
nmi, // Non-maskable interrupt (asynchronous)
per_dout, // Peripheral data output
pmem_dout, // Program Memory data output
reset_n, // Reset Pin (low active, asynchronous and non-glitchy)
scan_enable, // ASIC ONLY: Scan enable (active during scan shifting)
scan_mode, // ASIC ONLY: Scan mode
wkup // ASIC ONLY: System Wake-up (asynchronous and non-glitchy)
cpu_en, // Enable CPU code execution (asynchronous and non-glitchy)
dbg_en, // Debug interface enable (asynchronous and non-glitchy)
dbg_i2c_addr, // Debug interface: I2C Address
dbg_i2c_broadcast, // Debug interface: I2C Broadcast Address (for multicore systems)
dbg_i2c_scl, // Debug interface: I2C SCL
dbg_i2c_sda_in, // Debug interface: I2C SDA IN
dbg_uart_rxd, // Debug interface: UART RXD (asynchronous)
dco_clk, // Fast oscillator (fast clock)
dmem_dout, // Data Memory data output
irq, // Maskable interrupts
lfxt_clk, // Low frequency oscillator (typ 32kHz)
nmi, // Non-maskable interrupt (asynchronous)
per_dout, // Peripheral data output
pmem_dout, // Program Memory data output
reset_n, // Reset Pin (low active, asynchronous and non-glitchy)
scan_enable, // ASIC ONLY: Scan enable (active during scan shifting)
scan_mode, // ASIC ONLY: Scan mode
wkup // ASIC ONLY: System Wake-up (asynchronous and non-glitchy)
);
 
// PARAMETERs
//============
parameter INST_NR = 8'h00; // Current oMSP instance number (for multicore systems)
parameter TOTAL_NR = 8'h00; // Total number of oMSP instances-1 (for multicore systems)
 
// OUTPUTs
//=========
output aclk; // ASIC ONLY: ACLK
output aclk_en; // FPGA ONLY: ACLK enable
output dbg_freeze; // Freeze peripherals
output dbg_uart_txd; // Debug interface: UART TXD
output dco_enable; // ASIC ONLY: Fast oscillator enable
output dco_wkup; // ASIC ONLY: Fast oscillator wake-up (asynchronous)
output [`DMEM_MSB:0] dmem_addr; // Data Memory address
output dmem_cen; // Data Memory chip enable (low active)
output [15:0] dmem_din; // Data Memory data input
output [1:0] dmem_wen; // Data Memory write enable (low active)
output [13:0] irq_acc; // Interrupt request accepted (one-hot signal)
output lfxt_enable; // ASIC ONLY: Low frequency oscillator enable
output lfxt_wkup; // ASIC ONLY: Low frequency oscillator wake-up (asynchronous)
output mclk; // Main system clock
output [13:0] per_addr; // Peripheral address
output [15:0] per_din; // Peripheral data input
output [1:0] per_we; // Peripheral write enable (high active)
output per_en; // Peripheral enable (high active)
output [`PMEM_MSB:0] pmem_addr; // Program Memory address
output pmem_cen; // Program Memory chip enable (low active)
output [15:0] pmem_din; // Program Memory data input (optional)
output [1:0] pmem_wen; // Program Memory write enable (low active) (optional)
output puc_rst; // Main system reset
output smclk; // ASIC ONLY: SMCLK
output smclk_en; // FPGA ONLY: SMCLK enable
//============
output aclk; // ASIC ONLY: ACLK
output aclk_en; // FPGA ONLY: ACLK enable
output dbg_freeze; // Freeze peripherals
output dbg_i2c_sda_out; // Debug interface: I2C SDA OUT
output dbg_uart_txd; // Debug interface: UART TXD
output dco_enable; // ASIC ONLY: Fast oscillator enable
output dco_wkup; // ASIC ONLY: Fast oscillator wake-up (asynchronous)
output [`DMEM_MSB:0] dmem_addr; // Data Memory address
output dmem_cen; // Data Memory chip enable (low active)
output [15:0] dmem_din; // Data Memory data input
output [1:0] dmem_wen; // Data Memory write enable (low active)
output [13:0] irq_acc; // Interrupt request accepted (one-hot signal)
output lfxt_enable; // ASIC ONLY: Low frequency oscillator enable
output lfxt_wkup; // ASIC ONLY: Low frequency oscillator wake-up (asynchronous)
output mclk; // Main system clock
output [13:0] per_addr; // Peripheral address
output [15:0] per_din; // Peripheral data input
output [1:0] per_we; // Peripheral write enable (high active)
output per_en; // Peripheral enable (high active)
output [`PMEM_MSB:0] pmem_addr; // Program Memory address
output pmem_cen; // Program Memory chip enable (low active)
output [15:0] pmem_din; // Program Memory data input (optional)
output [1:0] pmem_wen; // Program Memory write enable (low active) (optional)
output puc_rst; // Main system reset
output smclk; // ASIC ONLY: SMCLK
output smclk_en; // FPGA ONLY: SMCLK enable
 
 
// INPUTs
//=========
input cpu_en; // Enable CPU code execution (asynchronous and non-glitchy)
input dbg_en; // Debug interface enable (asynchronous and non-glitchy)
input dbg_uart_rxd; // Debug interface: UART RXD (asynchronous)
input dco_clk; // Fast oscillator (fast clock)
input [15:0] dmem_dout; // Data Memory data output
input [13:0] irq; // Maskable interrupts
input lfxt_clk; // Low frequency oscillator (typ 32kHz)
input nmi; // Non-maskable interrupt (asynchronous and non-glitchy)
input [15:0] per_dout; // Peripheral data output
input [15:0] pmem_dout; // Program Memory data output
input reset_n; // Reset Pin (active low, asynchronous and non-glitchy)
input scan_enable; // ASIC ONLY: Scan enable (active during scan shifting)
input scan_mode; // ASIC ONLY: Scan mode
input wkup; // ASIC ONLY: System Wake-up (asynchronous and non-glitchy)
//============
input cpu_en; // Enable CPU code execution (asynchronous and non-glitchy)
input dbg_en; // Debug interface enable (asynchronous and non-glitchy)
input [6:0] dbg_i2c_addr; // Debug interface: I2C Address
input [6:0] dbg_i2c_broadcast; // Debug interface: I2C Broadcast Address (for multicore systems)
input dbg_i2c_scl; // Debug interface: I2C SCL
input dbg_i2c_sda_in; // Debug interface: I2C SDA IN
input dbg_uart_rxd; // Debug interface: UART RXD (asynchronous)
input dco_clk; // Fast oscillator (fast clock)
input [15:0] dmem_dout; // Data Memory data output
input [13:0] irq; // Maskable interrupts
input lfxt_clk; // Low frequency oscillator (typ 32kHz)
input nmi; // Non-maskable interrupt (asynchronous and non-glitchy)
input [15:0] per_dout; // Peripheral data output
input [15:0] pmem_dout; // Program Memory data output
input reset_n; // Reset Pin (active low, asynchronous and non-glitchy)
input scan_enable; // ASIC ONLY: Scan enable (active during scan shifting)
input scan_mode; // ASIC ONLY: Scan mode
input wkup; // ASIC ONLY: System Wake-up (asynchronous and non-glitchy)
 
 
 
169,7 → 184,9
wire mclk_enable;
wire mclk_wkup;
wire [31:0] cpu_id;
 
wire [7:0] cpu_nr_inst = INST_NR;
wire [7:0] cpu_nr_total = TOTAL_NR;
wire [15:0] eu_mab;
wire [15:0] eu_mdb_in;
wire [15:0] eu_mdb_out;
431,6 → 448,8
.wdtifg_sw_set(wdtifg_sw_set), // Watchdog-timer interrupt flag software set
// INPUTs
.cpu_nr_inst (cpu_nr_inst), // Current oMSP instance number
.cpu_nr_total (cpu_nr_total), // Total number of oMSP instances-1
.mclk (mclk), // Main system clock
.nmi (nmi), // Non-maskable interrupt (asynchronous)
.nmi_acc (nmi_acc), // Non-Maskable interrupt request accepted
530,49 → 549,57
omsp_dbg dbg_0 (
 
// OUTPUTs
.dbg_freeze (dbg_freeze), // Freeze peripherals
.dbg_halt_cmd (dbg_halt_cmd), // Halt CPU command
.dbg_mem_addr (dbg_mem_addr), // Debug address for rd/wr access
.dbg_mem_dout (dbg_mem_dout), // Debug unit data output
.dbg_mem_en (dbg_mem_en), // Debug unit memory enable
.dbg_mem_wr (dbg_mem_wr), // Debug unit memory write
.dbg_reg_wr (dbg_reg_wr), // Debug unit CPU register write
.dbg_cpu_reset(dbg_cpu_reset), // Reset CPU from debug interface
.dbg_uart_txd (dbg_uart_txd), // Debug interface: UART TXD
.dbg_cpu_reset (dbg_cpu_reset), // Reset CPU from debug interface
.dbg_freeze (dbg_freeze), // Freeze peripherals
.dbg_halt_cmd (dbg_halt_cmd), // Halt CPU command
.dbg_i2c_sda_out (dbg_i2c_sda_out), // Debug interface: I2C SDA OUT
.dbg_mem_addr (dbg_mem_addr), // Debug address for rd/wr access
.dbg_mem_dout (dbg_mem_dout), // Debug unit data output
.dbg_mem_en (dbg_mem_en), // Debug unit memory enable
.dbg_mem_wr (dbg_mem_wr), // Debug unit memory write
.dbg_reg_wr (dbg_reg_wr), // Debug unit CPU register write
.dbg_uart_txd (dbg_uart_txd), // Debug interface: UART TXD
// INPUTs
.cpu_en_s (cpu_en_s), // Enable CPU code execution (synchronous)
.cpu_id (cpu_id), // CPU ID
.dbg_clk (dbg_clk), // Debug unit clock
.dbg_en_s (dbg_en_s), // Debug interface enable (synchronous)
.dbg_halt_st (dbg_halt_st), // Halt/Run status from CPU
.dbg_mem_din (dbg_mem_din), // Debug unit Memory data input
.dbg_reg_din (dbg_reg_din), // Debug unit CPU register data input
.dbg_rst (dbg_rst), // Debug unit reset
.dbg_uart_rxd (dbg_uart_rxd), // Debug interface: UART RXD (asynchronous)
.decode_noirq (decode_noirq), // Frontend decode instruction
.eu_mab (eu_mab), // Execution-Unit Memory address bus
.eu_mb_en (eu_mb_en), // Execution-Unit Memory bus enable
.eu_mb_wr (eu_mb_wr), // Execution-Unit Memory bus write transfer
.eu_mdb_in (eu_mdb_in), // Memory data bus input
.eu_mdb_out (eu_mdb_out), // Memory data bus output
.exec_done (exec_done), // Execution completed
.fe_mb_en (fe_mb_en), // Frontend Memory bus enable
.fe_mdb_in (fe_mdb_in), // Frontend Memory data bus input
.pc (pc), // Program counter
.puc_pnd_set (puc_pnd_set) // PUC pending set for the serial debug interface
.cpu_en_s (cpu_en_s), // Enable CPU code execution (synchronous)
.cpu_id (cpu_id), // CPU ID
.cpu_nr_inst (cpu_nr_inst), // Current oMSP instance number
.cpu_nr_total (cpu_nr_total), // Total number of oMSP instances-1
.dbg_clk (dbg_clk), // Debug unit clock
.dbg_en_s (dbg_en_s), // Debug interface enable (synchronous)
.dbg_halt_st (dbg_halt_st), // Halt/Run status from CPU
.dbg_i2c_addr (dbg_i2c_addr), // Debug interface: I2C Address
.dbg_i2c_broadcast (dbg_i2c_broadcast), // Debug interface: I2C Broadcast Address (for multicore systems)
.dbg_i2c_scl (dbg_i2c_scl), // Debug interface: I2C SCL
.dbg_i2c_sda_in (dbg_i2c_sda_in), // Debug interface: I2C SDA IN
.dbg_mem_din (dbg_mem_din), // Debug unit Memory data input
.dbg_reg_din (dbg_reg_din), // Debug unit CPU register data input
.dbg_rst (dbg_rst), // Debug unit reset
.dbg_uart_rxd (dbg_uart_rxd), // Debug interface: UART RXD (asynchronous)
.decode_noirq (decode_noirq), // Frontend decode instruction
.eu_mab (eu_mab), // Execution-Unit Memory address bus
.eu_mb_en (eu_mb_en), // Execution-Unit Memory bus enable
.eu_mb_wr (eu_mb_wr), // Execution-Unit Memory bus write transfer
.eu_mdb_in (eu_mdb_in), // Memory data bus input
.eu_mdb_out (eu_mdb_out), // Memory data bus output
.exec_done (exec_done), // Execution completed
.fe_mb_en (fe_mb_en), // Frontend Memory bus enable
.fe_mdb_in (fe_mdb_in), // Frontend Memory data bus input
.pc (pc), // Program counter
.puc_pnd_set (puc_pnd_set) // PUC pending set for the serial debug interface
);
 
`else
assign dbg_freeze = ~cpu_en_s;
assign dbg_halt_cmd = 1'b0;
assign dbg_mem_addr = 16'h0000;
assign dbg_mem_dout = 16'h0000;
assign dbg_mem_en = 1'b0;
assign dbg_mem_wr = 2'b00;
assign dbg_reg_wr = 1'b0;
assign dbg_cpu_reset = 1'b0;
assign dbg_uart_txd = 1'b0;
assign dbg_cpu_reset = 1'b0;
assign dbg_freeze = ~cpu_en_s;
assign dbg_halt_cmd = 1'b0;
assign dbg_i2c_sda_out = 1'b1;
assign dbg_mem_addr = 16'h0000;
assign dbg_mem_dout = 16'h0000;
assign dbg_mem_en = 1'b0;
assign dbg_mem_wr = 2'b00;
assign dbg_reg_wr = 1'b0;
assign dbg_uart_txd = 1'b1;
`endif
 
/openMSP430_undefines.v
46,6 → 46,9
//----------------------------------------------------------------------------
 
// Program Memory sizes
`ifdef PMEM_SIZE_CUSTOM
`undef PMEM_SIZE_CUSTOM
`endif
`ifdef PMEM_SIZE_59_KB
`undef PMEM_SIZE_59_KB
`endif
90,6 → 93,9
`endif
 
// Data Memory sizes
`ifdef DMEM_SIZE_CUSTOM
`undef DMEM_SIZE_CUSTOM
`endif
`ifdef DMEM_SIZE_32_KB
`undef DMEM_SIZE_32_KB
`endif
145,7 → 151,36
// ADVANCED SYSTEM CONFIGURATION (FOR EXPERIENCED USERS)
//----------------------------------------------------------------------------
 
// Custom user version number
`ifdef USER_VERSION
`undef USER_VERSION
`endif
 
// Include/Exclude Watchdog timer
`ifdef WATCHDOG
`undef WATCHDOG
`endif
 
// Include/Exclude Non-Maskable-Interrupt support
`ifdef NMI
`undef NMI
`endif
 
// Input synchronizers
`ifdef SYNC_NMI
`undef SYNC_NMI
`endif
`ifdef SYNC_CPU_EN
`undef SYNC_CPU_EN
`endif
`ifdef SYNC_DBG_EN
`undef SYNC_DBG_EN
`endif
 
// Peripheral Memory Space:
`ifdef PER_SIZE_CUSTOM
`undef PER_SIZE_CUSTOM
`endif
`ifdef PER_SIZE_32_KB
`undef PER_SIZE_32_KB
`endif
173,25 → 208,24
`undef DBG_RST_BRK_EN
`endif
 
// Custom user version number
`ifdef USER_VERSION
`undef USER_VERSION
`endif
 
// Include/Exclude Watchdog timer
`ifdef WATCHDOG
`undef WATCHDOG
//----------------------------------------------------------------------------
// EXPERT SYSTEM CONFIGURATION ( !!!! EXPERTS ONLY !!!! )
//----------------------------------------------------------------------------
 
// Serial Debug interface protocol
`ifdef DBG_UART
`undef DBG_UART
`endif
`ifdef DBG_I2C
`undef DBG_I2C
`endif
 
// Include/Exclude Non-Maskable-Interrupt support
`ifdef NMI
`undef NMI
// Enable the I2C broadcast address
`ifdef DBG_I2C_BROADCAST
`undef DBG_I2C_BROADCAST
`endif
 
//----------------------------------------------------------------------------
// EXPERT SYSTEM CONFIGURATION ( !!!! EXPERTS ONLY !!!! )
//----------------------------------------------------------------------------
 
// Number of hardware breakpoint units
`ifdef DBG_HWBRK_0
`undef DBG_HWBRK_0
211,19 → 245,13
`undef DBG_HWBRK_RANGE
`endif
 
// Input synchronizers
`ifdef SYNC_CPU_EN
`undef SYNC_CPU_EN
`endif
`ifdef SYNC_DBG_EN
`undef SYNC_DBG_EN
`endif
`ifdef SYNC_DBG_UART_RXD
`undef SYNC_DBG_UART_RXD
`endif
`ifdef SYNC_NMI
`undef SYNC_NMI
`endif
// Custom Program/Data and Peripheral Memory Spaces
`undef PMEM_CUSTOM_AWIDTH
`undef PMEM_CUSTOM_SIZE
`undef DMEM_CUSTOM_AWIDTH
`undef DMEM_CUSTOM_SIZE
`undef PER_CUSTOM_AWIDTH
`undef PER_CUSTOM_SIZE
 
// ASIC version
`ifdef ASIC
259,6 → 287,9
`ifdef WATCHDOG_MUX
`undef WATCHDOG_MUX
`endif
`ifdef WATCHDOG_NOMUX_ACLK
`undef WATCHDOG_NOMUX_ACLK
`endif
 
// MCLK: Clock divider
`ifdef MCLK_DIVIDER
280,11 → 311,6
`undef CPUOFF_EN
`endif
 
// LOW POWER MODE: OSCOFF
`ifdef OSCOFF_EN
`undef OSCOFF_EN
`endif
 
// LOW POWER MODE: SCG0
`ifdef SCG0_EN
`undef SCG0_EN
295,7 → 321,12
`undef SCG1_EN
`endif
 
// LOW POWER MODE: OSCOFF
`ifdef OSCOFF_EN
`undef OSCOFF_EN
`endif
 
 
//==========================================================================//
//==========================================================================//
//==========================================================================//
705,13 → 736,10
`undef DBG_UART_CNT
`endif
 
// Debug interface selection
`ifdef DBG_UART
`undef DBG_UART
// Debug interface input synchronizer
`ifdef SYNC_DBG_UART_RXD
`undef SYNC_DBG_UART_RXD
`endif
`ifdef DBG_JTAG
`undef DBG_JTAG
`endif
 
// Enable/Disable the hardware breakpoint RANGE mode
`ifdef HWBRK_RANGE

powered by: WebSVN 2.1.0

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