Code cleaning

This commit is contained in:
Carles Fernandez 2018-05-09 13:09:26 +02:00
parent ecc3998d98
commit 7754fc66a6
6 changed files with 88 additions and 200 deletions

View File

@ -34,16 +34,15 @@
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_pcps_acquisition_fpga.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "gps_l1_ca_pcps_acquisition_fpga.h"
#include "gps_sdr_signal_processing.h"
#include "GPS_L1_CA.h"
#include "gps_sdr_signal_processing.h"
#include <gnuradio/fft/fft.h>
#include <glog/logging.h>
#include <new>
#define NUM_PRNs 32
using google::LogMessage;
@ -123,8 +122,7 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
}
}
//acq_parameters
// acq_parameters
acq_parameters.all_fft_codes = d_all_fft_codes_;
// temporary buffers that we can delete
@ -138,7 +136,6 @@ GpsL1CaPcpsAcquisitionFpga::GpsL1CaPcpsAcquisitionFpga(
channel_ = 0;
doppler_step_ = 0;
gnss_synchro_ = 0;
}
@ -212,15 +209,20 @@ void GpsL1CaPcpsAcquisitionFpga::set_state(int state)
acquisition_fpga_->set_state(state);
}
void GpsL1CaPcpsAcquisitionFpga::connect(gr::top_block_sptr top_block)
{
// nothing to connect
if (top_block)
{ // nothing to disconnect
}
}
void GpsL1CaPcpsAcquisitionFpga::disconnect(gr::top_block_sptr top_block)
{
// nothing to disconnect
if (top_block)
{ // nothing to disconnect
}
}

View File

@ -38,10 +38,10 @@
* -------------------------------------------------------------------------
*/
#include "pcps_acquisition_fpga.h"
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "pcps_acquisition_fpga.h"
using google::LogMessage;
@ -52,8 +52,8 @@ pcps_acquisition_fpga_sptr pcps_make_acquisition_fpga(pcpsconf_fpga_t conf_)
pcps_acquisition_fpga::pcps_acquisition_fpga(pcpsconf_fpga_t conf_) : gr::block("pcps_acquisition_fpga",
gr::io_signature::make(0, 0, 0),
gr::io_signature::make(0, 0, 0))
gr::io_signature::make(0, 0, 0),
gr::io_signature::make(0, 0, 0))
{
this->message_port_register_out(pmt::mp("events"));
@ -71,10 +71,8 @@ pcps_acquisition_fpga::pcps_acquisition_fpga(pcpsconf_fpga_t conf_) : gr::block(
d_channel = 0;
d_gnss_synchro = 0;
acquisition_fpga = std::make_shared <fpga_acquisition>
(acq_parameters.device_name, d_fft_size, acq_parameters.doppler_max, acq_parameters.samples_per_ms,
acq_parameters.fs_in, acq_parameters.freq, acq_parameters.sampled_ms, acq_parameters.select_queue_Fpga, acq_parameters.all_fft_codes);
acquisition_fpga = std::make_shared<fpga_acquisition>(acq_parameters.device_name, d_fft_size, acq_parameters.doppler_max, acq_parameters.samples_per_ms,
acq_parameters.fs_in, acq_parameters.freq, acq_parameters.sampled_ms, acq_parameters.select_queue_Fpga, acq_parameters.all_fft_codes);
}
@ -196,9 +194,9 @@ void pcps_acquisition_fpga::set_active(bool active)
int doppler = -static_cast<int>(acq_parameters.doppler_max) + d_doppler_step * doppler_index;
acquisition_fpga->set_phase_step(doppler_index);
acquisition_fpga->run_acquisition(); // runs acquisition and waits until it is finished
acquisition_fpga->run_acquisition(); // runs acquisition and waits until it is finished
acquisition_fpga->read_acquisition_results(&indext, &magt,
&initial_sample, &d_input_power);
&initial_sample, &d_input_power);
d_sample_counter = initial_sample;
if (d_mag < magt)
@ -213,7 +211,7 @@ void pcps_acquisition_fpga::set_active(bool active)
d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler);
d_gnss_synchro->Acq_samplestamp_samples = d_sample_counter;
d_test_statistics = (d_mag / d_input_power); //* correction_factor;
d_test_statistics = (d_mag / d_input_power); //* correction_factor;
}
// In the case of the FPGA the option of dumping the results of the acquisition to a file is not available

View File

@ -36,17 +36,13 @@
* -------------------------------------------------------------------------
*/
//#include <volk_gnsssdr/volk_gnsssdr.h>
#include <glog/logging.h>
#include "gps_sdr_signal_processing.h"
#include "gps_l1_ca_dll_pll_tracking_fpga.h"
#include "configuration_interface.h"
#include "GPS_L1_CA.h"
#include "gnss_sdr_flags.h"
#include "display.h"
#include "gnss_sdr_flags.h"
#include "GPS_L1_CA.h"
#include "gps_sdr_signal_processing.h"
#include <glog/logging.h>
#define NUM_PRNs 32
@ -54,16 +50,13 @@
using google::LogMessage;
GpsL1CaDllPllTrackingFpga::GpsL1CaDllPllTrackingFpga(
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams) :
role_(role), in_streams_(in_streams), out_streams_(out_streams)
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{
dllpllconf_fpga_t trk_param_fpga;
DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ########################
//std::string default_item_type = "gr_complex";
//std::string item_type = configuration->property(role + ".item_type", default_item_type);
int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
int fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
trk_param_fpga.fs_in = fs_in;
@ -136,11 +129,11 @@ GpsL1CaDllPllTrackingFpga::GpsL1CaDllPllTrackingFpga(
trk_param_fpga.device_base = device_base;
//################# PRE-COMPUTE ALL THE CODES #################
d_ca_codes = static_cast<int*>(volk_gnsssdr_malloc(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS*NUM_PRNs) * sizeof(int), volk_gnsssdr_get_alignment()));
d_ca_codes = static_cast<int*>(volk_gnsssdr_malloc(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS * NUM_PRNs) * sizeof(int), volk_gnsssdr_get_alignment()));
for (unsigned int PRN = 1; PRN <= NUM_PRNs; PRN++)
{
gps_l1_ca_code_gen_int(&d_ca_codes[(int(GPS_L1_CA_CODE_LENGTH_CHIPS)) * (PRN - 1)], PRN, 0);
}
{
gps_l1_ca_code_gen_int(&d_ca_codes[(int(GPS_L1_CA_CODE_LENGTH_CHIPS)) * (PRN - 1)], PRN, 0);
}
trk_param_fpga.ca_codes = d_ca_codes;
trk_param_fpga.code_length = GPS_L1_CA_CODE_LENGTH_CHIPS;
@ -148,104 +141,21 @@ GpsL1CaDllPllTrackingFpga::GpsL1CaDllPllTrackingFpga(
tracking_fpga_sc = dll_pll_veml_make_tracking_fpga(trk_param_fpga);
channel_ = 0;
DLOG(INFO) << "tracking(" << tracking_fpga_sc->unique_id() << ")";
/*
//################# CONFIGURATION PARAMETERS ########################
int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
int fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
trk_param_fpga.fs_in = fs_in;
bool dump = configuration->property(role + ".dump", false);
trk_param_fpga.dump = dump;
float pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0);
if (FLAGS_pll_bw_hz != 0.0) pll_bw_hz = static_cast<float>(FLAGS_pll_bw_hz);
trk_param_fpga.pll_bw_hz = pll_bw_hz;
float pll_bw_narrow_hz = configuration->property(role + ".pll_bw_narrow_hz", 20.0);
trk_param_fpga.pll_bw_narrow_hz = pll_bw_narrow_hz;
float dll_bw_narrow_hz = configuration->property(role + ".dll_bw_narrow_hz", 2.0);
trk_param_fpga.dll_bw_narrow_hz = dll_bw_narrow_hz;
float dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
if (FLAGS_dll_bw_hz != 0.0) dll_bw_hz = static_cast<float>(FLAGS_dll_bw_hz);
trk_param_fpga.dll_bw_hz = dll_bw_hz;
float early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
trk_param_fpga.early_late_space_chips = early_late_space_chips;
float early_late_space_narrow_chips = configuration->property(role + ".early_late_space_narrow_chips", 0.5);
trk_param_fpga.early_late_space_narrow_chips = early_late_space_narrow_chips;
std::string default_dump_filename = "./track_ch";
std::string dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
trk_param_fpga.dump_filename = dump_filename;
int vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
trk_param_fpga.vector_length = vector_length;
int symbols_extended_correlator = configuration->property(role + ".extend_correlation_symbols", 1);
if (symbols_extended_correlator < 1)
{
symbols_extended_correlator = 1;
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. extend_correlation_symbols must be bigger than 1. Coherent integration has been set to 1 symbol (1 ms)" << TEXT_RESET << std::endl;
}
else if (symbols_extended_correlator > 20)
{
symbols_extended_correlator = 20;
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. extend_correlation_symbols must be lower than 21. Coherent integration has been set to 20 symbols (20 ms)" << TEXT_RESET << std::endl;
}
trk_param_fpga.extend_correlation_symbols = symbols_extended_correlator;
bool track_pilot = configuration->property(role + ".track_pilot", false);
if (track_pilot)
{
std::cout << TEXT_RED << "WARNING: GPS L1 C/A does not have pilot signal. Data tracking has been enabled" << TEXT_RESET << std::endl;
}
if ((symbols_extended_correlator > 1) and (pll_bw_narrow_hz > pll_bw_hz or dll_bw_narrow_hz > dll_bw_hz))
{
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. PLL or DLL narrow tracking bandwidth is higher than wide tracking one" << TEXT_RESET << std::endl;
}
trk_param_fpga.very_early_late_space_chips = 0.0;
trk_param_fpga.very_early_late_space_narrow_chips = 0.0;
trk_param_fpga.track_pilot = false;
trk_param_fpga.system = 'G';
char sig_[3] = "1C";
std::memcpy(trk_param_fpga.signal, sig_, 3);
// FPGA configuration parameters
std::string default_device_name = "/dev/uio";
std::string device_name = configuration->property(role + ".devicename", default_device_name);
trk_param_fpga.device_name = device_name;
unsigned int device_base = configuration->property(role + ".device_base", 1);
trk_param_fpga.device_base = device_base;
//################# PRE-COMPUTE ALL THE CODES #################
d_ca_codes = static_cast<int*>(volk_gnsssdr_malloc(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS*NUM_PRNs) * sizeof(int), volk_gnsssdr_get_alignment()));
for (unsigned int PRN = 1; PRN <= NUM_PRNs; PRN++)
{
gps_l1_ca_code_gen_int(&d_ca_codes[(int(GPS_L1_CA_CODE_LENGTH_CHIPS)) * (PRN - 1)], PRN, 0);
}
trk_param_fpga.ca_codes = d_ca_codes;
trk_param_fpga.code_length = GPS_L1_CA_CODE_LENGTH_CHIPS;
//################# MAKE TRACKING GNURadio object ###################
tracking_fpga_sc = dll_pll_veml_make_tracking_fpga(trk_param_fpga);
channel_ = 0;
DLOG(INFO) << "tracking(" << tracking_fpga_sc->unique_id() << ")";
*/
}
GpsL1CaDllPllTrackingFpga::~GpsL1CaDllPllTrackingFpga()
{
delete[] d_ca_codes;
}
void GpsL1CaDllPllTrackingFpga::start_tracking()
{
tracking_fpga_sc->start_tracking();
}
/*
* Set tracking channel unique ID
*/
@ -255,21 +165,27 @@ void GpsL1CaDllPllTrackingFpga::set_channel(unsigned int channel)
tracking_fpga_sc->set_channel(channel);
}
void GpsL1CaDllPllTrackingFpga::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
{
tracking_fpga_sc->set_gnss_synchro(p_gnss_synchro);
}
void GpsL1CaDllPllTrackingFpga::connect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
if (top_block)
{ /* top_block is not null */
};
//nothing to connect
}
void GpsL1CaDllPllTrackingFpga::disconnect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
if (top_block)
{ /* top_block is not null */
};
//nothing to disconnect
}
@ -284,5 +200,3 @@ gr::basic_block_sptr GpsL1CaDllPllTrackingFpga::get_right_block()
{
return tracking_fpga_sc;
}

View File

@ -39,10 +39,9 @@
#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_FPGA_H_
#define GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_FPGA_H_
#include <string>
#include "tracking_interface.h"
#include "dll_pll_veml_tracking_fpga.h"
#include <string>
class ConfigurationInterface;
@ -53,9 +52,9 @@ class GpsL1CaDllPllTrackingFpga : public TrackingInterface
{
public:
GpsL1CaDllPllTrackingFpga(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GpsL1CaDllPllTrackingFpga();
@ -93,11 +92,8 @@ public:
void start_tracking() override;
//void reset(void);
private:
//gps_l1_ca_dll_pll_tracking_cc_sptr tracking_;
dll_pll_veml_tracking_fpga_sptr tracking_fpga_sc;
dll_pll_veml_tracking_fpga_sptr tracking_fpga_sc;
size_t item_size_;
unsigned int channel_;
std::string role_;
@ -106,4 +102,4 @@ private:
int* d_ca_codes;
};
#endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_FPGA_H_
#endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_FPGA_H_

View File

@ -64,9 +64,8 @@ dll_pll_veml_tracking_fpga_sptr dll_pll_veml_make_tracking_fpga(dllpllconf_fpga_
}
dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_) :
gr::block("dll_pll_veml_tracking_fpga", gr::io_signature::make(0, 0, sizeof(lv_16sc_t)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_) : gr::block("dll_pll_veml_tracking_fpga", gr::io_signature::make(0, 0, sizeof(lv_16sc_t)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
trk_parameters = conf_;
// Telemetry bit synchronization message port input
@ -133,21 +132,20 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_)
d_correlation_length_ms = 1;
d_code_samples_per_chip = 1;
d_code_length_chips = static_cast<unsigned int>(GPS_L5i_CODE_LENGTH_CHIPS);
// GPS L5 does not have pilot secondary code
d_secondary = true;
interchange_iq = false;
if (trk_parameters.track_pilot)
{
d_secondary_code_length = static_cast<unsigned int>(GPS_L5q_NH_CODE_LENGTH);
d_secondary_code_string = const_cast<std::string *>(&GPS_L5q_NH_CODE_STR);
signal_pretty_name = signal_pretty_name + "Q";
//interchange_iq = true;
interchange_iq = true;
}
else
{
d_secondary_code_length = static_cast<unsigned int>(GPS_L5i_NH_CODE_LENGTH);
d_secondary_code_string = const_cast<std::string *>(&GPS_L5i_NH_CODE_STR);
signal_pretty_name = signal_pretty_name + "I";
interchange_iq = false;
}
}
else
@ -201,18 +199,18 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_)
d_code_samples_per_chip = 1;
d_code_length_chips = static_cast<unsigned int>(Galileo_E5a_CODE_LENGTH_CHIPS);
d_secondary = true;
interchange_iq = false;
if (trk_parameters.track_pilot)
{
d_secondary_code_length = static_cast<unsigned int>(Galileo_E5a_Q_SECONDARY_CODE_LENGTH);
signal_pretty_name = signal_pretty_name + "Q";
// interchange_iq = true;
interchange_iq = true;
}
else
{
d_secondary_code_length = static_cast<unsigned int>(Galileo_E5a_I_SECONDARY_CODE_LENGTH);
d_secondary_code_string = const_cast<std::string *>(&Galileo_E5a_I_SECONDARY_CODE);
signal_pretty_name = signal_pretty_name + "I";
interchange_iq = false;
}
}
else
@ -248,7 +246,6 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_)
K_blk_samples = 0.0;
// Initialize tracking ==========================================
d_code_loop_filter = Tracking_2nd_DLL_filter(static_cast<float>(d_code_period));
d_carrier_loop_filter = Tracking_2nd_PLL_filter(static_cast<float>(d_code_period));
d_carrier_loop_filter.set_PLL_BW(trk_parameters.pll_bw_hz);
@ -333,7 +330,7 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_)
d_current_prn_length_samples = static_cast<int>(trk_parameters.vector_length);
d_next_prn_length_samples = d_current_prn_length_samples;
d_correlation_length_samples = static_cast<int>(trk_parameters.vector_length); // this one is only for initialisation and does not change its value (MM)
d_correlation_length_samples = static_cast<int>(trk_parameters.vector_length); // this one is only for initialisation and does not change its value (MM)
// CN0 estimation and lock detector buffers
d_cn0_estimation_counter = 0;
@ -364,9 +361,9 @@ dll_pll_veml_tracking_fpga::dll_pll_veml_tracking_fpga(dllpllconf_fpga_t conf_)
// create multicorrelator class
std::string device_name = trk_parameters.device_name;
unsigned int device_base = trk_parameters.device_base;
int* ca_codes = trk_parameters.ca_codes;
int *ca_codes = trk_parameters.ca_codes;
unsigned int code_length = trk_parameters.code_length;
multicorrelator_fpga = std::make_shared <fpga_multicorrelator_8sc>(d_n_correlator_taps, device_name, device_base, ca_codes, code_length);
multicorrelator_fpga = std::make_shared<fpga_multicorrelator_8sc>(d_n_correlator_taps, device_name, device_base, ca_codes, code_length);
multicorrelator_fpga->set_output_vectors(d_correlator_outs);
d_pull_in = 0;
@ -381,7 +378,7 @@ void dll_pll_veml_tracking_fpga::start_tracking()
d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz;
d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples;
double acq_trk_diff_seconds = 0; // when using the FPGA we don't use the global sample counter
double acq_trk_diff_seconds = 0; // when using the FPGA we don't use the global sample counter
// Doppler effect Fd = (C / (C + Vr)) * F
double radial_velocity = (d_signal_carrier_freq + d_acq_carrier_doppler_hz) / d_signal_carrier_freq;
// new chip and prn sequence periods based on acq Doppler
@ -509,7 +506,6 @@ void dll_pll_veml_tracking_fpga::start_tracking()
d_pull_in = 1;
// enable tracking pull-in and d_state at the end to avoid general work from starting pull-in before the start tracking function is finished
d_state = 1;
}
dll_pll_veml_tracking_fpga::~dll_pll_veml_tracking_fpga()
@ -1136,14 +1132,21 @@ void dll_pll_veml_tracking_fpga::set_channel(unsigned int channel)
}
}
void dll_pll_veml_tracking_fpga::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
void dll_pll_veml_tracking_fpga::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items)
void dll_pll_veml_tracking_fpga::reset(void)
{
multicorrelator_fpga->unlock_channel();
}
int dll_pll_veml_tracking_fpga::general_work(int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items)
{
// Block input data and block output stream pointers
Gnss_Synchro **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]);
@ -1160,22 +1163,21 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
{
for (int n = 0; n < d_n_correlator_taps; n++)
{
d_correlator_outs[n] = gr_complex(0,0);
d_correlator_outs[n] = gr_complex(0, 0);
}
current_synchro_data.Tracking_sample_counter =d_sample_counter + d_current_prn_length_samples;
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
current_synchro_data.System = {'G'};
current_synchro_data.correlation_length_ms = 1;
break;
}
case 1: // Standby - Consume samples at full throttle, do nothing
{
d_pull_in = 0;
multicorrelator_fpga->lock_channel();
unsigned counter_value = multicorrelator_fpga->read_sample_counter();
unsigned num_frames = ceil((counter_value - current_synchro_data.Acq_samplestamp_samples - current_synchro_data.Acq_delay_samples)/d_correlation_length_samples);
unsigned absolute_samples_offset = current_synchro_data.Acq_delay_samples + current_synchro_data.Acq_samplestamp_samples + num_frames*d_correlation_length_samples;
unsigned num_frames = ceil((counter_value - current_synchro_data.Acq_samplestamp_samples - current_synchro_data.Acq_delay_samples) / d_correlation_length_samples);
unsigned absolute_samples_offset = current_synchro_data.Acq_delay_samples + current_synchro_data.Acq_samplestamp_samples + num_frames * d_correlation_length_samples;
multicorrelator_fpga->set_initial_sample(absolute_samples_offset);
d_sample_counter = absolute_samples_offset;
current_synchro_data.Tracking_sample_counter = absolute_samples_offset;
@ -1188,14 +1190,14 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
case 2:
{
d_sample_counter = d_sample_counter_next;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
// ################# CARRIER WIPEOFF AND CORRELATORS ##############################
// perform carrier wipe-off and compute Early, Prompt and Late correlation
multicorrelator_fpga->Carrier_wipeoff_multicorrelator_resampler(
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
// Save single correlation step variables
if (d_veml)
@ -1317,11 +1319,9 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
}
else
{
d_state = 4;
}
}
}
break;
@ -1330,15 +1330,15 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
case 3:
{
d_sample_counter = d_sample_counter_next;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
// Fill the acquisition data
current_synchro_data = *d_acquisition_gnss_synchro;
// perform a correlation step
multicorrelator_fpga->Carrier_wipeoff_multicorrelator_resampler(
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
update_tracking_vars();
save_correlation_results();
@ -1390,14 +1390,14 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
case 4: // narrow tracking
{
d_sample_counter = d_sample_counter_next;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
d_sample_counter_next = d_sample_counter + d_current_prn_length_samples;
// perform a correlation step
//do_correlation_step(in);
multicorrelator_fpga->Carrier_wipeoff_multicorrelator_resampler(
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
d_rem_carr_phase_rad, d_carrier_phase_step_rad,
d_rem_code_phase_chips, d_code_phase_step_chips,
d_current_prn_length_samples);
save_correlation_results();
@ -1472,24 +1472,3 @@ int dll_pll_veml_tracking_fpga::general_work (int noutput_items __attribute__((u
}
return 0;
}
void dll_pll_veml_tracking_fpga::reset(void)
{
multicorrelator_fpga->unlock_channel();
}

View File

@ -39,15 +39,15 @@
#ifndef GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H
#define GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H
#include "fpga_multicorrelator.h"
#include "gnss_synchro.h"
#include "tracking_2nd_DLL_filter.h"
#include "tracking_2nd_PLL_filter.h"
#include "fpga_multicorrelator.h"
#include <gnuradio/block.h>
#include <fstream>
#include <string>
#include <map>
#include "fpga_multicorrelator.h"
typedef struct
{
@ -75,13 +75,13 @@ typedef struct
std::string device_name;
unsigned int device_base;
unsigned int code_length;
int* ca_codes;
int *ca_codes;
} dllpllconf_fpga_t;
class dll_pll_veml_tracking_fpga;
typedef boost::shared_ptr<dll_pll_veml_tracking_fpga>
dll_pll_veml_tracking_fpga_sptr;
dll_pll_veml_tracking_fpga_sptr;
dll_pll_veml_tracking_fpga_sptr dll_pll_veml_make_tracking_fpga(dllpllconf_fpga_t conf_);
@ -221,7 +221,6 @@ private:
int d_next_prn_length_samples;
unsigned long int d_sample_counter_next;
unsigned int d_pull_in = 0;
};
#endif //GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H
#endif //GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H