bug_fixes_integration_tx
David Michaeli 2023-02-22 10:42:41 +02:00
rodzic ecfd56782f
commit c78e4b760a
11 zmienionych plików z 254 dodań i 348 usunięć

Wyświetl plik

@ -0,0 +1,88 @@
from PySimpleGUI.PySimpleGUI import Canvas, Column
from PySimpleGUI import Window, WIN_CLOSED, Slider, Button, theme, Text, Radio, Image, InputText, Canvas
import numpy as np
import matplotlib.pyplot as plt
import time
import SoapySDR
from SoapySDR import SOAPY_SDR_RX, SOAPY_SDR_TX, SOAPY_SDR_CS16
"""
Build a dictionaly of parameters
"""
def MakeParameters():
params = { "DriverName": "HermonSDR",
"RxChannel": 0,
"NumOfComplexSample": 4*16384,
"RxFrequencyHz": 915e6,
"UseAGC": True,
"Gain": 50.0,
"RXBandwidth": 0.02e6,
#"Frontend": "TX/RX ANT2 LNA-Bypass"}
"Frontend": "TX/RX ANT2"}
return params
"""
Setup the RX channel
"""
def SetupReceiver(sdr, params):
# Gain mode
sdr.setGainMode(SOAPY_SDR_RX, params["RxChannel"], params["UseAGC"])
# Set RX gain (if not using AGC)
sdr.setGain(SOAPY_SDR_RX, params["RxChannel"], params["Gain"])
# Rx Frequency
sdr.setFrequency(SOAPY_SDR_RX, params["RxChannel"], params["RxFrequencyHz"])
# Rx BW
sdr.setBandwidth(SOAPY_SDR_RX, params["RxChannel"], params["RXBandwidth"])
# Frontend select
sdr.setAntenna(SOAPY_SDR_RX, params["RxChannel"], params["Frontend"])
# Make the stream
return sdr.setupStream(SOAPY_SDR_RX, SOAPY_SDR_CS16, [params["RxChannel"]]) # Setup data stream
"""
Main
"""
if __name__ == "__main__":
print("HermonSDR Sampling Test")
params = MakeParameters()
# Memory buffers
samples = np.empty(2 * params["NumOfComplexSample"], np.int16)
# Initialize Soapy
sdr = SoapySDR.Device(dict(driver=params["DriverName"]))
rxStream = SetupReceiver(sdr, params=params)
sdr.activateStream(rxStream)
# Read samples into buffer
for ii in range(1,10):
sr = sdr.readStream(rxStream, [samples], params["NumOfComplexSample"], timeoutUs=int(5e6))
rc = sr.ret
if (rc != params["NumOfComplexSample"]):
print("Error Reading Samples from Device (error code = %d)!" % rc)
exit
# convert to float complex
I = samples[::2].astype(np.float32)
Q = samples[1::2].astype(np.float32)
complexFloatSamples = I + 1j*Q
#for k in range(len(I)):
# if I[k] > 30 or I[k] < -30:
# print(I[k])
# plot samples
fig = plt.figure()
plt.plot(I)
plt.plot(Q)
plt.show()
print("Goodbye")

Wyświetl plik

@ -0,0 +1,80 @@
# PySimpleGUI
from PySimpleGUI.PySimpleGUI import Canvas, Column
from PySimpleGUI import Window, WIN_CLOSED, Slider, Button, theme, Text, Radio, Image, InputText, Canvas
# Numpy
import matplotlib.pyplot as plt
from matplotlib.backends.backend_tkagg import FigureCanvasTkAgg, NavigationToolbar2Tk
import numpy as np
from numpy.lib.arraypad import pad
# System
import time
# Soapy
import SoapySDR
from SoapySDR import SOAPY_SDR_RX, SOAPY_SDR_TX, SOAPY_SDR_CS16
def setup_receiver(sdr, channel, freq_hz):
use_agc = False # Use or don't use the AGC
# The wide channel parameters
sdr.setGainMode(SOAPY_SDR_RX, channel, use_agc) # Set the gain mode
sdr.setGain(SOAPY_SDR_RX, channel, 0) # Set the gain
sdr.setFrequency(SOAPY_SDR_RX, channel, freq_hz) # Tune the LO
sdr.setBandwidth(SOAPY_SDR_RX, channel, 2500e5)
rx_stream = sdr.setupStream(SOAPY_SDR_RX, SOAPY_SDR_CS16, [channel]) # Setup data stream
return rx_stream
def update_receiver_freq(sdr, stream, channel, freq_hz):
sdr.setFrequency(SOAPY_SDR_RX, channel, freq_hz)
##
## GLOBAL AREA
##
# Data and Source Configuration
rx_chan = 0
N = 16384 # Number of complex samples per transfer
rx_buff = np.empty(2 * N, np.int16) # Create memory buffer for data stream
freq = 915e6
# Initialize Soapy
sdr = SoapySDR.Device(dict(driver="HermonSDR"))
rx_stream = setup_receiver(sdr, rx_chan, freq)
sdr.activateStream(rx_stream)
sr = sdr.readStream(rx_stream, [rx_buff], N, timeoutUs=int(5e6))
# Make sure that the proper number of samples was read
rc = sr.ret
if (rc != N):
print("Error Reading Samples from Device (error code = %d)!" % rc)
exit
s_real = rx_buff[::2].astype(np.float32)
s_imag = -rx_buff[1::2].astype(np.float32)
x = s_real + 1j*s_imag
## PSD
Fs = 4e6
#N = 2048
#x = x[0:N] # we will only take the FFT of the first 1024 samples, see text below
x = x * np.hamming(len(x)) # apply a Hamming window
PSD = (np.abs(np.fft.fft(x))/N)**2
PSD_log = 10.0*np.log10(PSD)
PSD_shifted = np.fft.fftshift(PSD_log)
center_freq = freq
f = np.arange(Fs/-2.0, Fs/2.0, Fs/N) # start, stop, step. centered around 0 Hz
#f += center_freq # now add center frequency
fig = plt.figure()
plt.plot(f, PSD_shifted)
plt.show()
fig = plt.figure()
plt.plot(s_real)
plt.plot(s_imag)
plt.show()

Wyświetl plik

@ -1,5 +1,7 @@
module complex_fifo #( parameter ADDR_WIDTH = 10,
parameter DATA_WIDTH = 16 )
module complex_fifo #(
parameter ADDR_WIDTH = 10,
parameter DATA_WIDTH = 16
)
(
input wire wr_rst_b_i,
input wire wr_clk_i,

Wyświetl plik

@ -22,15 +22,15 @@
# specifying clock constraints without needing the Python API.
# For the iCE40 UltraPlus (iCE40LP1K-QN84) Breakout Board
# For the iCE40 (iCE40LP1K-QN84)
#set_frequency i_glob_clock 125
#set_frequency w_clock_sys 64
#set_frequency smi_ctrl_ins.soe_and_reset 16
#set_frequency i_smi_swe_srw 16
set_frequency lvds_clock_buf 64
#set_frequency i_sck 5
#set_frequency i_glob_clock 125
#set_frequency w_clock_sys 64
#set_frequency smi_ctrl_ins.soe_and_reset 16
#set_frequency i_smi_swe_srw 16
set_frequency lvds_clock_buf 64
#set_frequency i_sck 5
# CLOCK
set_io i_glob_clock A29

Wyświetl plik

@ -1,30 +1,33 @@
module io_ctrl( input i_rst_b,
input i_sys_clk, // FPGA Clock
module io_ctrl
(
input i_rst_b,
input i_sys_clk, // FPGA Clock
input [4:0] i_ioc,
input [7:0] i_data_in,
output reg [7:0] o_data_out,
input i_cs,
input i_fetch_cmd,
input i_load_cmd,
input [4:0] i_ioc,
input [7:0] i_data_in,
output reg [7:0] o_data_out,
input i_cs,
input i_fetch_cmd,
input i_load_cmd,
// Digital interfaces
input i_button,
input [3:0] i_config,
output o_led0,
output o_led1,
output [7:0] o_pmod,
// Digital interfaces
input i_button,
input [3:0] i_config,
output o_led0,
output o_led1,
output [7:0] o_pmod,
// Analog interfaces
output o_mixer_fm,
output o_rx_h_tx_l,
output o_rx_h_tx_l_b,
output o_tr_vc1,
output o_tr_vc1_b,
output o_tr_vc2,
output o_shdn_tx_lna,
output o_shdn_rx_lna,
output o_mixer_en );
// Analog interfaces
output o_mixer_fm,
output o_rx_h_tx_l,
output o_rx_h_tx_l_b,
output o_tr_vc1,
output o_tr_vc1_b,
output o_tr_vc2,
output o_shdn_tx_lna,
output o_shdn_rx_lna,
output o_mixer_en
);
//=========================================================================

Wyświetl plik

@ -54,7 +54,7 @@ module lvds_rx
if (i_ddr_data == modem_i_sync) begin
r_state_if <= state_i_phase;
o_fifo_data <= {30'b000000000000000000000000000000, i_ddr_data};
r_sync_input <= i_sync_input;
r_sync_input <= i_sync_input; // mark the sync input for this sample
end
r_phase_count <= 3'b111;
o_fifo_push <= 1'b0;
@ -93,91 +93,3 @@ module lvds_rx
end
endmodule
/*
module lvds_rx (input i_rst_b,
input i_ddr_clk,
input [1:0] i_ddr_data,
input i_fifo_full,
output o_fifo_write_clk,
output o_fifo_push,
output reg [31:0] o_fifo_data,
input i_sync_input,
output [1:0] o_debug_state );
// Internal FSM States
localparam
state_idle = 3'b00,
state_i_phase = 3'b01,
state_q_phase = 3'b11;
// Modem sync symbols
localparam
modem_i_sync = 3'b10,
modem_q_sync = 3'b01;
// Internal Registers
reg [1:0] r_state_if;
reg [3:0] r_phase_count;
assign o_debug_state = r_state_if;
// Initial conditions
initial begin
r_state_if = state_idle;
r_phase_count = 4'd15;
end
// Global Assignments
assign o_fifo_write_clk = i_ddr_clk;
// Main Process
// Data structure from the modem:
// [S'10'] [13'I] ['0'] [S'01'] [13'Q] ['0']
// Data structure with out sync 's'
// ['10'] [I] ['0'] ['01'] [Q] ['s']
always @(posedge i_ddr_clk or negedge i_rst_b)
begin
if (i_rst_b == 1'b0) begin
r_state_if <= state_idle;
r_phase_count <= 4'd15;
o_fifo_push <= 1'b0;
end else begin
case (r_state_if)
state_idle: begin
if (i_ddr_data == modem_i_sync ) begin
r_state_if <= state_i_phase;
end
r_phase_count <= 4'd15;
end
state_i_phase: begin
if (r_phase_count == 4'd8) begin
if (i_ddr_data == modem_q_sync ) begin
r_state_if <= state_q_phase;
end else begin
r_state_if <= state_idle;
end
end
r_phase_count <= r_phase_count - 1;
end
state_q_phase: begin
if (r_phase_count == 4'd1) begin
r_state_if <= state_idle;
end
r_phase_count <= r_phase_count - 1;
end
endcase
o_fifo_data <= {o_fifo_data[29:0], i_ddr_data};
o_fifo_push <= r_phase_count == 4'd0 && ~i_fifo_full;
end
end
endmodule
*/

Wyświetl plik

@ -1,181 +0,0 @@
library IEEE;
use IEEE.STD_LOGIC_1164.ALL;
use IEEE.STD_LOGIC_UNSIGNED.ALL;
use IEEE.NUMERIC_STD.ALL;
library UNISIM;
use UNISIM.VComponents.all;
entity at86rf215_rx_interface is
Port (
reset_n : in STD_LOGIC;
rxd_09_24 : in STD_LOGIC_VECTOR(1 downto 0);
rxclk : in STD_LOGIC; --64 MHz clk from Radio Chip
IQenable : in std_logic;
Isample_o : out std_logic_vector(15 downto 0);
Qsample_o : out std_logic_vector(15 downto 0);
IQValid_o : out std_logic;
rx_bits_o : out std_logic_vector(1 downto 0);
rxclk_o : out std_logic
);
end at86rf215_rx_interface;
architecture Behavioral of at86rf215_rx_interface is
-- differential signals
signal rx_bits : std_logic_vector(1 downto 0) := "00";
signal rx_bits_d : std_logic_vector(1 downto 0) := "00";
--output data
signal I_Sample : std_logic_vector(13 downto 0) := (others=>'0');
signal Q_Sample : std_logic_vector(13 downto 0) := (others=>'0');
-- state variables
signal ibit_counter : std_logic_vector(3 downto 0) := x"0";
signal inc_icntr : std_logic := '0';
signal icntr_ovf : std_logic := '0';
signal qbit_counter : std_logic_vector(3 downto 0) := x"0";
signal inc_qcntr : std_logic := '0';
signal qcntr_ovf : std_logic := '0';
signal ien,qen : std_logic := '0';
constant I_SYNC : std_logic_vector := "10";
constant Q_SYNC : std_logic_vector := "01";
type state_type is (IDLE,ISAMPLE,QSAMPLE);
signal current_state, next_state : state_type := IDLE;
begin
-- debug IO's
rxclk_o <= rxclk;
rx_bits_o <= rx_bits_d;
-- RX FSM
Rx_state_transit : process(reset_n,rxclk)
begin
if(reset_n ='0') then
rx_bits_d <= "00";
current_state <= IDLE;
else
if(rising_edge(rxclk)) then
--rx_bits are swapped, as selectio output bits are somehow shifted
rx_bits_d <= rxd_09_24(0) & rxd_09_24(1);
current_state <= next_state;
end if;
end if;
end process;
Rx_Sampling_FSM : process(current_state,rx_bits_d,icntr_ovf,qcntr_ovf)
begin
inc_icntr <= '0';
inc_qcntr <= '0';
ien <= '0';
qen <= '0';
case current_State is
when IDLE =>
if (IQenable = '1') then
if(rx_bits_d = I_SYNC) then
next_state <= ISAMPLE;
else
next_state <= IDLE;
end if;
end if;
when ISAMPLE =>
if(icntr_ovf = '1') then
if(rx_bits_d = Q_SYNC) then
next_state <= QSAMPLE;
else
next_state <= IDLE;
end if;
else
inc_icntr <= '1';
ien <= '1';
next_state <= ISAMPLE;
end if;
when QSAMPLE =>
if(qcntr_ovf = '1') then
if(rx_bits_d = I_SYNC) then
next_state <= ISAMPLE;
else
next_state <= IDLE;
end if;
else
inc_qcntr <= '1';
qen <= '1';
next_state <= QSAMPLE;
end if;
when others =>
next_state <= IDLE;
end case;
end process;
cntr_proc: process(reset_n,rxclk)
begin
if(reset_n = '0') then
ibit_counter <= x"0";
icntr_ovf <= '0';
qbit_counter <= x"0";
qcntr_ovf <= '0';
else
if(rising_edge(rxclk)) then
if(ien = '1') then
I_Sample <= I_Sample(11 downto 0) & rx_bits_d;
end if;
if(qen = '1') then
Q_Sample <= Q_Sample(11 downto 0) & rx_bits_d;
end if;
if(inc_icntr = '1') then
if(ibit_counter < 6) then
ibit_counter <= ibit_counter + 1;
icntr_ovf <= '0';
else
ibit_counter <= X"0";
icntr_ovf <= '1';
end if;
else
icntr_ovf <= '0';
end if;
if(inc_qcntr = '1') then
if(qbit_counter < 6) then
qbit_counter <= qbit_counter + 1;
qcntr_ovf <= '0';
else
qbit_counter <= X"0";
qcntr_ovf <= '1';
end if;
else
qcntr_ovf <= '0';
end if;
end if;
end if;
end process;
IQ_sample_output_process: process(reset_n,rxclk)
begin
if(reset_n = '0') then
ISample_o <= (others => '0');
QSample_o <= (others => '0');
IQValid_o <= '0';
else
if(rising_edge(rxclk)) then
if(icntr_ovf = '1') then
ISample_o <= I_Sample(13) & I_Sample(13) & I_Sample(13 downto 0);
end if;
if(qcntr_ovf = '1') then
QSample_o <= Q_Sample(13) & Q_Sample(13) & Q_Sample(13 downto 0);
IQValid_o <= '1';
else
IQValid_o <= '0';
end if;
end if;
end if;
end process;
end Behavioral;

Wyświetl plik

@ -1,32 +1,34 @@
module smi_ctrl ( input i_rst_b,
input i_sys_clk, // FPGA Clock
input i_fast_clk,
module smi_ctrl
(
input i_rst_b,
input i_sys_clk, // FPGA Clock
input i_fast_clk,
input [4:0] i_ioc,
input [7:0] i_data_in,
output reg [7:0] o_data_out,
input i_cs,
input i_fetch_cmd,
input i_load_cmd,
input [4:0] i_ioc,
input [7:0] i_data_in,
output reg [7:0] o_data_out,
input i_cs,
input i_fetch_cmd,
input i_load_cmd,
// FIFO INTERFACE
output o_fifo_pull,
input [31:0] i_fifo_pulled_data,
input i_fifo_full,
input i_fifo_empty,
// FIFO INTERFACE
output o_fifo_pull,
input [31:0] i_fifo_pulled_data,
input i_fifo_full,
input i_fifo_empty,
// SMI INTERFACE
input i_smi_soe_se,
input i_smi_swe_srw,
output reg [7:0] o_smi_data_out,
input [7:0] i_smi_data_in,
output o_smi_read_req,
output o_smi_write_req,
input i_smi_test,
output o_channel,
// SMI INTERFACE
input i_smi_soe_se,
input i_smi_swe_srw,
output reg [7:0] o_smi_data_out,
input [7:0] i_smi_data_in,
output o_smi_read_req,
output o_smi_write_req,
input i_smi_test,
output o_channel,
// Errors
output reg o_address_error);
// Errors
output reg o_address_error);

Wyświetl plik

@ -1,20 +1,22 @@
`include "spi_slave.v"
module spi_if ( input i_rst_b, // FPGA Reset
input i_sys_clk, // FPGA Clock
module spi_if
(
input i_rst_b, // FPGA Reset
input i_sys_clk, // FPGA Clock
output reg [4:0] o_ioc,
output reg [7:0] o_data_in, // data that was received over SPI
input [7:0] i_data_out, // data to be sent over the SPI
output reg [3:0] o_cs,
output reg o_fetch_cmd,
output reg o_load_cmd,
output reg [4:0] o_ioc,
output reg [7:0] o_data_in, // data that was received over SPI
input [7:0] i_data_out, // data to be sent over the SPI
output reg [3:0] o_cs,
output reg o_fetch_cmd,
output reg o_load_cmd,
// SPI Interface
input i_spi_sck,
output o_spi_miso,
input i_spi_mosi,
input i_spi_cs_b );
// SPI Interface
input i_spi_sck,
output o_spi_miso,
input i_spi_mosi,
input i_spi_cs_b );
localparam
state_idle = 3'b000,

Wyświetl plik

@ -36,8 +36,6 @@ module sys_ctrl
// MODULE INTERNAL SIGNALS
// -----------------------
reg [3:0] reset_count;
reg reset_cmd;
reg debug_fifo_push;
reg debug_fifo_pull;
reg debug_smi_test;
@ -80,8 +78,6 @@ module sys_ctrl
end
endcase
end
end else begin
reset_cmd <= 1'b0;
end
end

Wyświetl plik

@ -82,7 +82,8 @@ module top( input i_glob_clock,
input i_mosi,
input i_sck,
input i_ss,
output o_miso );
output o_miso
);
//=========================================================================
@ -105,8 +106,6 @@ module top( input i_glob_clock,
//=========================================================================
// INSTANCES
//=========================================================================
// SPI
spi_if spi_if_ins
(
.i_rst_b (i_rst_b),
@ -186,6 +185,9 @@ module top( input i_glob_clock,
//=========================================================================
assign w_clock_sys = r_counter;
//=========================================================================
// CLOCK AND DATA-FLOW
//=========================================================================
always @(posedge i_glob_clock)
begin
if (i_rst_b == 1'b0) begin