1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-01-08 16:30:35 +00:00

Minor code cleaning.

This commit is contained in:
mmajoral 2018-04-30 11:59:56 +02:00
parent 512bf3f4cf
commit 4433c0c6be
5 changed files with 52 additions and 54 deletions

View File

@ -1,4 +1,3 @@
/*! /*!
* \file gps_l1_ca_pcps_acquisition_fpga.cc * \file gps_l1_ca_pcps_acquisition_fpga.cc
* \brief Adapts a PCPS acquisition block to an FPGA AcquisitionInterface * \brief Adapts a PCPS acquisition block to an FPGA AcquisitionInterface
@ -59,21 +58,21 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
long fs_in_deprecated = configuration_->property("GNSS-SDR.internal_fs_hz", 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); long fs_in = configuration_->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
acq_parameters.fs_in = fs_in_; acq_parameters.fs_in = fs_in;
if_ = configuration_->property(role + ".if", 0); long ifreq = configuration_->property(role + ".if", 0);
acq_parameters.freq = if_; acq_parameters.freq = ifreq;
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; if (FLAGS_doppler_max != 0) doppler_max_ = FLAGS_doppler_max;
acq_parameters.doppler_max = doppler_max_; acq_parameters.doppler_max = doppler_max_;
sampled_ms_ = configuration_->property(role + ".coherent_integration_time_ms", 1); unsigned int sampled_ms = configuration_->property(role + ".coherent_integration_time_ms", 1);
acq_parameters.sampled_ms = sampled_ms_; acq_parameters.sampled_ms = sampled_ms;
code_length_ = static_cast<unsigned int>(std::round(static_cast<double>(fs_in_) / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS))); unsigned int code_length = static_cast<unsigned int>(std::round(static_cast<double>(fs_in) / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)));
// The FPGA can only use FFT lengths that are a power of two. // The FPGA can only use FFT lengths that are a power of two.
float nbits = ceilf(log2f((float) code_length_)); float nbits = ceilf(log2f((float) code_length));
unsigned int nsamples_total = pow(2, nbits); unsigned int nsamples_total = pow(2, nbits);
vector_length_ = nsamples_total * sampled_ms_; unsigned int vector_length = nsamples_total * sampled_ms;
unsigned int select_queue_Fpga = configuration_->property(role + ".select_queue_Fpga",0); unsigned int select_queue_Fpga = configuration_->property(role + ".select_queue_Fpga",0);
acq_parameters.select_queue_Fpga = select_queue_Fpga; acq_parameters.select_queue_Fpga = select_queue_Fpga;
std::string default_device_name = "/dev/uio0"; std::string default_device_name = "/dev/uio0";
@ -85,20 +84,18 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
// compute all the GPS L1 PRN Codes (this is done only once upon the class constructor in order to avoid re-computing the PRN codes every time // compute all the GPS L1 PRN Codes (this is done only once upon the class constructor in order to avoid re-computing the PRN codes every time
// a channel is assigned) // a channel is assigned)
// Direct FFT gr::fft::fft_complex* fft_if = new gr::fft::fft_complex(vector_length, true); // Direct FFT
gr::fft::fft_complex* fft_if = new gr::fft::fft_complex(vector_length_, true); // allocate memory to compute all the PRNs and compute all the possible codes
// allocate memory to compute all the PRNs
// 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
gr_complex* fft_codes_padded = static_cast<gr_complex*>(volk_gnsssdr_malloc(nsamples_total * sizeof(gr_complex), volk_gnsssdr_get_alignment())); gr_complex* 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 d_all_fft_codes_ = new lv_16sc_t[nsamples_total * 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 = 1; 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 // fill in zero padding
for (int s=code_length_;s<nsamples_total;s++) for (int s=code_length;s<nsamples_total;s++)
{ {
code[s] = 0; code[s] = 0;
} }
@ -120,14 +117,16 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
} }
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 < nsamples_total; 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 + nsamples_total * (PRN -1)] = lv_16sc_t(static_cast<int>(floor(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>(floor(fft_codes_padded[i].real() * (pow(2, 7) - 1) / max)),
static_cast<int>(floor(fft_codes_padded[i].imag() * (pow(2, 7) - 1) / max))); static_cast<int>(floor(fft_codes_padded[i].imag() * (pow(2, 7) - 1) / max)));
} }
} }
acq_parameters.all_fft_codes = d_all_fft_codes;
//acq_parameters //acq_parameters
acq_parameters.all_fft_codes = d_all_fft_codes_;
// temporary buffers that we can delete // temporary buffers that we can delete
delete[] code; delete[] code;
delete fft_if; delete fft_if;
@ -144,8 +143,7 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
GpsL1CaPcpsAcquisitionFpga::~GpsL1CaPcpsAcquisitionFpga() GpsL1CaPcpsAcquisitionFpga::~GpsL1CaPcpsAcquisitionFpga()
{ {
//delete[] code_; delete[] d_all_fft_codes_;
delete[] d_all_fft_codes;
} }

View File

@ -37,10 +37,10 @@
#ifndef GNSS_SDR_GPS_L1_CA_PCPS_ACQUISITION_FPGA_H_ #ifndef GNSS_SDR_GPS_L1_CA_PCPS_ACQUISITION_FPGA_H_
#define GNSS_SDR_GPS_L1_CA_PCPS_ACQUISITION_FPGA_H_ #define GNSS_SDR_GPS_L1_CA_PCPS_ACQUISITION_FPGA_H_
#include <string>
#include "acquisition_interface.h" #include "acquisition_interface.h"
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "pcps_acquisition_fpga.h" #include "pcps_acquisition_fpga.h"
#include <string>
class ConfigurationInterface; class ConfigurationInterface;
@ -137,19 +137,14 @@ public:
private: private:
ConfigurationInterface* configuration_; ConfigurationInterface* configuration_;
pcps_acquisition_fpga_sptr acquisition_fpga_; pcps_acquisition_fpga_sptr acquisition_fpga_;
unsigned int vector_length_;
unsigned int code_length_;
unsigned int channel_; unsigned int channel_;
unsigned int doppler_max_; unsigned int doppler_max_;
unsigned int doppler_step_; unsigned int doppler_step_;
unsigned int sampled_ms_;
long fs_in_;
long if_;
Gnss_Synchro* gnss_synchro_; Gnss_Synchro* gnss_synchro_;
std::string role_; std::string role_;
unsigned int in_streams_; unsigned int in_streams_;
unsigned int out_streams_; unsigned int out_streams_;
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
}; };

View File

@ -38,11 +38,10 @@
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
*/ */
#include "pcps_acquisition_fpga.h"
#include "GPS_L1_CA.h" // for GPS_TWO_PI
#include "GLONASS_L1_L2_CA.h" // for GLONASS_TWO_PI"
#include <glog/logging.h> #include <glog/logging.h>
#include <gnuradio/io_signature.h> #include <gnuradio/io_signature.h>
#include "pcps_acquisition_fpga.h"
using google::LogMessage; using google::LogMessage;
@ -175,12 +174,10 @@ void pcps_acquisition_fpga::set_active(bool active)
// initialize acquisition algorithm // initialize acquisition algorithm
uint32_t indext = 0; uint32_t indext = 0;
float magt = 0.0; float magt = 0.0;
int effective_fft_size = d_fft_size;
float fft_normalization_factor = static_cast<float>(d_fft_size) * static_cast<float>(d_fft_size); float fft_normalization_factor = static_cast<float>(d_fft_size) * static_cast<float>(d_fft_size);
d_input_power = 0.0; d_input_power = 0.0;
d_mag = 0.0; d_mag = 0.0;
//d_well_count++;
DLOG(INFO) << "Channel: " << d_channel DLOG(INFO) << "Channel: " << d_channel
<< " , doing acquisition of satellite: " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN << " , doing acquisition of satellite: " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN
@ -208,9 +205,9 @@ void pcps_acquisition_fpga::set_active(bool active)
{ {
d_mag = magt; d_mag = magt;
input_power_all = d_input_power / (effective_fft_size - 1); input_power_all = d_input_power / (d_fft_size - 1);
input_power_computed = (d_input_power - d_mag) / (effective_fft_size - 1); input_power_computed = (d_input_power - d_mag) / (d_fft_size - 1);
d_input_power = (d_input_power - d_mag) / (effective_fft_size - 1); d_input_power = (d_input_power - d_mag) / (d_fft_size - 1);
d_gnss_synchro->Acq_delay_samples = static_cast<double>(indext % acq_parameters.samples_per_code); d_gnss_synchro->Acq_delay_samples = static_cast<double>(indext % acq_parameters.samples_per_code);
d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler); d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler);

View File

@ -56,9 +56,10 @@
#ifndef GNSS_SDR_PCPS_ACQUISITION_FPGA_H_ #ifndef GNSS_SDR_PCPS_ACQUISITION_FPGA_H_
#define GNSS_SDR_PCPS_ACQUISITION_FPGA_H_ #define GNSS_SDR_PCPS_ACQUISITION_FPGA_H_
#include "gnss_synchro.h"
#include <gnuradio/block.h> #include <gnuradio/block.h>
#include "fpga_acquisition.h" #include "fpga_acquisition.h"
#include "gnss_synchro.h"
typedef struct typedef struct
{ {
@ -69,10 +70,8 @@ typedef struct
long fs_in; long fs_in;
int samples_per_ms; int samples_per_ms;
int samples_per_code; int samples_per_code;
std::string dump_filename;
unsigned int select_queue_Fpga; unsigned int select_queue_Fpga;
std::string device_name; std::string device_name;
unsigned int code_length;
lv_16sc_t *all_fft_codes; // memory that contains all the code ffts lv_16sc_t *all_fft_codes; // memory that contains all the code ffts
} pcpsconf_fpga_t; } pcpsconf_fpga_t;
@ -118,8 +117,6 @@ private:
Gnss_Synchro* d_gnss_synchro; Gnss_Synchro* d_gnss_synchro;
std::shared_ptr<fpga_acquisition> acquisition_fpga; std::shared_ptr<fpga_acquisition> acquisition_fpga;
public: public:
~pcps_acquisition_fpga(); ~pcps_acquisition_fpga();

View File

@ -33,9 +33,6 @@
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
*/ */
#include "fpga_acquisition.h"
#include "gps_sdr_signal_processing.h"
// libraries used by the GIPO // libraries used by the GIPO
#include <fcntl.h> #include <fcntl.h>
#include <sys/mman.h> #include <sys/mman.h>
@ -46,9 +43,23 @@
// GPS L1 // GPS L1
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#define PAGE_SIZE 0x10000 #include "fpga_acquisition.h"
#include "gps_sdr_signal_processing.h"
#define PAGE_SIZE 0x10000 // default page size for the multicorrelator memory map
#define MAX_PHASE_STEP_RAD 0.999999999534339 // 1 - pow(2,-31); #define MAX_PHASE_STEP_RAD 0.999999999534339 // 1 - pow(2,-31);
#define TEST_REG_SANITY_CHECK 0x55AA #define RESET_ACQUISITION 2 // command to reset the multicorrelator
#define LAUNCH_ACQUISITION 1 // command to launch the multicorrelator
#define TEST_REG_SANITY_CHECK 0x55AA // value to check the presence of the test register (to detect the hw)
#define LOCAL_CODE_CLEAR_MEM 0x10000000 // command to clear the internal memory of the multicorrelator
#define MEM_LOCAL_CODE_WR_ENABLE 0x0C000000 // command to enable the ENA and WR pins of the internal memory of the multicorrelator
#define POW_2_2 4 // 2^2 (used for the conversion of floating point numbers to integers)
#define POW_2_29 536870912 // 2^29 (used for the conversion of floating point numbers to integers)
#define SELECT_LSB 0x00FF // value to select the least significant byte
#define SELECT_MSB 0XFF00 // value to select the most significant byte
#define SELECT_16_BITS 0xFFFF // value to select 16 bits
#define SHL_8_BITS 256 // value used to shift a value 8 bits to the left
bool fpga_acquisition::init() bool fpga_acquisition::init()
{ {
@ -144,14 +155,14 @@ void fpga_acquisition::fpga_configure_acquisition_local_code(lv_16sc_t fft_local
unsigned int k, tmp, tmp2; unsigned int k, tmp, tmp2;
unsigned int fft_data; unsigned int fft_data;
// clear memory address counter // clear memory address counter
d_map_base[4] = 0x10000000; d_map_base[4] = LOCAL_CODE_CLEAR_MEM;
// write local code // 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 & SELECT_LSB) | ((tmp2 * SHL_8_BITS) & SELECT_MSB); // put together the real part and the imaginary part
fft_data = 0x0C000000 | (local_code & 0xFFFF); fft_data = MEM_LOCAL_CODE_WR_ENABLE | (local_code & SELECT_16_BITS);
d_map_base[4] = fft_data; d_map_base[4] = fft_data;
} }
} }
@ -162,7 +173,7 @@ void fpga_acquisition::run_acquisition(void)
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 // launch the acquisition process
d_map_base[6] = 1; // writing anything to reg 6 launches the acquisition process d_map_base[6] = LAUNCH_ACQUISITION; // writing anything to reg 6 launches the acquisition process
int irq_count; int irq_count;
ssize_t nb; ssize_t nb;
@ -201,8 +212,8 @@ void fpga_acquisition::set_phase_step(unsigned int doppler_index)
{ {
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 * POW_2_2; // * 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 * (POW_2_29)); // * 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;
} }
@ -243,5 +254,5 @@ void fpga_acquisition::close_device()
void fpga_acquisition::reset_acquisition(void) void fpga_acquisition::reset_acquisition(void)
{ {
d_map_base[6] = 2; // writing a 2 to d_map_base[6] resets the multicorrelator d_map_base[6] = RESET_ACQUISITION; // writing a 2 to d_map_base[6] resets the multicorrelator
} }