1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-12-15 12:40:35 +00:00

Updating FPGA acquisition modules

This commit is contained in:
Javier Arribas 2018-03-02 12:23:10 +01:00
parent dc4c7b9551
commit 288dd481e7
5 changed files with 126 additions and 190 deletions

View File

@ -32,12 +32,10 @@
*/ */
#include "gps_l1_ca_pcps_acquisition_fpga.h" #include "gps_l1_ca_pcps_acquisition_fpga.h"
#include <stdexcept>
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#include "configuration_interface.h" #include "configuration_interface.h"
#include "gnss_sdr_flags.h"
using google::LogMessage; using google::LogMessage;
@ -57,57 +55,46 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
unsigned int nsamples_total; unsigned int nsamples_total;
unsigned int select_queue_Fpga; unsigned int select_queue_Fpga;
std::string device_name; std::string device_name;
configuration_ = configuration; configuration_ = configuration;
std::string default_item_type = "cshort"; std::string default_item_type = "cshort";
std::string default_dump_filename = "./data/acquisition.dat"; std::string default_dump_filename = "./data/acquisition.dat";
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
item_type_ = configuration_->property(role + ".item_type",
item_type_ = configuration_->property(role + ".item_type", default_item_type); default_item_type);
fs_in = configuration_->property("GNSS-SDR.internal_fs_sps", 2048000);
long fs_in_deprecated = configuration_->property("GNSS-SDR.internal_fs_hz", 2048000);
fs_in = configuration_->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
ifreq = configuration_->property(role + ".if", 0); ifreq = configuration_->property(role + ".if", 0);
dump = configuration_->property(role + ".dump", false); dump = configuration_->property(role + ".dump", false);
doppler_max_ = configuration_->property(role + ".doppler_max", 5000); doppler_max_ = configuration_->property(role + ".doppler_max", 5000);
if (FLAGS_doppler_max != 0 ) doppler_max_ = FLAGS_doppler_max; sampled_ms = configuration_->property(
sampled_ms = configuration_->property(role + ".coherent_integration_time_ms", 1); role + ".coherent_integration_time_ms", 1);
// note : the FPGA is implemented according to bit transition flag = 0. Setting bit transition flag to 1 has no effect. // note : the FPGA is implemented according to bit transition flag = 0. Setting bit transition flag to 1 has no effect.
bit_transition_flag = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag = configuration_->property(
role + ".bit_transition_flag", false);
// note : the FPGA is implemented according to use_CFAR_algorithm = 0. Setting use_CFAR_algorithm to 1 has no effect. // note : the FPGA is implemented according to use_CFAR_algorithm = 0. Setting use_CFAR_algorithm to 1 has no effect.
use_CFAR_algorithm_flag = configuration_->property(role + ".use_CFAR_algorithm", false); use_CFAR_algorithm_flag = configuration_->property(
role + ".use_CFAR_algorithm", false);
// note : the FPGA does not use the max_dwells variable. // note : the FPGA does not use the max_dwells variable.
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
dump_filename = configuration_->property(role + ".dump_filename",
dump_filename = configuration_->property(role + ".dump_filename", default_dump_filename); default_dump_filename);
//--- Find number of samples per spreading code ------------------------- //--- Find number of samples per spreading code -------------------------
code_length = round( code_length = round(
fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)); fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
// code length has the same value as d_fft_size // code length has the same value as d_fft_size
float nbits; float nbits;
nbits = ceilf(log2f(code_length)); nbits = ceilf(log2f(code_length));
nsamples_total = pow(2, nbits); nsamples_total = pow(2, nbits);
//vector_length_ = code_length_ * sampled_ms_; //vector_length_ = code_length_ * sampled_ms_;
vector_length_ = nsamples_total * sampled_ms; vector_length_ = nsamples_total * sampled_ms;
// if( bit_transition_flag_ ) // if( bit_transition_flag_ )
// { // {
// vector_length_ *= 2; // vector_length_ *= 2;
// } // }
select_queue_Fpga = configuration_->property(role + ".select_queue_Fpga",
select_queue_Fpga = configuration_->property(role + ".select_queue_Fpga", 0); 0);
std::string default_device_name = "/dev/uio0";
std::string default_device_name = "/dev/uio0"; device_name = configuration_->property(role + ".devicename",
device_name = configuration_->property(role + ".devicename", default_device_name); default_device_name);
if (item_type_.compare("cshort") == 0) if (item_type_.compare("cshort") == 0)
{ {
item_size_ = sizeof(lv_16sc_t); item_size_ = sizeof(lv_16sc_t);
@ -121,10 +108,8 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
} }
else else
{ {
LOG(WARNING) << "item_type configured to " << item_type_ << "but FPGA implementation only accepts cshort"; LOG(FATAL) << item_type_ << " FPGA only accepts chsort";
throw std::invalid_argument( "Wrong input_type configuration. Should be cshort" );
} }
channel_ = 0; channel_ = 0;
threshold_ = 0.0; threshold_ = 0.0;
doppler_step_ = 0; doppler_step_ = 0;
@ -192,7 +177,6 @@ signed int GpsL1CaPcpsAcquisitionFpga::mag()
void GpsL1CaPcpsAcquisitionFpga::init() void GpsL1CaPcpsAcquisitionFpga::init()
{ {
gps_acquisition_fpga_sc_->init(); gps_acquisition_fpga_sc_->init();
set_local_code();
} }
@ -230,7 +214,6 @@ float GpsL1CaPcpsAcquisitionFpga::calculate_threshold(float pfa)
double lambda = double(vector_length_); double lambda = double(vector_length_);
boost::math::exponential_distribution<double> mydist(lambda); boost::math::exponential_distribution<double> mydist(lambda);
float threshold = static_cast<float>(quantile(mydist, val)); float threshold = static_cast<float>(quantile(mydist, val));
return threshold; return threshold;
} }

View File

@ -39,7 +39,10 @@
#include <volk/volk.h> #include <volk/volk.h>
#include <volk_gnsssdr/volk_gnsssdr.h> #include <volk_gnsssdr/volk_gnsssdr.h>
#include "control_message_factory.h" #include "control_message_factory.h"
#include "GPS_L1_CA.h" //GPS_TWO_PI #include "GPS_L1_CA.h"
#include <boost/thread.hpp>
using google::LogMessage; using google::LogMessage;
void wait3(int seconds) void wait3(int seconds)
@ -74,12 +77,13 @@ gps_pcps_acquisition_fpga_sc::gps_pcps_acquisition_fpga_sc(
unsigned int select_queue_Fpga, std::string device_name, bool dump, unsigned int select_queue_Fpga, std::string device_name, bool dump,
std::string dump_filename) : std::string dump_filename) :
gr::block("pcps_acquisition_fpga_sc", //gr::block("pcps_acquisition_fpga_sc",
gr::block("gps_pcps_acquisition_fpga_sc",
gr::io_signature::make(0, 0, sizeof(lv_16sc_t)), gr::io_signature::make(0, 0, sizeof(lv_16sc_t)),
gr::io_signature::make(0, 0, 0)) gr::io_signature::make(0, 0, 0))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0; // SAMPLE COUNTER d_sample_counter = 0; // sample counter
d_active = false; d_active = false;
d_state = 0; d_state = 0;
d_samples_per_code = samples_per_code; d_samples_per_code = samples_per_code;
@ -94,16 +98,13 @@ gps_pcps_acquisition_fpga_sc::gps_pcps_acquisition_fpga_sc(
d_threshold = 0.0; d_threshold = 0.0;
d_doppler_step = 250; d_doppler_step = 250;
d_channel = 0; d_channel = 0;
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = dump_filename;
d_gnss_synchro = 0; d_gnss_synchro = 0;
// instantiate HW accelerator class // instantiate HW accelerator class
acquisition_fpga_8sc = std::make_shared < gps_fpga_acquisition_8sc> acquisition_fpga_8sc = std::make_shared < gps_fpga_acquisition_8sc>
(device_name, vector_length, d_fft_size, nsamples_total, fs_in, freq, sampled_ms, select_queue_Fpga); (device_name, vector_length, d_fft_size, doppler_max, nsamples_total, fs_in, freq, sampled_ms, select_queue_Fpga);
} }
@ -113,7 +114,6 @@ gps_pcps_acquisition_fpga_sc::~gps_pcps_acquisition_fpga_sc()
{ {
d_dump_file.close(); d_dump_file.close();
} }
acquisition_fpga_8sc->free(); acquisition_fpga_8sc->free();
} }
@ -134,14 +134,11 @@ void gps_pcps_acquisition_fpga_sc::init()
d_gnss_synchro->Acq_doppler_hz = 0.0; d_gnss_synchro->Acq_doppler_hz = 0.0;
d_gnss_synchro->Acq_samplestamp_samples = 0; d_gnss_synchro->Acq_samplestamp_samples = 0;
d_mag = 0.0; d_mag = 0.0;
d_num_doppler_bins = ceil( d_num_doppler_bins = ceil(
static_cast<double>(static_cast<int>(d_doppler_max) static_cast<double>(static_cast<int>(d_doppler_max)
- static_cast<int>(-d_doppler_max)) - static_cast<int>(-d_doppler_max))
/ static_cast<double>(d_doppler_step)); / static_cast<double>(d_doppler_step));
//acquisition_fpga_8sc->open_device();
acquisition_fpga_8sc->open_device();
acquisition_fpga_8sc->init(); acquisition_fpga_8sc->init();
} }
@ -167,34 +164,28 @@ void gps_pcps_acquisition_fpga_sc::set_state(int state)
} }
void gps_pcps_acquisition_fpga_sc::set_active(bool active) void gps_pcps_acquisition_fpga_sc::set_active(bool active)
{ {
float temp_peak_to_noise_level = 0.0; float temp_peak_to_noise_level = 0.0;
float peak_to_noise_level = 0.0; float peak_to_noise_level = 0.0;
float input_power; float input_power;
float test_statistics = 0.0; float test_statistics = 0.0;
acquisition_fpga_8sc->block_samples(); // block the samples to run the acquisition this is only necessary for the tests //printf("ACQ : Block samples for PRN %d\n", d_gnss_synchro->PRN);
// acquisition_fpga_8sc->block_samples(); // block the samples to run the acquisition this is only necessary for the tests
d_active = active; d_active = active;
int acquisition_message = -1; //0=STOP_CHANNEL 1=ACQ_SUCCEES 2=ACQ_FAIL int acquisition_message = -1; //0=STOP_CHANNEL 1=ACQ_SUCCEES 2=ACQ_FAIL
d_state = 1; d_state = 1;
// initialize acquisition algorithm // initialize acquisition algorithm
int doppler; int doppler;
uint32_t indext = 0; uint32_t indext = 0;
float magt = 0.0; float magt = 0.0;
//int effective_fft_size = ( d_bit_transition_flag ? d_fft_size/2 : d_fft_size ); //int effective_fft_size = ( d_bit_transition_flag ? d_fft_size/2 : d_fft_size );
int effective_fft_size = d_fft_size; int effective_fft_size = d_fft_size;
//float fft_normalization_factor = static_cast<float>(d_fft_size) * static_cast<float>(d_fft_size);
d_mag = 0.0; d_mag = 0.0;
unsigned int initial_sample; unsigned int initial_sample;
d_well_count++; d_well_count++;
DLOG(INFO) << "Channel: " << d_channel DLOG(INFO) << "Channel: " << d_channel
<< " , doing acquisition of satellite: " << d_gnss_synchro->System << " , doing acquisition of satellite: " << d_gnss_synchro->System
<< " " << d_gnss_synchro->PRN << " ,sample stamp: " << " " << d_gnss_synchro->PRN << " ,sample stamp: "
@ -207,26 +198,20 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
doppler_index++) doppler_index++)
{ {
doppler = -static_cast<int>(d_doppler_max) doppler = -static_cast<int>(d_doppler_max) + d_doppler_step * doppler_index;
+ d_doppler_step * doppler_index;
acquisition_fpga_8sc->set_phase_step(doppler_index); acquisition_fpga_8sc->set_phase_step(doppler_index);
acquisition_fpga_8sc->run_acquisition(); // runs acquisition and waits until it is finished acquisition_fpga_8sc->run_acquisition(); // runs acquisition and waits until it is finished
acquisition_fpga_8sc->read_acquisition_results(&indext, &magt, acquisition_fpga_8sc->read_acquisition_results(&indext, &magt,
&initial_sample, &input_power); &initial_sample, &input_power);
d_sample_counter = initial_sample; d_sample_counter = initial_sample;
temp_peak_to_noise_level = static_cast<float>(magt) / static_cast<float>(input_power); temp_peak_to_noise_level = static_cast<float>(magt) / static_cast<float>(input_power);
if (peak_to_noise_level < temp_peak_to_noise_level) if (peak_to_noise_level < temp_peak_to_noise_level)
{ {
peak_to_noise_level = temp_peak_to_noise_level; peak_to_noise_level = temp_peak_to_noise_level;
d_mag = magt; d_mag = magt;
input_power = (input_power - d_mag) input_power = (input_power - d_mag)
/ (effective_fft_size - 1); / (effective_fft_size - 1);
d_gnss_synchro->Acq_delay_samples = d_gnss_synchro->Acq_delay_samples =
static_cast<double>(indext % d_samples_per_code); static_cast<double>(indext % d_samples_per_code);
d_gnss_synchro->Acq_doppler_hz = d_gnss_synchro->Acq_doppler_hz =
@ -234,14 +219,12 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
d_gnss_synchro->Acq_samplestamp_samples = d_sample_counter; d_gnss_synchro->Acq_samplestamp_samples = d_sample_counter;
test_statistics = d_mag / input_power; test_statistics = d_mag / input_power;
} }
// Record results to file if required // Record results to file if required
if (d_dump) if (d_dump)
{ {
std::stringstream filename; std::stringstream filename;
//std::streamsize n = 2 * sizeof(float) * (d_fft_size); // complex file write //std::streamsize n = 2 * sizeof(float) * (d_fft_size); // complex file write
filename.str(""); filename.str("");
boost::filesystem::path p = d_dump_filename; boost::filesystem::path p = d_dump_filename;
filename << p.parent_path().string() filename << p.parent_path().string()
<< boost::filesystem::path::preferred_separator << boost::filesystem::path::preferred_separator
@ -250,19 +233,21 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
<< d_gnss_synchro->Signal << "_sat_" << d_gnss_synchro->Signal << "_sat_"
<< d_gnss_synchro->PRN << "_doppler_" << doppler << d_gnss_synchro->PRN << "_doppler_" << doppler
<< p.extension().string(); << p.extension().string();
DLOG(INFO) << "Writing ACQ out to " << filename.str(); DLOG(INFO) << "Writing ACQ out to " << filename.str();
d_dump_file.open(filename.str().c_str(), d_dump_file.open(filename.str().c_str(),
std::ios::out | std::ios::binary); std::ios::out | std::ios::binary);
d_dump_file.close(); d_dump_file.close();
} }
} }
//printf("ACQ : unblocking samples for satellite %d\n", d_gnss_synchro->PRN);
// acquisition_fpga_8sc->unblock_samples(); // unblock samples before sending positive or negative acquisition message to let the samples flow when the
// set local code function is called
if (test_statistics > d_threshold) if (test_statistics > d_threshold)
{ {
d_state = 2; // Positive acquisition d_state = 2; // Positive acquisition
// 6.1- Declare positive acquisition using a message port // 6.1- Declare positive acquisition using a message port
DLOG(INFO) << "positive acquisition"; DLOG(INFO) << "positive acquisition";
DLOG(INFO) << "satellite " << d_gnss_synchro->System << " " DLOG(INFO) << "satellite " << d_gnss_synchro->System << " "
@ -274,10 +259,8 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz; DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz;
DLOG(INFO) << "magnitude " << d_mag; DLOG(INFO) << "magnitude " << d_mag;
DLOG(INFO) << "input signal power " << input_power; DLOG(INFO) << "input signal power " << input_power;
d_active = false; d_active = false;
d_state = 0; d_state = 0;
acquisition_message = 1; acquisition_message = 1;
this->message_port_pub(pmt::mp("events"), this->message_port_pub(pmt::mp("events"),
pmt::from_long(acquisition_message)); pmt::from_long(acquisition_message));
@ -285,7 +268,6 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
else else
{ {
d_state = 3; // Negative acquisition d_state = 3; // Negative acquisition
// 6.2- Declare negative acquisition using a message port // 6.2- Declare negative acquisition using a message port
DLOG(INFO) << "negative acquisition"; DLOG(INFO) << "negative acquisition";
DLOG(INFO) << "satellite " << d_gnss_synchro->System << " " DLOG(INFO) << "satellite " << d_gnss_synchro->System << " "
@ -297,25 +279,18 @@ void gps_pcps_acquisition_fpga_sc::set_active(bool active)
DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz; DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz;
DLOG(INFO) << "magnitude " << d_mag; DLOG(INFO) << "magnitude " << d_mag;
DLOG(INFO) << "input signal power " << input_power; DLOG(INFO) << "input signal power " << input_power;
d_active = false; d_active = false;
d_state = 0; d_state = 0;
acquisition_message = 2; acquisition_message = 2;
this->message_port_pub(pmt::mp("events"), this->message_port_pub(pmt::mp("events"),
pmt::from_long(acquisition_message)); pmt::from_long(acquisition_message));
} }
acquisition_fpga_8sc->unblock_samples();
acquisition_fpga_8sc->close_device();
DLOG(INFO) << "Done. Consumed 1 item."; DLOG(INFO) << "Done. Consumed 1 item.";
} }
int gps_pcps_acquisition_fpga_sc::general_work(int noutput_items, int gps_pcps_acquisition_fpga_sc::general_work(int noutput_items,
gr_vector_int &ninput_items, gr_vector_const_void_star &input_items, gr_vector_int &ninput_items __attribute__((unused)), gr_vector_const_void_star &input_items __attribute__((unused)),
gr_vector_void_star &output_items __attribute__((unused))) gr_vector_void_star &output_items __attribute__((unused)))
{ {
// general work not used with the acquisition // general work not used with the acquisition

View File

@ -46,8 +46,8 @@
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
*/ */
#ifndef GNSS_SDR_PCPS_ACQUISITION_FPGA_SC_H_ #ifndef GNSS_SDR_GPS_PCPS_ACQUISITION_FPGA_SC_H_
#define GNSS_SDR_PCPS_ACQUISITION_FPGA_SC_H_ #define GNSS_SDR_GPS_PCPS_ACQUISITION_FPGA_SC_H_
#include <fstream> #include <fstream>
#include <string> #include <string>
@ -57,6 +57,8 @@
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "gps_fpga_acquisition_8sc.h" #include "gps_fpga_acquisition_8sc.h"
#include <boost/thread.hpp>
class gps_pcps_acquisition_fpga_sc; class gps_pcps_acquisition_fpga_sc;
typedef boost::shared_ptr<gps_pcps_acquisition_fpga_sc> gps_pcps_acquisition_fpga_sc_sptr; typedef boost::shared_ptr<gps_pcps_acquisition_fpga_sc> gps_pcps_acquisition_fpga_sc_sptr;
@ -95,7 +97,6 @@ private:
bool bit_transition_flag, bool use_CFAR_algorithm_flag, bool bit_transition_flag, bool use_CFAR_algorithm_flag,
unsigned int select_queue_Fpga, std::string device_name, bool dump, unsigned int select_queue_Fpga, std::string device_name, bool dump,
std::string dump_filename); std::string dump_filename);
int d_samples_per_code; int d_samples_per_code;
float d_threshold; float d_threshold;
unsigned int d_doppler_max; unsigned int d_doppler_max;
@ -105,15 +106,16 @@ private:
unsigned int d_fft_size; unsigned int d_fft_size;
unsigned long int d_sample_counter; unsigned long int d_sample_counter;
unsigned int d_num_doppler_bins; unsigned int d_num_doppler_bins;
Gnss_Synchro *d_gnss_synchro; Gnss_Synchro *d_gnss_synchro;
float d_mag;bool d_bit_transition_flag;bool d_use_CFAR_algorithm_flag; float d_mag;bool d_bit_transition_flag;bool d_use_CFAR_algorithm_flag;
std::ofstream d_dump_file;bool d_active; std::ofstream d_dump_file;
bool d_active;
int d_state;bool d_dump; int d_state;bool d_dump;
unsigned int d_channel; unsigned int d_channel;
std::string d_dump_filename; std::string d_dump_filename;
std::shared_ptr<gps_fpga_acquisition_8sc> acquisition_fpga_8sc; std::shared_ptr<gps_fpga_acquisition_8sc> acquisition_fpga_8sc;
//void set_active2(bool active);
boost::thread d_acq_thread;
public: public:
/*! /*!
@ -155,6 +157,8 @@ public:
* active mode * active mode
* \param active - bool that activates/deactivates the block. * \param active - bool that activates/deactivates the block.
*/ */
void set_active(bool active); void set_active(bool active);
/*! /*!
@ -212,4 +216,4 @@ public:
}; };
#endif /* GNSS_SDR_PCPS_ACQUISITION_SC_H_*/ #endif /* GNSS_SDR_GPS_PCPS_ACQUISITION_SC_H_*/

View File

@ -60,8 +60,10 @@
// logging // logging
#include <glog/logging.h> #include <glog/logging.h>
// volk
#include <volk/volk.h> #include <volk/volk.h>
// GPS L1
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#define PAGE_SIZE 0x10000 #define PAGE_SIZE 0x10000
@ -78,15 +80,15 @@ bool gps_fpga_acquisition_8sc::init()
bool gps_fpga_acquisition_8sc::set_local_code(unsigned int PRN) bool gps_fpga_acquisition_8sc::set_local_code(unsigned int PRN)
{ {
// select the code with the chosen PRN // select the code with the chosen PRN
gps_fpga_acquisition_8sc::fpga_configure_acquisition_local_code( gps_fpga_acquisition_8sc::fpga_configure_acquisition_local_code(
&d_all_fft_codes[d_vector_length * PRN]); &d_all_fft_codes[d_nsamples_total * (PRN - 1)]);
return true; return true;
} }
gps_fpga_acquisition_8sc::gps_fpga_acquisition_8sc(std::string device_name, gps_fpga_acquisition_8sc::gps_fpga_acquisition_8sc(std::string device_name,
unsigned int vector_length, unsigned int nsamples, unsigned int vector_length, unsigned int nsamples,
unsigned int doppler_max,
unsigned int nsamples_total, long fs_in, long freq, unsigned int nsamples_total, long fs_in, long freq,
unsigned int sampled_ms, unsigned select_queue) unsigned int sampled_ms, unsigned select_queue)
{ {
@ -97,48 +99,33 @@ gps_fpga_acquisition_8sc::gps_fpga_acquisition_8sc(std::string device_name,
d_vector_length = vector_length; d_vector_length = vector_length;
d_nsamples = nsamples; // number of samples not including padding d_nsamples = nsamples; // number of samples not including padding
d_select_queue = select_queue; d_select_queue = select_queue;
d_nsamples_total = nsamples_total;
d_doppler_max = 0; d_doppler_max = doppler_max;
d_doppler_step = 0; d_doppler_step = 0;
d_fd = 0; // driver descriptor d_fd = 0; // driver descriptor
d_map_base = nullptr; // driver memory map d_map_base = nullptr; // driver memory map
// compute all the possible code ffts
// Direct FFT // Direct FFT
d_fft_if = new gr::fft::fft_complex(vector_length, true); d_fft_if = new gr::fft::fft_complex(vector_length, true);
// allocate memory to compute all the PRNs // allocate memory to compute all the PRNs
// and compute all the possible codes // and compute all the possible codes
std::complex<float>* code = new std::complex<float>[nsamples_total]; // buffer for the local code std::complex<float>* code = new std::complex<float>[nsamples_total]; // buffer for the local code
std::complex<float> * code_total = new gr_complex[vector_length]; // buffer for the local code repeate every number of ms gr_complex* d_fft_codes_padded = static_cast<gr_complex*>(volk_gnsssdr_malloc(nsamples_total * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
d_all_fft_codes = new lv_16sc_t[nsamples_total * NUM_PRNs]; // memory containing all the possible fft codes for PRN 0 to 32
gr_complex* d_fft_codes_padded = static_cast<gr_complex*>(volk_gnsssdr_malloc(vector_length * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
d_all_fft_codes = new lv_16sc_t[vector_length * NUM_PRNs]; // memory containing all the possible fft codes for PRN 0 to 32
float max; // temporary maxima search float max; // temporary maxima search
for (unsigned int PRN = 1; PRN <= NUM_PRNs; PRN++)
for (unsigned int PRN = 0; PRN < NUM_PRNs; PRN++)
{ {
gps_l1_ca_code_gen_complex_sampled(code, PRN, fs_in, 0); // generate PRN code gps_l1_ca_code_gen_complex_sampled(code, PRN, fs_in, 0); // generate PRN code
// fill in zero padding
for (unsigned int i = 0; i < sampled_ms; i++) for (int s=nsamples;s<nsamples_total;s++)
{ {
memcpy(&(code_total[i * nsamples_total]), code, sizeof(gr_complex) * nsamples_total); // repeat for each ms code[s] = 0;
} }
int offset = 0; int offset = 0;
memcpy(d_fft_if->get_inbuf() + offset, code, sizeof(gr_complex) * nsamples_total); // copy to FFT buffer
memcpy(d_fft_if->get_inbuf() + offset, code_total, sizeof(gr_complex) * vector_length); // copy to FFT buffer
d_fft_if->execute(); // Run the FFT of local code d_fft_if->execute(); // Run the FFT of local code
volk_32fc_conjugate_32fc(d_fft_codes_padded, d_fft_if->get_outbuf(), nsamples_total); // conjugate values
volk_32fc_conjugate_32fc(d_fft_codes_padded, d_fft_if->get_outbuf(), vector_length); // conjugate values
max = 0; // initialize maximum value max = 0; // initialize maximum value
for (unsigned int i = 0; i < nsamples_total; i++) // search for maxima
for (unsigned int i = 0; i < vector_length; i++) // search for maxima
{ {
if (std::abs(d_fft_codes_padded[i].real()) > max) if (std::abs(d_fft_codes_padded[i].real()) > max)
{ {
@ -149,35 +136,65 @@ gps_fpga_acquisition_8sc::gps_fpga_acquisition_8sc(std::string device_name,
max = std::abs(d_fft_codes_padded[i].imag()); max = std::abs(d_fft_codes_padded[i].imag());
} }
} }
for (unsigned int i = 0; i < nsamples_total; i++) // map the FFT to the dynamic range of the fixed point values an copy to buffer containing all FFTs
for (unsigned int i = 0; i < vector_length; i++) // map the FFT to the dynamic range of the fixed point values an copy to buffer containing all FFTs
{ {
d_all_fft_codes[i + vector_length * PRN] = lv_16sc_t(static_cast<int>(d_fft_codes_padded[i].real() * (pow(2, 7) - 1) / max), d_all_fft_codes[i + nsamples_total * (PRN -1)] = lv_16sc_t(static_cast<int>(d_fft_codes_padded[i].real() * (pow(2, 7) - 1) / max),
static_cast<int>(d_fft_codes_padded[i].imag() * (pow(2, 7) - 1) / max)); static_cast<int>(d_fft_codes_padded[i].imag() * (pow(2, 7) - 1) / max));
} }
}
// open communication with HW accelerator
//printf("opening device %s\n", d_device_name.c_str());
if ((d_fd = open(d_device_name.c_str(), O_RDWR | O_SYNC)) == -1)
{
LOG(WARNING) << "Cannot open deviceio" << d_device_name;
//std::cout << "acquisition cannot open deviceio";
} }
d_map_base = reinterpret_cast<volatile unsigned *>(mmap(NULL, PAGE_SIZE,
PROT_READ | PROT_WRITE, MAP_SHARED, d_fd, 0));
if (d_map_base == reinterpret_cast<void*>(-1))
{
LOG(WARNING) << "Cannot map the FPGA acquisition module into user memory";
//std::cout << "acquisition : could not map the fpga registers to the driver" << std::endl;
}
// sanity check : check test register
// we only nee to do this when the class is created
// but the device is not opened yet when the class is create
// because we need to open and close the device every time we run an acquisition
// since the same device may be used by more than one class (gps acquisition, galileo
// acquisition, etc ..)
unsigned writeval = TEST_REGISTER_ACQ_WRITEVAL;
unsigned readval;
readval = gps_fpga_acquisition_8sc::fpga_acquisition_test_register(writeval);
if (writeval != readval)
{
LOG(WARNING) << "Acquisition test register sanity check failed";
//std:: cout << "Acquisition test register sanity check failed" << std::endl;
}
else
{
//std::cout << "Acquisition test register sanity check success !" << std::endl;
LOG(INFO) << "Acquisition test register sanity check success !";
}
gps_fpga_acquisition_8sc::reset_acquisition();
DLOG(INFO) << "Acquisition FPGA class created";
// temporary buffers that we can delete // temporary buffers that we can delete
delete[] code; delete[] code;
delete[] code_total;
delete d_fft_if; delete d_fft_if;
delete[] d_fft_codes_padded; delete[] d_fft_codes_padded;
} }
gps_fpga_acquisition_8sc::~gps_fpga_acquisition_8sc() gps_fpga_acquisition_8sc::~gps_fpga_acquisition_8sc()
{ {
close_device();
delete[] d_all_fft_codes; delete[] d_all_fft_codes;
} }
bool gps_fpga_acquisition_8sc::free() bool gps_fpga_acquisition_8sc::free()
{ {
return true; return true;
} }
unsigned gps_fpga_acquisition_8sc::fpga_acquisition_test_register(unsigned writeval) unsigned gps_fpga_acquisition_8sc::fpga_acquisition_test_register(unsigned writeval)
{ {
unsigned readval; unsigned readval;
@ -189,31 +206,31 @@ unsigned gps_fpga_acquisition_8sc::fpga_acquisition_test_register(unsigned write
return readval; return readval;
} }
void gps_fpga_acquisition_8sc::fpga_configure_acquisition_local_code(lv_16sc_t fft_local_code[]) void gps_fpga_acquisition_8sc::fpga_configure_acquisition_local_code(lv_16sc_t fft_local_code[])
{ {
short int local_code; unsigned short local_code;
unsigned int k, tmp, tmp2; unsigned int k, tmp, tmp2;
unsigned int fft_data;
// clear memory address counter // clear memory address counter
d_map_base[4] = 0x10000000; d_map_base[4] = 0x10000000;
// write local code
for (k = 0; k < d_vector_length; k++) for (k = 0; k < d_vector_length; k++)
{ {
tmp = fft_local_code[k].real(); tmp = fft_local_code[k].real();
tmp2 = fft_local_code[k].imag(); tmp2 = fft_local_code[k].imag();
local_code = (tmp & 0xFF) | ((tmp2 * 256) & 0xFF00); // put together the real part and the imaginary part local_code = (tmp & 0xFF) | ((tmp2 * 256) & 0xFF00); // put together the real part and the imaginary part
d_map_base[4] = 0x0C000000 | (local_code & 0xFFFF); fft_data = 0x0C000000 | (local_code & 0xFFFF);
d_map_base[4] = fft_data;
} }
} }
void gps_fpga_acquisition_8sc::run_acquisition(void) void gps_fpga_acquisition_8sc::run_acquisition(void)
{ {
// enable interrupts // enable interrupts
int reenable = 1; int reenable = 1;
write(d_fd, reinterpret_cast<void*>(&reenable), sizeof(int)); write(d_fd, reinterpret_cast<void*>(&reenable), sizeof(int));
// launch the acquisition process
d_map_base[5] = 0; // writing anything to reg 4 launches the acquisition process d_map_base[6] = 1; // writing anything to reg 6 launches the acquisition process
int irq_count; int irq_count;
ssize_t nb; ssize_t nb;
@ -221,26 +238,24 @@ void gps_fpga_acquisition_8sc::run_acquisition(void)
nb = read(d_fd, &irq_count, sizeof(irq_count)); nb = read(d_fd, &irq_count, sizeof(irq_count));
if (nb != sizeof(irq_count)) if (nb != sizeof(irq_count))
{ {
printf("Tracking_module Read failed to retrieve 4 bytes!\n"); printf("acquisition module Read failed to retrieve 4 bytes!\n");
printf("Tracking_module Interrupt number %d\n", irq_count); printf("acquisition module Interrupt number %d\n", irq_count);
} }
} }
void gps_fpga_acquisition_8sc::configure_acquisition() void gps_fpga_acquisition_8sc::configure_acquisition()
{ {
d_map_base[0] = d_select_queue; d_map_base[0] = d_select_queue;
d_map_base[1] = d_vector_length; d_map_base[1] = d_vector_length;
d_map_base[2] = d_nsamples; d_map_base[2] = d_nsamples;
d_map_base[5] = (int) log2((float) d_vector_length); // log2 FFTlength
} }
void gps_fpga_acquisition_8sc::set_phase_step(unsigned int doppler_index) void gps_fpga_acquisition_8sc::set_phase_step(unsigned int doppler_index)
{ {
float phase_step_rad_real; float phase_step_rad_real;
float phase_step_rad_int_temp; float phase_step_rad_int_temp;
int32_t phase_step_rad_int; int32_t phase_step_rad_int;
int doppler = static_cast<int>(-d_doppler_max) + d_doppler_step * doppler_index; int doppler = static_cast<int>(-d_doppler_max) + d_doppler_step * doppler_index;
float phase_step_rad = GPS_TWO_PI * (d_freq + doppler) / static_cast<float>(d_fs_in); float phase_step_rad = GPS_TWO_PI * (d_freq + doppler) / static_cast<float>(d_fs_in);
// The doppler step can never be outside the range -pi to +pi, otherwise there would be aliasing // The doppler step can never be outside the range -pi to +pi, otherwise there would be aliasing
@ -250,22 +265,19 @@ void gps_fpga_acquisition_8sc::set_phase_step(unsigned int doppler_index)
phase_step_rad_real = phase_step_rad / (GPS_TWO_PI / 2); phase_step_rad_real = phase_step_rad / (GPS_TWO_PI / 2);
// avoid saturation of the fixed point representation in the fpga // avoid saturation of the fixed point representation in the fpga
// (only the positive value can saturate due to the 2's complement representation) // (only the positive value can saturate due to the 2's complement representation)
if (phase_step_rad_real == 1.0) if (phase_step_rad_real >= 1.0)
{ {
phase_step_rad_real = MAX_PHASE_STEP_RAD; phase_step_rad_real = MAX_PHASE_STEP_RAD;
} }
phase_step_rad_int_temp = phase_step_rad_real * 4; // * 2^2 phase_step_rad_int_temp = phase_step_rad_real * 4; // * 2^2
phase_step_rad_int = (int32_t) (phase_step_rad_int_temp * (536870912)); // * 2^29 (in total it makes x2^31 in two steps to avoid the warnings phase_step_rad_int = (int32_t) (phase_step_rad_int_temp * (536870912)); // * 2^29 (in total it makes x2^31 in two steps to avoid the warnings
d_map_base[3] = phase_step_rad_int; d_map_base[3] = phase_step_rad_int;
} }
void gps_fpga_acquisition_8sc::read_acquisition_results(uint32_t* max_index, void gps_fpga_acquisition_8sc::read_acquisition_results(uint32_t* max_index,
float* max_magnitude, unsigned *initial_sample, float *power_sum) float* max_magnitude, unsigned *initial_sample, float *power_sum)
{ {
unsigned readval = 0; unsigned readval = 0;
readval = d_map_base[0];
readval = d_map_base[1]; readval = d_map_base[1];
*initial_sample = readval; *initial_sample = readval;
readval = d_map_base[2]; readval = d_map_base[2];
@ -276,7 +288,6 @@ void gps_fpga_acquisition_8sc::read_acquisition_results(uint32_t* max_index,
*max_index = readval; *max_index = readval;
} }
void gps_fpga_acquisition_8sc::block_samples() void gps_fpga_acquisition_8sc::block_samples()
{ {
d_map_base[14] = 1; // block the samples d_map_base[14] = 1; // block the samples
@ -288,44 +299,6 @@ void gps_fpga_acquisition_8sc::unblock_samples()
d_map_base[14] = 0; // unblock the samples d_map_base[14] = 0; // unblock the samples
} }
void gps_fpga_acquisition_8sc::open_device()
{
if ((d_fd = open(d_device_name.c_str(), O_RDWR | O_SYNC)) == -1)
{
LOG(WARNING) << "Cannot open deviceio" << d_device_name;
}
d_map_base = reinterpret_cast<volatile unsigned *>(mmap(NULL, PAGE_SIZE,
PROT_READ | PROT_WRITE, MAP_SHARED, d_fd, 0));
if (d_map_base == reinterpret_cast<void*>(-1))
{
LOG(WARNING) << "Cannot map the FPGA acquisition module into user memory";
}
// sanity check : check test register
// we only nee to do this when the class is created
// but the device is not opened yet when the class is create
// because we need to open and close the device every time we run an acquisition
// since the same device may be used by more than one class (gps acquisition, galileo
// acquisition, etc ..)
unsigned writeval = TEST_REGISTER_ACQ_WRITEVAL;
unsigned readval;
readval = gps_fpga_acquisition_8sc::fpga_acquisition_test_register(writeval);
if (writeval != readval)
{
LOG(WARNING) << "Acquisition test register sanity check failed";
}
else
{
LOG(INFO) << "Acquisition test register sanity check success !";
}
}
void gps_fpga_acquisition_8sc::close_device() void gps_fpga_acquisition_8sc::close_device()
{ {
unsigned * aux = const_cast<unsigned*>(d_map_base); unsigned * aux = const_cast<unsigned*>(d_map_base);
@ -336,3 +309,7 @@ void gps_fpga_acquisition_8sc::close_device()
close(d_fd); close(d_fd);
} }
void gps_fpga_acquisition_8sc::reset_acquisition(void)
{
d_map_base[6] = 2; // writing a 2 to d_map_base[6] resets the multicorrelator
}

View File

@ -2,7 +2,7 @@
* \file fpga_acquisition_8sc.h * \file fpga_acquisition_8sc.h
* \brief High optimized FPGA vector correlator class for lv_16sc_t (short int complex). * \brief High optimized FPGA vector correlator class for lv_16sc_t (short int complex).
* \authors <ul> * \authors <ul>
* <li> Marc Majoral, 2017. mmajoral(at)cttc.cat * <li> Marc Majoral, 2017. mmajoral(at)cttc.cat
* </ul> * </ul>
* *
* Class that controls and executes a high optimized vector correlator * Class that controls and executes a high optimized vector correlator
@ -33,11 +33,10 @@
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
*/ */
#ifndef GNSS_SDR_FPGA_ACQUISITION_8SC_H_ #ifndef GNSS_GPS_SDR_FPGA_ACQUISITION_8SC_H_
#define GNSS_SDR_FPGA_ACQUISITION_8SC_H_ #define GNSS_GPS_SDR_FPGA_ACQUISITION_8SC_H_
#include <volk_gnsssdr/volk_gnsssdr.h> #include <volk_gnsssdr/volk_gnsssdr.h>
#include <gnuradio/block.h> #include <gnuradio/block.h>
#include <gnuradio/fft/fft.h> #include <gnuradio/fft/fft.h>
@ -49,6 +48,7 @@ class gps_fpga_acquisition_8sc
public: public:
gps_fpga_acquisition_8sc(std::string device_name, gps_fpga_acquisition_8sc(std::string device_name,
unsigned int vector_length, unsigned int nsamples, unsigned int vector_length, unsigned int nsamples,
unsigned int doppler_max,
unsigned int nsamples_total, long fs_in, long freq, unsigned int nsamples_total, long fs_in, long freq,
unsigned int sampled_ms, unsigned select_queue); unsigned int sampled_ms, unsigned select_queue);
~gps_fpga_acquisition_8sc();bool init();bool set_local_code( ~gps_fpga_acquisition_8sc();bool init();bool set_local_code(
@ -60,9 +60,7 @@ public:
unsigned *initial_sample, float *power_sum); unsigned *initial_sample, float *power_sum);
void block_samples(); void block_samples();
void unblock_samples(); void unblock_samples();
void open_device(); //void open_device();
void close_device();
/*! /*!
* \brief Set maximum Doppler grid search * \brief Set maximum Doppler grid search
* \param doppler_max - Maximum Doppler shift considered in the grid search [Hz]. * \param doppler_max - Maximum Doppler shift considered in the grid search [Hz].
@ -71,7 +69,6 @@ public:
{ {
d_doppler_max = doppler_max; d_doppler_max = doppler_max;
} }
/*! /*!
* \brief Set Doppler steps for the grid search * \brief Set Doppler steps for the grid search
* \param doppler_step - Frequency bin of the search grid [Hz]. * \param doppler_step - Frequency bin of the search grid [Hz].
@ -86,23 +83,23 @@ private:
long d_freq; long d_freq;
long d_fs_in; long d_fs_in;
gr::fft::fft_complex* d_fft_if; // function used to run the fft of the local codes gr::fft::fft_complex* d_fft_if; // function used to run the fft of the local codes
// data related to the hardware module and the driver // data related to the hardware module and the driver
int d_fd; // driver descriptor int d_fd; // driver descriptor
volatile unsigned *d_map_base; // driver memory map volatile unsigned *d_map_base; // driver memory map
lv_16sc_t *d_all_fft_codes; // memory that contains all the code ffts lv_16sc_t *d_all_fft_codes; // memory that contains all the code ffts
unsigned int d_vector_length; // number of samples incluing padding and number of ms unsigned int d_vector_length; // number of samples incluing padding and number of ms
unsigned int d_nsamples_total; // number of samples including padding
unsigned int d_nsamples; // number of samples not including padding unsigned int d_nsamples; // number of samples not including padding
unsigned int d_select_queue; // queue selection unsigned int d_select_queue; // queue selection
std::string d_device_name; // HW device name std::string d_device_name; // HW device name
unsigned int d_doppler_max; // max doppler unsigned int d_doppler_max; // max doppler
unsigned int d_doppler_step; // doppler step unsigned int d_doppler_step; // doppler step
// FPGA private functions // FPGA private functions
unsigned fpga_acquisition_test_register(unsigned writeval); unsigned fpga_acquisition_test_register(unsigned writeval);
void fpga_configure_acquisition_local_code(lv_16sc_t fft_local_code[]); void fpga_configure_acquisition_local_code(lv_16sc_t fft_local_code[]);
void configure_acquisition(); void configure_acquisition();
void reset_acquisition(void);
void close_device();
}; };
#endif /* GNSS_SDR_FPGA_MULTICORRELATOR_H_ */ #endif /* GNSS_GPS_SDR_FPGA_MULTICORRELATOR_H_ */