update firmware for tx control signals output on pmod

added dsp flow example
gr-cariboulite_tag_samples
David Michaeli 2024-03-16 12:14:41 +02:00
rodzic 21a97334a7
commit 1b34c568ff
20 zmienionych plików z 27899 dodań i 27836 usunięć

Wyświetl plik

@ -15,7 +15,7 @@ USERSPACE_SMI_DIR="../software/libcariboulite/src/caribou_smi/kernel"
## FUNCTIONS
install() {
local mtu_mult=${1:-6}
local mtu_mult=${1:-16}
local dir_offs=${2:-2}
local ch_offs=${3:-3}

Wyświetl plik

@ -262,11 +262,11 @@ static int set_state(smi_stream_state_en new_state)
if (new_state == smi_stream_tx_channel)
{
ret = transfer_thread_init(inst,DMA_MEM_TO_DEV,stream_smi_write_dma_callback);
ret = transfer_thread_init(inst, DMA_MEM_TO_DEV, stream_smi_write_dma_callback);
}
else
{
ret = transfer_thread_init(inst,DMA_DEV_TO_MEM,stream_smi_read_dma_callback);
ret = transfer_thread_init(inst, DMA_DEV_TO_MEM, stream_smi_read_dma_callback);
}
// if starting the transfer succeeded update the state
@ -329,12 +329,14 @@ static int smi_disable_sync(struct bcm2835_smi_instance *smi_inst)
}
/***************************************************************************/
static void smi_refresh_dma_command(struct bcm2835_smi_instance *smi_inst, int num_transfers)
{
int smics_temp = 0;
//print_smil_registers_ext("refresh 1");
write_smi_reg(smi_inst, SMI_TRANSFER_MULTIPLIER*num_transfers, SMIL); //to avoid stopping and restarting
//print_smil_registers_ext("refresh 2");
// Start the transaction
smics_temp = read_smi_reg(smi_inst, SMICS);
smics_temp |= SMICS_START;
@ -345,7 +347,7 @@ static void smi_refresh_dma_command(struct bcm2835_smi_instance *smi_inst, int n
}
/***************************************************************************/
static int smi_init_programmed_transfer(struct bcm2835_smi_instance *smi_inst, enum dma_transfer_direction dma_dir,int num_transfers)
static int smi_init_programmed_transfer(struct bcm2835_smi_instance *smi_inst, enum dma_transfer_direction dma_dir, int num_transfers)
{
int smics_temp = 0;
int success = 0;
@ -597,6 +599,7 @@ static void stream_smi_read_dma_callback(void *param)
inst->current_read_chunk++;
}
/***************************************************************************/
static void stream_smi_check_and_restart(struct bcm2835_smi_dev_instance *inst)
{
struct bcm2835_smi_instance *smi_inst = inst->smi_inst;
@ -621,6 +624,7 @@ static void stream_smi_check_and_restart(struct bcm2835_smi_dev_instance *inst)
}
}
/***************************************************************************/
static void stream_smi_write_dma_callback(void *param)
{
/* Notify the bottom half that a chunk is ready for user copy */
@ -656,7 +660,7 @@ static void stream_smi_write_dma_callback(void *param)
}
/***************************************************************************/
static struct dma_async_tx_descriptor *stream_smi_dma_init_cyclic( struct bcm2835_smi_instance *inst,
enum dma_transfer_direction dir,
dma_async_tx_callback callback, void*param)
@ -691,14 +695,13 @@ static struct dma_async_tx_descriptor *stream_smi_dma_init_cyclic( struct bcm28
*
***************************************************************************/
int transfer_thread_init(struct bcm2835_smi_dev_instance *inst, enum dma_transfer_direction dir,dma_async_tx_callback callback)
int transfer_thread_init(struct bcm2835_smi_dev_instance *inst, enum dma_transfer_direction dir, dma_async_tx_callback callback)
{
unsigned int errors = 0;
int ret;
int success;
dev_info(inst->dev, "Starting cyclic transfer");
dev_info(inst->dev, "Starting cyclic transfer, dma dir: %d", dir);
inst->transfer_thread_running = true;
/* Disable the peripheral: */
@ -723,6 +726,7 @@ int transfer_thread_init(struct bcm2835_smi_dev_instance *inst, enum dma_transfe
{
spin_unlock(&inst->smi_inst->transaction_lock);
}
inst->current_read_chunk = 0;
inst->counter_missed = 0;
if(!errors)
@ -896,6 +900,7 @@ static ssize_t smi_stream_write_file(struct file *f, const char __user *user_ptr
num_to_push = num_bytes_available > count ? count : num_bytes_available;
ret = kfifo_from_user(&inst->tx_fifo, user_ptr, num_to_push, &actual_copied);
//dev_info(inst->dev, "smi_stream_write_file: pushed %ld bytes of %ld, available was %ld", actual_copied, count, num_bytes_available);
mutex_unlock(&inst->write_lock);
return ret ? ret : (ssize_t)actual_copied;
@ -949,6 +954,7 @@ static dev_t smi_stream_devid;
static struct class *smi_stream_class;
static struct device *smi_stream_dev;
/***************************************************************************/
static int smi_stream_dev_probe(struct platform_device *pdev)
{
int err;

Wyświetl plik

@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 3.2)
project(test_app)
# Find the package using pkg-config
find_package(PkgConfig REQUIRED)
pkg_check_modules(CARIBOULITE REQUIRED cariboulite)
# Add the executable
add_executable(test_app main.cpp)
# Include directories from the cariboulite package
target_include_directories(test_app PRIVATE ${CARIBOULITE_INCLUDE_DIRS})
# Link against the cariboulite library
target_link_libraries(test_app PRIVATE ${CARIBOULITE_LIBRARIES} -lcariboulite)

Wyświetl plik

@ -0,0 +1,165 @@
#ifndef __CIRC_BUFFER_H__
#define __CIRC_BUFFER_H__
#include <string.h>
#include <thread>
#include <mutex>
#include <condition_variable>
#include <chrono>
#include <atomic>
#define IS_POWER_OF_2(x) (!((x) == 0) && !((x) & ((x) - 1)))
#define MIN(x,y) ((x)>(y)?(y):(x))
template <class T>
class circular_buffer {
public:
circular_buffer(size_t size, bool override_write = true, bool block_read = true)
{
max_size_ = size;
if (!IS_POWER_OF_2(max_size_))
{
max_size_ = next_power_of_2(max_size_);
}
buf_ = new T[max_size_];
override_write_ = override_write;
block_read_ = block_read;
}
~circular_buffer()
{
std::unique_lock<std::mutex> lock(mutex_);
delete []buf_;
}
size_t put(const T *data, size_t length)
{
std::lock_guard<std::mutex> lock(mutex_);
if ((max_size_ - size()) < length && override_write_)
{
// pop the amount of data the is needed
tail_ += length - (max_size_ - size());
}
size_t len = MIN(length, max_size_ - head_ + tail_);
auto l = MIN(len, max_size_ - (head_ & (max_size_ - 1)));
memcpy(buf_ + (head_ & (max_size_ - 1)), data, l * sizeof(T));
memcpy(buf_, data + l, (len - l) * sizeof(T));
head_ += len;
if (block_read_)
{
cond_var_.notify_one();
}
return len;
}
size_t get(T *data, size_t length, int timeout_us = 100000)
{
std::unique_lock<std::mutex> lock(mutex_);
if (block_read_)
{
cond_var_.wait_for(lock, std::chrono::microseconds(timeout_us), [&]()
{
// Acquire the lock only if
// we got enough items
return size() >= length;
});
if (size() < length)
{
return 0;
}
}
size_t len = MIN(length, head_ - tail_);
auto l = MIN(len, max_size_ - (tail_ & (max_size_ - 1)));
if (data != NULL)
{
memcpy(data, buf_ + (tail_ & (max_size_ - 1)), l * sizeof(T));
memcpy(data + l, buf_, (len - l) * sizeof(T));
}
tail_ += len;
return len;
}
void put(T item)
{
put(&item, 1);
}
T get()
{
T item;
get(&item, 1);
return item;
}
void reset()
{
std::unique_lock<std::mutex> lock(mutex_);
head_ = tail_ = 0;
}
inline bool empty()
{
return head_ == tail_;
}
inline bool full()
{
return size() == capacity();
}
inline size_t capacity() const
{
return max_size_;
}
size_t size()
{
return (head_ - tail_);
}
void print_buffer()
{
std::unique_lock<std::mutex> lock(mutex_);
size_t t = tail_;
int i = 0;
while (t < head_)
{
printf("%d => %d\n", i++, (int)buf_[t++&(max_size_-1)]);
}
}
private:
uint32_t next_power_of_2 (uint32_t x)
{
uint32_t power = 1;
while(power < x)
{
power <<= 1;
}
return power;
}
private:
std::mutex mutex_;
std::condition_variable cond_var_;
T* buf_;
size_t head_ = 0;
size_t tail_ = 0;
size_t max_size_;
bool override_write_;
bool block_read_;
};
#endif

Wyświetl plik

@ -0,0 +1,235 @@
#include <iostream>
#include <string>
#include <thread>
#include <complex>
#include <cmath>
#include <CaribouLite.hpp> // CPP API for CaribouLite
#include "circular_buffer.hpp" // for circular sample buffer
#define SAMPLE_RATE (4000000)
#define SAMPLE_RATE_CLOSEST (4194304)
#define MAX_FIFO_SECONDS (2)
#define MAX_FIFO_SIZE (SAMPLE_RATE_CLOSEST * MAX_FIFO_SECONDS)
#define TIME_BETWEEN_EPOCHS (5)
#define TIME_OF_SAMPLING (1)
#define RX_CHUNK_SAMPLES (8192)
// ==========================================================================================
// The Application context
// ==========================================================================================
typedef enum
{
app_state_setup = 0,
app_state_sampling = 1,
app_state_sleaping = 2,
} appState_en;
typedef struct
{
// device
CaribouLite* cl;
CaribouLiteRadio* radio;
// operational parameters
bool running;
float freq;
float gain;
size_t num_samples_read_so_far;
size_t epoch;
appState_en state;
bool requested_to_quit;
// buffers & threads
circular_buffer<std::complex<float>> rx_fifo;
thread *dsp_thread;
} appContext_st;
static appContext_st app = {0};
// ==========================================================================================
// General printing and detection of the board
// ==========================================================================================
void printInfo(CaribouLite& cl)
{
std::cout << "Initialized CaribouLite: " << cl.IsInitialized() << std::endl;
std::cout << "API Versions: " << cl.GetApiVersion() << std::endl;
std::cout << "Hardware Serial Number: " << std::hex << cl.GetHwSerialNumber() << std::endl;
std::cout << "System Type: " << cl.GetSystemVersionStr() << std::endl;
std::cout << "Hardware Unique ID: " << cl.GetHwGuid() << std::endl;
}
// Detect boards
void detectBoard()
{
CaribouLite::SysVersion ver;
std::string name;
std::string guid;
if (CaribouLite::DetectBoard(&ver, name, guid))
{
std::cout << "Detected Version: " << CaribouLite::GetSystemVersionStr(ver) << ", Name: " << name << ", GUID: " << guid << std::endl;
}
else
{
std::cout << "Undetected CaribouLite!" << std::endl;
}
}
// Print radio information
void printRadioInformation(CaribouLiteRadio* radio)
{
std::cout << "Radio Name: " << radio->GetRadioName() << " MtuSize: " << std::dec << radio->GetNativeMtuSample() << " Samples" << std::endl;
std::vector<CaribouLiteFreqRange> range = radio->GetFrequencyRange();
std::cout << "Frequency Regions:" << std::endl;
for (int i = 0; i < range.size(); i++)
{
std::cout << " " << i << ": " << range[i] << std::endl;
}
}
// ==========================================================================================
// DSP Thread - The thread that processes data whenever it is available and its
// helper sub-functions
// ==========================================================================================
// Helper DSP function example: calculate the RSSI
float RSSI(const std::complex<float>* signal, size_t num_of_samples)
{
if (num_of_samples == 0)
{
return 0.0f;
}
float sum_of_squares = 0.0f;
for (size_t i = 0; i < num_of_samples && i < num_of_samples; ++i)
{
float vrms = std::norm(signal[i]);
sum_of_squares += vrms * vrms / 100.0;
}
float mean_of_squares = sum_of_squares / num_of_samples;
// Convert RMS value to dBm
return 10 * log10(mean_of_squares);
}
// Consumer thread
void dataConsumerThread(appContext_st* app)
{
std::cout << "Data consumer thread started" << std::endl;
std::complex<float> local_dsp_buffer[RX_CHUNK_SAMPLES * 4];
while (app->running)
{
// get the number of elements in the fifo
size_t num_lements = app.rx_fifo.size();
if (num_lements == 0)
{
std::this_thread::sleep_for(std::chrono::milliseconds(50))
continue;
}
app.rx_fifo.get(local_dsp_buffer, (num_lements>(RX_CHUNK_SAMPLES*4)) ? (RX_CHUNK_SAMPLES * 4) : num_lements);
}
std::cout << "Data consumer thread exitting" << std::endl;
}
// ==========================================================================================
// Asynchronous API for receiving data and managing data flow in RX
// ==========================================================================================
// Rx Callback (async)
void receivedSamples(CaribouLiteRadio* radio, const std::complex<float>* samples, CaribouLiteMeta* sync, size_t num_samples)
{
for (int i = 0; i < 6; i ++)
{
std::cout << "[" << samples[i].real() << ", " << samples[i].imag() << "]";
}
std::cout << std::endl;
// push the received samples in the fifo
app.rx_fifo.put(samples, num_samples);
}
// Main entry
int main ()
{
// try detecting the board before getting the instance
detectBoard();
CaribouLite &cl = CaribouLite::GetInstance();
printInfo(cl);
// get the radios
CaribouLiteRadio *s1g = cl.GetRadioChannel(CaribouLiteRadio::RadioType::S1G);
printRadioInformation(s1g);
// create the application context
app.cl = &cl;
app.radio = s1g;
app.freq = 900000000;
app.gain = 69;
app.rx_fifo = new circular_buffer<std::complex<float>>(MAX_FIFO_SIZE);
app.num_samples_read_so_far = 0;
app.state = app_state_sampling;
app.epoch = 0;
app.requested_to_quit = false;
app.running = true;
app.dsp_thread = new std::thread(dataConsumerThread, &app);
// time management
while (1)
{
switch(app.state)
{
//----------------------------------------------
case app_state_setup:
// an example periodic radio setup stage
app.radio->SetRxGain(app.gain);
app.radio->SetFrequency(app.freq);
app.num_samples_read_so_far = 0;
// and now go directly to the next sampling stage
app.state = app_state_sampling;
break;
//----------------------------------------------
case app_state_sampling:
// start receiving
app.radio->StartReceiving(receivedSamples, RX_CHUNK_SAMPLES);
std::this_thread::sleep_for(std::chrono::milliseconds(TIME_OF_SAMPLING * 1000));
// stop receiving
app.radio->StopReceiving();
app.state = app_state_sleeping;
break;
//----------------------------------------------
case app_state_sleeping:
std::this_thread::sleep_for(std::chrono::milliseconds(TIME_BETWEEN_EPOCHS * 1000));
app.epoch ++;
// either go the next epoch or quit the program
// this is an example flow but other possibilities exist
if (!app.requested_to_quit) app.state = app_state_setup;
else break;
break;
//----------------------------------------------
default:
break;
}
}
// cleanup - done by the creator
app.running = false;
app.dsp_thread->join();
delete app.dsp_thread;
delete app.rx_fifo;
return 0;
}

Wyświetl plik

@ -128,7 +128,6 @@ int main ()
{
std::cout << "Radio: " << hif->GetRadioName() << " Received " << std::dec << ret << " samples"
<< "RSSI: " << RSSI(samples, ret) << " dBm" << std::endl;
std::cout << "Radio: " << s1g->GetRadioName() << " Received " << std::dec << ret << " samples" << std::endl;
}
}

Wyświetl plik

@ -0,0 +1,15 @@
cmake_minimum_required(VERSION 3.2)
project(test_app)
# Find the package using pkg-config
find_package(PkgConfig REQUIRED)
pkg_check_modules(CARIBOULITE REQUIRED cariboulite)
# Add the executable
add_executable(test_app main.cpp)
# Include directories from the cariboulite package
target_include_directories(test_app PRIVATE ${CARIBOULITE_INCLUDE_DIRS})
# Link against the cariboulite library
target_link_libraries(test_app PRIVATE ${CARIBOULITE_LIBRARIES} -lcariboulite)

Wyświetl plik

@ -0,0 +1,141 @@
#include <iostream>
#include <string>
#include <CaribouLite.hpp>
#include <thread>
#include <complex>
#include <cmath>
// Print Board Information
void printInfo(CaribouLite& cl)
{
std::cout << "Initialized CaribouLite: " << cl.IsInitialized() << std::endl;
std::cout << "API Versions: " << cl.GetApiVersion() << std::endl;
std::cout << "Hardware Serial Number: " << std::hex << cl.GetHwSerialNumber() << std::endl;
std::cout << "System Type: " << cl.GetSystemVersionStr() << std::endl;
std::cout << "Hardware Unique ID: " << cl.GetHwGuid() << std::endl;
}
// Detect the board before instantiating it
void detectBoard()
{
CaribouLite::SysVersion ver;
std::string name;
std::string guid;
if (CaribouLite::DetectBoard(&ver, name, guid))
{
std::cout << "Detected Version: " << CaribouLite::GetSystemVersionStr(ver) << ", Name: " << name << ", GUID: " << guid << std::endl;
}
else
{
std::cout << "Undetected CaribouLite!" << std::endl;
}
}
// Rx Callback (async)
void receivedSamples(CaribouLiteRadio* radio, const std::complex<float>* samples, CaribouLiteMeta* sync, size_t num_samples)
{
std::cout << "Radio: " << radio->GetRadioName() << " Received " << std::dec << num_samples << " samples" << std::endl;
}
// Tx buffer generation
void generateCwWave(float freq, float sample_rate, std::complex<float>* samples, size_t num_samples)
{
// angular frequency
float omega = 2.0f * M_PI * freq;
for (int i = 0; i < num_samples; ++i)
{
float t = (float)(i) / sample_rate;
float I = cos(omega * t);
float Q = sin(omega * t);
samples[i] = std::complex<float>(I, Q);
}
}
// Main entry
int main ()
{
// try detecting the board before getting the instance
detectBoard();
// get driver instance - use "CaribouLite&" rather than "CaribouLite" (ref)
CaribouLite &cl = CaribouLite::GetInstance();
// print the info after connecting
printInfo(cl);
// get the radios
CaribouLiteRadio *s1g = cl.GetRadioChannel(CaribouLiteRadio::RadioType::S1G);
CaribouLiteRadio *hif = cl.GetRadioChannel(CaribouLiteRadio::RadioType::HiF);
// write radio information
std::cout << "First Radio Name: " << s1g->GetRadioName() << " MtuSize: " << std::dec << s1g->GetNativeMtuSample() << " Samples" << std::endl;
std::cout << "First Radio Name: " << hif->GetRadioName() << " MtuSize: " << std::dec << hif->GetNativeMtuSample() << " Samples" << std::endl;
std::vector<CaribouLiteFreqRange> range_s1g = s1g->GetFrequencyRange();
std::vector<CaribouLiteFreqRange> range_hif = hif->GetFrequencyRange();
std::cout << "S1G Frequency Regions:" << std::endl;
for (int i = 0; i < range_s1g.size(); i++)
{
std::cout << " " << i << ": " << range_s1g[i] << std::endl;
}
std::cout << "HiF Frequency Regions:" << std::endl;
for (int i = 0; i < range_hif.size(); i++)
{
std::cout << " " << i << ": " << range_hif[i] << std::endl;
}
/********************************************************************************/
/* TRANSMITTING CW */
/********************************************************************************/
/*try
{
s1g->SetFrequency(900000000);
}
catch (...)
{
std::cout << "The specified freq couldn't be used" << std::endl;
}
s1g->SetTxPower(0);
s1g->SetTxBandwidth(1e6);
s1g->SetTxSampleRate(4e6);
s1g->StartTransmittingCw();
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
s1g->StopTransmitting();*/
/********************************************************************************/
/* TRANSMITTING */
/********************************************************************************/
std::complex<float>* samples = new std::complex<float>[s1g->GetNativeMtuSample()];
generateCwWave(500e3, 4e6, samples, s1g->GetNativeMtuSample());
try
{
s1g->SetFrequency(900000000);
}
catch (...)
{
std::cout << "The specified freq couldn't be used" << std::endl;
}
s1g->SetTxPower(0);
s1g->SetTxBandwidth(1e6);
s1g->SetTxSampleRate(4e6);
s1g->StartTransmitting();
for (int i = 0; i < 18; i++)
{
printf("buffer #%d\n", i);
s1g->WriteSamples(samples, s1g->GetNativeMtuSample());
}
std::this_thread::sleep_for(std::chrono::milliseconds(10000));
s1g->StopTransmitting();
delete [] samples;
return 0;
}

Wyświetl plik

@ -5,7 +5,7 @@ pcf_file = ./io.pcf
top.bin:
yosys -p 'synth_ice40 -top top -json $(filename).json -blif $(filename).blif' -p 'ice40_opt' -p 'fsm_opt' $(filename).v
#nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc
nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc --freq 80 --parallel-refine --opt-timing --seed 1 --timing-allow-fail
nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc --freq 80 --parallel-refine --opt-timing --seed 5 --timing-allow-fail
#nextpnr-ice40 --json blinky.json --pcf blinky.pcf --asc blinky.asc --gui
icepack $(filename).asc $(filename).bin

Wyświetl plik

@ -1,15 +1,15 @@
module lvds_tx (
input i_rst_b,
input i_ddr_clk,
input i_rst_b,
input i_ddr_clk,
output reg[1:0] o_ddr_data,
input i_fifo_empty,
output o_fifo_read_clk,
input i_fifo_empty,
output o_fifo_read_clk,
output o_fifo_pull,
input [31:0] i_fifo_data,
input [31:0] i_fifo_data,
input [3:0] i_sample_gap,
input i_tx_state,
input i_sync_input,
input i_tx_state,
input i_sync_input,
input i_debug_lb,
output o_tx_state_bit,
output o_sync_state_bit,
@ -17,28 +17,29 @@ module lvds_tx (
// STATES and PARAMS
localparam
tx_state_sync = 1'b0,
tx_state_tx = 1'b1;
tx_state_sync = 1'b0,
tx_state_tx = 1'b1;
localparam sync_duration_frames = 4'd10; // at least 2.5usec
localparam zero_frame = 32'b00000000_00000000_00000000_00000000;
localparam lb_frame = 32'b10000100_00000011_01110000_01001000;
// Internal Registers
// Internal Registers
reg [3:0] r_sync_count;
wire frame_pull_clock;
wire frame_assign_clock;
reg r_state;
reg [3:0] r_phase_count;
reg [31:0] r_fifo_data;
reg [31:0] r_fifo_data;
reg r_pulled;
reg r_schedule_zero_frame;
// Initial conditions
initial begin
// Initial conditions
initial begin
r_phase_count = 4'd15;
r_fifo_data <= zero_frame;
end
end
assign o_fifo_read_clk = i_ddr_clk;
assign o_fifo_read_clk = i_ddr_clk;
assign o_tx_state_bit = r_state;
assign o_sync_state_bit = 1'b0;
assign o_fifo_pull = r_pulled;
@ -52,15 +53,17 @@ module lvds_tx (
r_phase_count <= r_phase_count - 1;
end
end
// SYNC AND MANAGEMENT
always @(posedge i_ddr_clk) begin
if (i_rst_b == 1'b0) begin
always @(posedge i_ddr_clk)
begin
if (i_rst_b == 1'b0) begin
r_state <= tx_state_sync;
r_pulled <= 1'b0;
r_fifo_data <= zero_frame;
r_sync_count <= sync_duration_frames;
r_schedule_zero_frame <= 1'b0;
end else begin
end else begin
case (r_state)
//----------------------------------------------
tx_state_sync:
@ -83,14 +86,15 @@ module lvds_tx (
r_state <= tx_state_sync;
r_fifo_data <= zero_frame;
end
end else begin
end else begin
r_sync_count <= r_sync_count - 1;
r_schedule_zero_frame <= 1'b1;
//r_fifo_data <= zero_frame;
r_state <= tx_state_sync;
end
end
end
end
//----------------------------------------------
tx_state_tx:
begin
@ -106,7 +110,7 @@ module lvds_tx (
r_sync_count <= sync_duration_frames;
r_fifo_data <= zero_frame;
r_state <= tx_state_sync;
end else begin
end else begin
r_fifo_data <= i_fifo_data;
if (i_sample_gap > 0) begin
r_sync_count <= i_sample_gap;
@ -115,11 +119,11 @@ module lvds_tx (
r_state <= tx_state_tx;
end
end
r_pulled <= 1'b0;
end
end
end
endcase
end
end
end
endmodule

Wyświetl plik

@ -171,7 +171,7 @@ module smi_ctrl
tx_state_third = 2'b10,
tx_state_fourth = 2'b11;
reg [4:0] int_cnt_tx;
reg [12:0] int_cnt_tx;
reg [31:0] r_fifo_pushed_data;
reg [1:0] tx_reg_state;
reg modem_tx_ctrl;
@ -194,7 +194,11 @@ module smi_ctrl
r_fifo_pushed_data <= 32'h00000000;
modem_tx_ctrl <= 1'b0;
cond_tx_ctrl <= 1'b0;
//cnt <= 0;
// DEBUG
int_cnt_tx <= 0;
// END_DEBUG
end else begin
case (tx_reg_state)
//----------------------------------------------
@ -247,10 +251,11 @@ module smi_ctrl
begin
if (i_smi_data_in[7] == 1'b0) begin
o_tx_fifo_pushed_data <= {r_fifo_pushed_data[31:8], i_smi_data_in[6:0], 1'b0};
//o_tx_fifo_pushed_data <= {i_smi_data_in[6:0], 1'b0, r_fifo_pushed_data[15:8], r_fifo_pushed_data[23:16], r_fifo_pushed_data[31:24]};
//o_tx_fifo_pushed_data <= {2'b10, cnt, 1'b1, 2'b01, 13'h3F, 1'b0};
//o_tx_fifo_pushed_data <= {cnt, cnt, 6'b111111};
//cnt <= cnt + 1024;
o_tx_fifo_pushed_data <= {2'b10, int_cnt_tx, 1'b1, 2'b01, 13'h3F, 1'b0};
int_cnt_tx <= int_cnt_tx + 512;
w_fifo_push_trigger <= 1'b1;
o_cond_tx <= cond_tx_ctrl;
end else begin

Plik diff jest za duży Load Diff

Plik binarny nie jest wyświetlany.

Plik diff jest za duży Load Diff

Plik diff jest za duży Load Diff

Wyświetl plik

@ -199,7 +199,7 @@ module top (
.i_config(i_config),
.o_led0 (o_led0),
.o_led1 (o_led1),
.o_pmod (io_pmod[3:0]),
.o_pmod (/*io_pmod[3:0]*/),
// Analog interfaces
.o_mixer_fm(/*o_mixer_fm*/),
@ -213,6 +213,11 @@ module top (
.o_mixer_en(/*o_mixer_en*/)
);
assign io_pmod[0] = ~lvds_clock_buf;
assign io_pmod[1] = w_lvds_tx_d0;
assign io_pmod[2] = w_lvds_tx_d1;
assign io_pmod[3] = i_smi_swe_srw;
//=========================================================================
// CONBINATORIAL ASSIGNMENTS
//=========================================================================
@ -302,7 +307,7 @@ module top (
.IO_STANDARD("SB_LVCMOS"),
) iq_tx_p (
.PACKAGE_PIN(o_iq_tx_p),
.OUTPUT_CLK(lvds_clock_buf),
.OUTPUT_CLK(~lvds_clock_buf),
.D_OUT_0(~w_lvds_tx_d0),
.D_OUT_1(~w_lvds_tx_d1)
);
@ -313,16 +318,34 @@ module top (
.IO_STANDARD("SB_LVCMOS"),
) iq_tx_n (
.PACKAGE_PIN(o_iq_tx_n),
.OUTPUT_CLK(lvds_clock_buf),
.OUTPUT_CLK(~lvds_clock_buf),
.D_OUT_0(w_lvds_tx_d0),
.D_OUT_1(w_lvds_tx_d1)
);
// Non-inverting, P-side clock
SB_IO #(
.PIN_TYPE(6'b011001),
.IO_STANDARD("SB_LVCMOS")
) iq_tx_clk_p (
.PACKAGE_PIN(o_iq_tx_clk_p),
.D_OUT_0(lvds_clock_buf),
);
// Inverting, N-side clock
SB_IO #(
.PIN_TYPE(6'b011001),
.IO_STANDARD("SB_LVCMOS")
) iq_tx_clk_n (
.PACKAGE_PIN(o_iq_tx_clk_n),
.D_OUT_0(~lvds_clock_buf),
);
// Logic on a clock signal is very bad - try to use a dedicated
// SB_IO
assign o_iq_tx_clk_p = lvds_clock_buf;
assign o_iq_tx_clk_n = ~lvds_clock_buf;
//assign o_iq_tx_clk_p = lvds_clock_buf;
//assign o_iq_tx_clk_n = ~lvds_clock_buf;
//=========================================================================
// LVDS RX SIGNAL FROM MODEM

Wyświetl plik

@ -1134,7 +1134,7 @@ int cariboulite_radio_activate_channel(cariboulite_radio_state_st* radio,
{
modem_iq_config.radio09_mode = at86rf215_baseband_mode;
modem_iq_config.radio24_mode = at86rf215_iq_if_mode;
modem_iq_config.clock_skew = at86rf215_iq_clock_data_skew_2_906ns;
modem_iq_config.clock_skew = at86rf215_iq_clock_data_skew_4_906ns;
smi_state = smi_stream_rx_channel_1;
}
@ -1220,6 +1220,7 @@ int cariboulite_radio_activate_channel(cariboulite_radio_state_st* radio,
// apply the state
caribou_smi_set_driver_streaming_state(&radio->sys->smi, smi_stream_tx_channel);
caribou_fpga_set_smi_ctrl_data_direction (&radio->sys->fpga, 0);
//cariboulite_radio_set_modem_state(radio, cariboulite_radio_state_cmd_tx);
}
}