Merge branch 'next_fpga' of https://github.com/gnss-sdr/gnss-sdr into

next

# Conflicts:
#	README.md
This commit is contained in:
Carles Fernandez 2017-03-13 21:05:38 +01:00
commit c12384cce4
18 changed files with 2561 additions and 120 deletions

View File

@ -56,6 +56,7 @@ option(ENABLE_GPROF "Enable the use of the GNU profiler tool 'gprof'" OFF)
option(ENABLE_PROFILING "Enable execution of volk_gnsssdr_profile at the end of the building" OFF)
option(ENABLE_OPENCL "Enable building of processing blocks implemented with OpenCL (experimental)" OFF)
option(ENABLE_CUDA "Enable building of processing blocks implemented with CUDA (experimental, requires CUDA SDK)" OFF)
option(ENABLE_FPGA "Enable building of processing blocks implemented with FPGA (experimental, requires EZDMA driver)" OFF)
# Building and packaging options
option(ENABLE_GENERIC_ARCH "Builds a portable binary" OFF)
@ -76,7 +77,10 @@ if(ENABLE_SYSTEM_TESTING_EXTRA)
set(ENABLE_SYSTEM_TESTING ON)
endif(ENABLE_SYSTEM_TESTING_EXTRA)
option(ENABLE_OWN_GPSTK "Force to download, build and link GPSTk for system tests, even if it is already installed" OFF)
option(ENABLE_INSTALL_TESTS "Install QA code system-wide" OFF)
if(ENABLE_FPGA)
set(ENABLE_INSTALL_TESTS ON)
endif(ENABLE_FPGA)
###############################
@ -1122,7 +1126,16 @@ else(ENABLE_CUDA)
message(STATUS "Enable it with 'cmake -DENABLE_CUDA=ON ../' to add support for GPU-based acceleration using CUDA." )
endif(ENABLE_CUDA)
###############################################################################
# FPGA (OPTIONAL)
###############################################################################
if(ENABLE_FPGA)
message(STATUS "FPGA Acceleration will be enabled." )
message(STATUS "You can disable it with 'cmake -DENABLE_FPGA=OFF ../'" )
else(ENABLE_FPGA)
message(STATUS "Fpga Acceleration will be not enabled." )
message(STATUS "Enable it with 'cmake -DENABLE_FPGA=ON ../' to add support for GPU-based acceleration using the FPGA." )
endif(ENABLE_FPGA)
################################################################################
# Setup of optional drivers

View File

@ -406,6 +406,7 @@ $ sudo make install
Using this option, all SIMD instructions are exclusively accessed via VOLK, which automatically includes versions of each function for different SIMD instruction sets, then detects at runtime which to use, or if there are none, substitutes a generic, non-SIMD implementation.
More details can be found in our tutorial about [GNSS-SDR configuration options at building time](http://gnss-sdr.org/docs/tutorials/using-git/ "Configuration options at building time").
<a name="macosx">macOS and Mac OS X</a>
@ -1288,7 +1289,7 @@ Publications and Credits
If you use GNSS-SDR to produce a research paper or Thesis, we would appreciate if you reference the following article to credit the GNSS-SDR project:
* C. Fern&aacute;ndez-Prades, J. Arribas, P. Closas, C. Avil&eacute;s, and L. Esteve, [GNSS-SDR: an open source tool for researchers and developers](http://www.cttc.es/publication/gnss-sdr-an-open-source-tool-for-researchers-and-developers/), in Proc. of the 24th International Technical Meeting of The Satellite Division of the Institute of Navigation (ION GNSS), Portland, Oregon, Sept. 19-23, 2011, pp. 780-794.
* C. Fern&aacute;ndez-Prades, J. Arribas, P. Closas, C. Avil&eacute;s, and L. Esteve, [GNSS-SDR: an open source tool for researchers and developers](http://www.cttc.es/publication/gnss-sdr-an-open-source-tool-for-researchers-and-developers/), in Proceedings of the 24th International Technical Meeting of The Satellite Division of the Institute of Navigation (ION GNSS), Portland, Oregon, Sept. 19-23, 2011, pp. 780-794.
For LaTeX users, this is the BibTeX entry for your convenience:
@ -1296,11 +1297,11 @@ For LaTeX users, this is the BibTeX entry for your convenience:
@INPROCEEDINGS{GNSS-SDR11,
AUTHOR = {C.~{Fern\'{a}ndez--Prades} and J.~Arribas and P.~Closas and C.~Avil\'{e}s and L.~Esteve},
TITLE = {{GNSS-SDR}: An Open Source Tool For Researchers and Developers},
BOOKTITLE = {Proc. 24th Int. Tech. Meeting Sat. Div. Inst. Navig.},
BOOKTITLE = {Proc. 24th Intl. Tech. Meeting Sat. Div. Inst. Navig.},
YEAR = {2011},
pages = {780--794},
address = {Portland, Oregon},
month = {Sept.} }
PAGES = {780--794},
ADDRESS = {Portland, Oregon},
MONTH = {Sept.} }
~~~~~~

View File

@ -21,6 +21,10 @@ if(ENABLE_CUDA)
set(OPT_TRACKING_INCLUDE_DIRS ${OPT_TRACKING_INCLUDE_DIRS} ${CUDA_INCLUDE_DIRS})
endif(ENABLE_CUDA)
if(ENABLE_FPGA)
SET(OPT_TRACKING_ADAPTERS ${OPT_TRACKING_ADAPTERS} gps_l1_ca_dll_pll_c_aid_tracking_fpga.cc)
endif(ENABLE_FPGA)
set(TRACKING_ADAPTER_SOURCES
galileo_e1_dll_pll_veml_tracking.cc
galileo_e1_tcp_connector_tracking.cc

View File

@ -0,0 +1,209 @@
/*!
* \file gps_l1_ca_dll_pll_c_aid_tracking_fpga.cc
* \brief Implementation of an adapter of a DLL+PLL tracking loop block
* for GPS L1 C/A to a TrackingInterface
* \author Marc Majoral, 2017. mmajoral(at)cttc.cat
* Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Javier Arribas, 2011. jarribas(at)cttc.es
*
* Code DLL + carrier PLL according to the algorithms described in:
* K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency
* Approach, Birkhauser, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_dll_pll_c_aid_tracking_fpga.h"
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
using google::LogMessage;
GpsL1CaDllPllCAidTrackingFpga::GpsL1CaDllPllCAidTrackingFpga(
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams) :
role_(role), in_streams_(in_streams), out_streams_(out_streams)
{
DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
bool dump;
std::string dump_filename;
std::string default_item_type = "cshort";
float pll_bw_hz;
float pll_bw_narrow_hz;
float dll_bw_hz;
float dll_bw_narrow_hz;
float early_late_space_chips;
item_type_ = configuration->property(role + ".item_type", default_item_type);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
f_if = configuration->property(role + ".if", 0);
dump = configuration->property(role + ".dump", false);
pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0);
dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
pll_bw_narrow_hz = configuration->property(role + ".pll_bw_narrow_hz", 20.0);
dll_bw_narrow_hz = configuration->property(role + ".dll_bw_narrow_hz", 2.0);
int extend_correlation_ms;
extend_correlation_ms = configuration->property(role + ".extend_correlation_ms", 1);
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
if(item_type_.compare("cshort") == 0)
{
item_size_ = sizeof(lv_16sc_t);
tracking_fpga_sc = gps_l1_ca_dll_pll_c_aid_make_tracking_fpga_sc(
f_if,
fs_in,
vector_length,
dump,
dump_filename,
pll_bw_hz,
dll_bw_hz,
pll_bw_narrow_hz,
dll_bw_narrow_hz,
extend_correlation_ms,
early_late_space_chips);
DLOG(INFO) << "tracking(" << tracking_fpga_sc->unique_id() << ")";
}
else
{
item_size_ = sizeof(lv_16sc_t);
// LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
}
channel_ = 0;
}
GpsL1CaDllPllCAidTrackingFpga::~GpsL1CaDllPllCAidTrackingFpga()
{
LOG(INFO) << "gspl1cadllpllcaidtrackingfpga destructor called";
}
void GpsL1CaDllPllCAidTrackingFpga::start_tracking()
{
if (item_type_.compare("cshort") == 0)
{
tracking_fpga_sc->start_tracking();
}
else
{
// LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
}
}
/*
* Set tracking channel unique ID
*/
void GpsL1CaDllPllCAidTrackingFpga::set_channel(unsigned int channel)
{
channel_ = channel;
if (item_type_.compare("cshort") == 0)
{
tracking_fpga_sc->set_channel(channel);
}
else
{
// LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
}
}
void GpsL1CaDllPllCAidTrackingFpga::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
{
if (item_type_.compare("cshort") == 0)
{
tracking_fpga_sc->set_gnss_synchro(p_gnss_synchro);
}
else
{
// LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
}
}
void GpsL1CaDllPllCAidTrackingFpga::connect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
//nothing to connect, now the tracking uses gr_sync_decimator
}
void GpsL1CaDllPllCAidTrackingFpga::disconnect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
//nothing to disconnect, now the tracking uses gr_sync_decimator
}
// CONVERT TO SOURCE
gr::basic_block_sptr GpsL1CaDllPllCAidTrackingFpga::get_left_block()
{
if (item_type_.compare("cshort") == 0)
{
return tracking_fpga_sc;
}
else
{
//LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
return nullptr;
}
}
gr::basic_block_sptr GpsL1CaDllPllCAidTrackingFpga::get_right_block()
{
if (item_type_.compare("cshort") == 0)
{
return tracking_fpga_sc;
}
else
{
//LOG(WARNING) << item_type_ << " unknown tracking item type";
LOG(WARNING) << item_type_ << " the tracking item type for the FPGA tracking test has to be cshort";
return nullptr;
}
}

View File

@ -0,0 +1,108 @@
/*!
* \file gps_l1_ca_dll_pll_c_aid_tracking_fpga.h
* \brief Interface of an adapter of a DLL+PLL tracking loop block
* for GPS L1 C/A to a TrackingInterface
* \author Marc Majoral, 2017. mmajoral(at)cttc.cat
* Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Javier Arribas, 2011. jarribas(at)cttc.es
*
* Code DLL + carrier PLL according to the algorithms described in:
* K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency
* Approach, Birkha user, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA__H_
#define GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA__H_
#include <string>
#include "tracking_interface.h"
#include "gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc.h"
class ConfigurationInterface;
/*!
* \brief This class implements a code DLL + carrier PLL tracking loop
*/
class GpsL1CaDllPllCAidTrackingFpga : public TrackingInterface
{
public:
GpsL1CaDllPllCAidTrackingFpga(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GpsL1CaDllPllCAidTrackingFpga();
std::string role()
{
return role_;
}
//! Returns "GPS_L1_CA_DLL_PLL_C_Aid_Tracking_Fpga"
std::string implementation()
{
return "GPS_L1_CA_DLL_PLL_C_Aid_Tracking_Fpga";
}
size_t item_size()
{
return item_size_;
}
void connect(gr::top_block_sptr top_block);
void disconnect(gr::top_block_sptr top_block);
// CONVERT TO SOURCE
gr::basic_block_sptr get_left_block();
gr::basic_block_sptr get_right_block();
/*!
* \brief Set tracking channel unique ID
*/
void set_channel(unsigned int channel);
/*!
* \brief Set acquisition/tracking common Gnss_Synchro object pointer
* to efficiently exchange synchronization data between acquisition and tracking blocks
*/
void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro);
void start_tracking();
private:
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr tracking_fpga_sc;
size_t item_size_;
std::string item_type_;
unsigned int channel_;
std::string role_;
unsigned int in_streams_;
unsigned int out_streams_;
};
#endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA__H_

View File

@ -22,6 +22,10 @@ if(ENABLE_CUDA)
set(OPT_TRACKING_LIBRARIES ${OPT_TRACKING_LIBRARIES} ${CUDA_LIBRARIES})
endif(ENABLE_CUDA)
if(ENABLE_FPGA)
set(OPT_TRACKING_BLOCKS ${OPT_TRACKING_BLOCKS} gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc.cc)
endif(ENABLE_FPGA)
set(TRACKING_GR_BLOCKS_SOURCES
galileo_e1_dll_pll_veml_tracking_cc.cc
galileo_e1_tcp_connector_tracking_cc.cc
@ -30,7 +34,7 @@ set(TRACKING_GR_BLOCKS_SOURCES
galileo_e5a_dll_pll_tracking_cc.cc
gps_l2_m_dll_pll_tracking_cc.cc
gps_l1_ca_dll_pll_c_aid_tracking_cc.cc
gps_l1_ca_dll_pll_c_aid_tracking_sc.cc
gps_l1_ca_dll_pll_c_aid_tracking_sc.cc
${OPT_TRACKING_BLOCKS}
)

View File

@ -0,0 +1,668 @@
/*!
* \file gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc.cc
* \brief Implementation of a code DLL + carrier PLL tracking block
* \author Marc Majoral, 2017. mmajoral(at)cttc.cat
* Javier Arribas, 2015. jarribas(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc.h"
#include <cmath>
#include <iostream>
#include <memory>
#include <sstream>
#include <boost/bind.hpp>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <pmt/pmt.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "gps_sdr_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
#include "GPS_L1_CA.h"
#include "control_message_factory.h"
/*!
* \todo Include in definition header file
*/
#define CN0_ESTIMATION_SAMPLES 20
#define MINIMUM_VALID_CN0 25
#define MAXIMUM_LOCK_FAIL_COUNTER 50
#define CARRIER_LOCK_THRESHOLD 0.85
using google::LogMessage;
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr
gps_l1_ca_dll_pll_c_aid_make_tracking_fpga_sc(
long if_freq,
long fs_in,
unsigned int vector_length,
bool dump,
std::string dump_filename,
float pll_bw_hz,
float dll_bw_hz,
float pll_bw_narrow_hz,
float dll_bw_narrow_hz,
int extend_correlation_ms,
float early_late_space_chips)
{
return gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr(new gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc(if_freq,
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips));
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::msg_handler_preamble_index(pmt::pmt_t msg)
{
//pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator
{
d_preamble_timestamp_s = pmt::to_double(msg);
d_enable_extended_integration = true;
d_preamble_synchronized = false;
}
}
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc(
long if_freq,
long fs_in,
unsigned int vector_length,
bool dump,
std::string dump_filename,
float pll_bw_hz,
float dll_bw_hz,
float pll_bw_narrow_hz,
float dll_bw_narrow_hz,
int extend_correlation_ms,
float early_late_space_chips) :
gr::block("gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc", gr::io_signature::make(0, 0, sizeof(lv_16sc_t)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry bit synchronization message port input
this->message_port_register_in(pmt::mp("preamble_timestamp_s"));
this->set_msg_handler(pmt::mp("preamble_timestamp_s"),
boost::bind(&gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::msg_handler_preamble_index, this, _1));
this->message_port_register_out(pmt::mp("events"));
// initialize internal vars
d_dump = dump;
d_if_freq = if_freq;
d_fs_in = fs_in;
d_vector_length = vector_length;
d_dump_filename = dump_filename;
d_correlation_length_samples = static_cast<int>(d_vector_length);
// Initialize tracking ==========================================
d_pll_bw_hz = pll_bw_hz;
d_dll_bw_hz = dll_bw_hz;
d_pll_bw_narrow_hz = pll_bw_narrow_hz;
d_dll_bw_narrow_hz = dll_bw_narrow_hz;
d_code_loop_filter.set_DLL_BW(d_dll_bw_hz);
d_carrier_loop_filter.set_params(10.0, d_pll_bw_hz, 2);
d_extend_correlation_ms = extend_correlation_ms;
// --- DLL variables --------------------------------------------------------
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
// Initialization of local code replica
// Get space for a vector with the C/A code replica sampled 1x/chip
d_ca_code = static_cast<gr_complex*>(volk_gnsssdr_malloc(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
d_ca_code_16sc = static_cast<lv_16sc_t*>(volk_gnsssdr_malloc(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(lv_16sc_t), volk_gnsssdr_get_alignment()));
// correlator outputs (scalar)
d_n_correlator_taps = 3; // Early, Prompt, and Late
d_correlator_outs_16sc = static_cast<lv_16sc_t*>(volk_gnsssdr_malloc(d_n_correlator_taps*sizeof(lv_16sc_t), volk_gnsssdr_get_alignment()));
for (int n = 0; n < d_n_correlator_taps; n++)
{
d_correlator_outs_16sc[n] = lv_cmake(0,0);
}
d_local_code_shift_chips = static_cast<float*>(volk_gnsssdr_malloc(d_n_correlator_taps*sizeof(float), volk_gnsssdr_get_alignment()));
// Set TAPs delay values [chips]
d_local_code_shift_chips[0] = - d_early_late_spc_chips;
d_local_code_shift_chips[1] = 0.0;
d_local_code_shift_chips[2] = d_early_late_spc_chips;
multicorrelator_fpga_8sc.init(2 * d_correlation_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------
// define initial code frequency basis of NCO
d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ;
// define residual code phase (in chips)
d_rem_code_phase_samples = 0.0;
// define residual carrier phase
d_rem_carrier_phase_rad = 0.0;
// sample synchronization
d_sample_counter = 0; //(from trk to tlm)
d_acq_sample_stamp = 0;
d_enable_tracking = false;
d_pull_in = false;
// CN0 estimation and lock detector buffers
d_cn0_estimation_counter = 0;
d_Prompt_buffer = new gr_complex[CN0_ESTIMATION_SAMPLES];
d_carrier_lock_test = 1;
d_CN0_SNV_dB_Hz = 0;
d_carrier_lock_fail_counter = 0;
d_carrier_lock_threshold = CARRIER_LOCK_THRESHOLD;
systemName["G"] = std::string("GPS");
systemName["S"] = std::string("SBAS");
set_relative_rate(1.0 / static_cast<double>(d_vector_length));
d_acquisition_gnss_synchro = 0;
d_channel = 0;
d_acq_code_phase_samples = 0.0;
d_acq_carrier_doppler_hz = 0.0;
d_carrier_doppler_hz = 0.0;
d_acc_carrier_phase_cycles = 0.0;
d_code_phase_samples = 0.0;
d_enable_extended_integration = false;
d_preamble_synchronized = false;
d_rem_code_phase_integer_samples = 0;
d_code_error_chips_Ti = 0.0;
d_pll_to_dll_assist_secs_Ti = 0.0;
d_rem_code_phase_chips = 0.0;
d_code_phase_step_chips = 0.0;
d_carrier_phase_step_rad = 0.0;
d_code_error_filt_chips_s = 0.0;
d_code_error_filt_chips_Ti = 0.0;
d_preamble_timestamp_s = 0.0;
d_carr_phase_error_secs_Ti = 0.0;
//set_min_output_buffer((long int)300);
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::start_tracking()
{
/*
* correct the code phase according to the delay between acq and trk
*/
d_acq_code_phase_samples = d_acquisition_gnss_synchro->Acq_delay_samples;
d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz;
d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples;
long int acq_trk_diff_samples;
double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<long int>(d_sample_counter) - static_cast<long int>(d_acq_sample_stamp);//-d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect
// Fd=(C/(C+Vr))*F
double radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ;
// new chip and prn sequence periods based on acq Doppler
double T_chip_mod_seconds;
double T_prn_mod_seconds;
double T_prn_mod_samples;
d_code_freq_chips = radial_velocity * GPS_L1_CA_CODE_RATE_HZ;
d_code_phase_step_chips = static_cast<double>(d_code_freq_chips) / static_cast<double>(d_fs_in);
T_chip_mod_seconds = 1.0 / d_code_freq_chips;
T_prn_mod_seconds = T_chip_mod_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
T_prn_mod_samples = T_prn_mod_seconds * static_cast<double>(d_fs_in);
d_correlation_length_samples = round(T_prn_mod_samples);
double T_prn_true_seconds = GPS_L1_CA_CODE_LENGTH_CHIPS / GPS_L1_CA_CODE_RATE_HZ;
double T_prn_true_samples = T_prn_true_seconds * static_cast<double>(d_fs_in);
double T_prn_diff_seconds = T_prn_true_seconds - T_prn_mod_seconds;
double N_prn_diff = acq_trk_diff_seconds / T_prn_true_seconds;
double corrected_acq_phase_samples, delay_correction_samples;
corrected_acq_phase_samples = fmod((d_acq_code_phase_samples + T_prn_diff_seconds * N_prn_diff * static_cast<double>(d_fs_in)), T_prn_true_samples);
if (corrected_acq_phase_samples < 0)
{
corrected_acq_phase_samples = T_prn_mod_samples + corrected_acq_phase_samples;
}
delay_correction_samples = d_acq_code_phase_samples - corrected_acq_phase_samples;
d_acq_code_phase_samples = corrected_acq_phase_samples;
d_carrier_doppler_hz = d_acq_carrier_doppler_hz;
d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
// DLL/PLL filter initialization
d_carrier_loop_filter.initialize(d_acq_carrier_doppler_hz); // The carrier loop filter implements the Doppler accumulator
d_code_loop_filter.initialize(); // initialize the code filter
// generate local reference ALWAYS starting at chip 1 (1 sample per chip)
gps_l1_ca_code_gen_complex(d_ca_code, d_acquisition_gnss_synchro->PRN, 0);
volk_gnsssdr_32fc_convert_16ic(d_ca_code_16sc, d_ca_code, static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS));
multicorrelator_fpga_8sc.set_local_code_and_taps(static_cast<int>(GPS_L1_CA_CODE_LENGTH_CHIPS), d_ca_code_16sc, d_local_code_shift_chips);
for (int n = 0; n < d_n_correlator_taps; n++)
{
d_correlator_outs_16sc[n] = lv_16sc_t(0,0);
}
d_carrier_lock_fail_counter = 0;
d_rem_code_phase_samples = 0.0;
d_rem_carrier_phase_rad = 0.0;
d_rem_code_phase_chips = 0.0;
d_acc_carrier_phase_cycles = 0.0;
d_pll_to_dll_assist_secs_Ti = 0.0;
d_code_phase_samples = d_acq_code_phase_samples;
std::string sys_ = &d_acquisition_gnss_synchro->System;
sys = sys_.substr(0,1);
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
d_enable_extended_integration = false;
d_preamble_synchronized = false;
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " Code Phase correction [samples]=" << delay_correction_samples
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
}
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::~gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc()
{
d_dump_file.close();
volk_gnsssdr_free(d_local_code_shift_chips);
volk_gnsssdr_free(d_ca_code);
volk_gnsssdr_free(d_ca_code_16sc);
volk_gnsssdr_free(d_correlator_outs_16sc);
delete[] d_Prompt_buffer;
multicorrelator_fpga_8sc.free();
}
int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::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 = (Gnss_Synchro **) &output_items[0];
Gnss_Synchro current_synchro_data = Gnss_Synchro();
// process vars
double code_error_filt_secs_Ti = 0.0;
double CURRENT_INTEGRATION_TIME_S = 0.0;
double CORRECTED_INTEGRATION_TIME_S = 0.0;
if (d_enable_tracking == true)
{
// Fill the acquisition data
current_synchro_data = *d_acquisition_gnss_synchro;
// Receiver signal alignment
if (d_pull_in == true)
{
int samples_offset;
double acq_trk_shif_correction_samples;
int acq_to_trk_delay_samples;
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_correlation_length_samples));
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
d_sample_counter += samples_offset; // count for the processed samples
d_pull_in = false;
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI;
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI;
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
*out[0] = current_synchro_data;
consume_each(samples_offset); // shift input to perform alignment with local replica
multicorrelator_fpga_8sc.set_initial_sample(samples_offset);
return 1;
}
// ################# CARRIER WIPEOFF AND CORRELATORS ##############################
// perform carrier wipe-off and compute Early, Prompt and Late correlation
//multicorrelator_fpga_8sc.set_input_output_vectors(d_correlator_outs_16sc, in);
multicorrelator_fpga_8sc.set_output_vectors(d_correlator_outs_16sc);
multicorrelator_fpga_8sc.Carrier_wipeoff_multicorrelator_resampler(d_rem_carrier_phase_rad,
d_carrier_phase_step_rad,
d_rem_code_phase_chips,
d_code_phase_step_chips,
d_correlation_length_samples);
// ####### coherent intergration extension
// keep the last symbols
d_E_history.push_back(d_correlator_outs_16sc[0]); // save early output
d_P_history.push_back(d_correlator_outs_16sc[1]); // save prompt output
d_L_history.push_back(d_correlator_outs_16sc[2]); // save late output
if (static_cast<int>(d_P_history.size()) > d_extend_correlation_ms)
{
d_E_history.pop_front();
d_P_history.pop_front();
d_L_history.pop_front();
}
bool enable_dll_pll;
if (d_enable_extended_integration == true)
{
long int symbol_diff = round(1000.0 * ((static_cast<double>(d_sample_counter) + d_rem_code_phase_samples) / static_cast<double>(d_fs_in) - d_preamble_timestamp_s));
if (symbol_diff > 0 and symbol_diff % d_extend_correlation_ms == 0)
{
// compute coherent integration and enable tracking loop
// perform coherent integration using correlator output history
// std::cout<<"##### RESET COHERENT INTEGRATION ####"<<std::endl;
d_correlator_outs_16sc[0] = lv_cmake(0,0);
d_correlator_outs_16sc[1] = lv_cmake(0,0);
d_correlator_outs_16sc[2] = lv_cmake(0,0);
for (int n = 0; n < d_extend_correlation_ms; n++)
{
d_correlator_outs_16sc[0] += d_E_history.at(n);
d_correlator_outs_16sc[1] += d_P_history.at(n);
d_correlator_outs_16sc[2] += d_L_history.at(n);
}
if (d_preamble_synchronized == false)
{
d_code_loop_filter.set_DLL_BW(d_dll_bw_narrow_hz);
d_carrier_loop_filter.set_params(10.0, d_pll_bw_narrow_hz,2);
d_preamble_synchronized = true;
std::cout << "Enabled " << d_extend_correlation_ms << " [ms] extended correlator for CH "<< d_channel << " : Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< " pll_bw = " << d_pll_bw_hz << " [Hz], pll_narrow_bw = " << d_pll_bw_narrow_hz << " [Hz]" << std::endl
<< " dll_bw = " << d_dll_bw_hz << " [Hz], dll_narrow_bw = " << d_dll_bw_narrow_hz << " [Hz]" << std::endl;
}
// UPDATE INTEGRATION TIME
CURRENT_INTEGRATION_TIME_S = static_cast<double>(d_extend_correlation_ms) * GPS_L1_CA_CODE_PERIOD;
enable_dll_pll = true;
}
else
{
if(d_preamble_synchronized == true)
{
// continue extended coherent correlation
// Compute the next buffer length based on the period of the PRN sequence and the code phase error estimation
double T_chip_seconds = 1.0 / d_code_freq_chips;
double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
int K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples;
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
// code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
// remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + d_carrier_phase_step_rad * static_cast<double>(d_correlation_length_samples), GPS_TWO_PI);
// UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI;
// disable tracking loop and inform telemetry decoder
enable_dll_pll = false;
}
else
{
// perform basic (1ms) correlation
// UPDATE INTEGRATION TIME
CURRENT_INTEGRATION_TIME_S = static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in);
enable_dll_pll = true;
}
}
}
else
{
// UPDATE INTEGRATION TIME
CURRENT_INTEGRATION_TIME_S = static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in);
enable_dll_pll = true;
}
if (enable_dll_pll == true)
{
// ################## PLL ##########################################################
// Update PLL discriminator [rads/Ti -> Secs/Ti]
d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex<float>(d_correlator_outs_16sc[1].real(),d_correlator_outs_16sc[1].imag())) / GPS_TWO_PI; //prompt output
// Carrier discriminator filter
// NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan
// Input [s/Ti] -> output [Hz]
d_carrier_doppler_hz = d_carrier_loop_filter.get_carrier_error(0.0, d_carr_phase_error_secs_Ti, CURRENT_INTEGRATION_TIME_S);
// PLL to DLL assistance [Secs/Ti]
d_pll_to_dll_assist_secs_Ti = (d_carrier_doppler_hz * CURRENT_INTEGRATION_TIME_S) / GPS_L1_FREQ_HZ;
// code Doppler frequency update
d_code_freq_chips = GPS_L1_CA_CODE_RATE_HZ + ((d_carrier_doppler_hz * GPS_L1_CA_CODE_RATE_HZ) / GPS_L1_FREQ_HZ);
// ################## DLL ##########################################################
// DLL discriminator
d_code_error_chips_Ti = dll_nc_e_minus_l_normalized(std::complex<float>(d_correlator_outs_16sc[0].real(),d_correlator_outs_16sc[0].imag()), std::complex<float>(d_correlator_outs_16sc[2].real(),d_correlator_outs_16sc[2].imag())); // [chips/Ti] //early and late
// Code discriminator filter
d_code_error_filt_chips_s = d_code_loop_filter.get_code_nco(d_code_error_chips_Ti); // input [chips/Ti] -> output [chips/second]
d_code_error_filt_chips_Ti = d_code_error_filt_chips_s * CURRENT_INTEGRATION_TIME_S;
code_error_filt_secs_Ti = d_code_error_filt_chips_Ti / d_code_freq_chips; // [s/Ti]
// ################## CARRIER AND CODE NCO BUFFER ALIGNEMENT #######################
// keep alignment parameters for the next input buffer
// Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation
double T_chip_seconds = 1.0 / d_code_freq_chips;
double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
double K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in);
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
//################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GPS_TWO_PI;
// UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GPS_TWO_PI);
//################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES)
{
// fill buffer with prompt correlator output values
d_Prompt_buffer[d_cn0_estimation_counter] = lv_cmake(static_cast<float>(d_correlator_outs_16sc[1].real()), static_cast<float>(d_correlator_outs_16sc[1].imag()) ); // prompt
d_cn0_estimation_counter++;
}
else
{
d_cn0_estimation_counter = 0;
// Code lock indicator
d_CN0_SNV_dB_Hz = cn0_svn_estimator(d_Prompt_buffer, CN0_ESTIMATION_SAMPLES, d_fs_in, GPS_L1_CA_CODE_LENGTH_CHIPS);
// Carrier lock indicator
d_carrier_lock_test = carrier_lock_detector(d_Prompt_buffer, CN0_ESTIMATION_SAMPLES);
// Loss of lock detection
if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < MINIMUM_VALID_CN0)
{
d_carrier_lock_fail_counter++;
}
else
{
if (d_carrier_lock_fail_counter > 0) d_carrier_lock_fail_counter--;
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3));//3 -> loss of lock
d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
}
}
// ########### Output the tracking data to navigation and PVT ##########
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
current_synchro_data.Rem_code_phase_secs = d_rem_code_phase_samples / static_cast<double>(d_fs_in);
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
current_synchro_data.Flag_valid_symbol_output = true;
if (d_preamble_synchronized == true)
{
current_synchro_data.correlation_length_ms = d_extend_correlation_ms;
}
else
{
current_synchro_data.correlation_length_ms = 1;
}
}
else
{
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
current_synchro_data.Rem_code_phase_secs = d_rem_code_phase_samples / static_cast<double>(d_fs_in);
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;// todo: project the carrier doppler
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
}
}
else
{
for (int n = 0; n < d_n_correlator_taps; n++)
{
d_correlator_outs_16sc[n] = lv_cmake(0,0);
}
current_synchro_data.System = {'G'};
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
current_synchro_data.Rem_code_phase_secs = d_rem_code_phase_samples / static_cast<double>(d_fs_in);
}
*out[0] = current_synchro_data;
if(d_dump)
{
// MULTIPLEXED FILE RECORDING - Record results to file
float prompt_I;
float prompt_Q;
float tmp_E, tmp_P, tmp_L;
double tmp_double;
prompt_I = d_correlator_outs_16sc[1].real();
prompt_Q = d_correlator_outs_16sc[1].imag();
tmp_E = std::abs<float>(std::complex<float>(d_correlator_outs_16sc[0].real(),d_correlator_outs_16sc[0].imag()));
tmp_P = std::abs<float>(std::complex<float>(d_correlator_outs_16sc[1].real(),d_correlator_outs_16sc[1].imag()));
tmp_L = std::abs<float>(std::complex<float>(d_correlator_outs_16sc[2].real(),d_correlator_outs_16sc[2].imag()));
try
{
// EPR
d_dump_file.write(reinterpret_cast<char*>(&tmp_E), sizeof(float));
d_dump_file.write(reinterpret_cast<char*>(&tmp_P), sizeof(float));
d_dump_file.write(reinterpret_cast<char*>(&tmp_L), sizeof(float));
// PROMPT I and Q (to analyze navigation symbols)
d_dump_file.write(reinterpret_cast<char*>(&prompt_I), sizeof(float));
d_dump_file.write(reinterpret_cast<char*>(&prompt_Q), sizeof(float));
// PRN start sample stamp
//tmp_float=(float)d_sample_counter;
d_dump_file.write(reinterpret_cast<char*>(&d_sample_counter), sizeof(unsigned long int));
// accumulated carrier phase
d_dump_file.write(reinterpret_cast<char*>(&d_acc_carrier_phase_cycles), sizeof(double));
// carrier and code frequency
d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
d_dump_file.write(reinterpret_cast<char*>(&d_code_freq_chips), sizeof(double));
//PLL commands
d_dump_file.write(reinterpret_cast<char*>(&d_carr_phase_error_secs_Ti), sizeof(double));
d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
//DLL commands
d_dump_file.write(reinterpret_cast<char*>(&d_code_error_chips_Ti), sizeof(double));
d_dump_file.write(reinterpret_cast<char*>(&d_code_error_filt_chips_Ti), sizeof(double));
// CN0 and carrier lock test
d_dump_file.write(reinterpret_cast<char*>(&d_CN0_SNV_dB_Hz), sizeof(double));
d_dump_file.write(reinterpret_cast<char*>(&d_carrier_lock_test), sizeof(double));
// AUX vars (for debug purposes)
tmp_double = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S;
d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
tmp_double = static_cast<double>(d_sample_counter + d_correlation_length_samples);
d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
}
catch (const std::ifstream::failure* e)
{
LOG(WARNING) << "Exception writing trk dump file " << e->what();
}
}
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::set_channel(unsigned int channel)
{
d_channel = channel;
multicorrelator_fpga_8sc.set_channel(d_channel);
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename.append(boost::lexical_cast<std::string>(d_channel));
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (const std::ifstream::failure* e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what();
}
}
}
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -0,0 +1,203 @@
/*!
* \file gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc.h
* \brief Interface of a code DLL + carrier PLL tracking block
* \author Marc Majoral, 2017. mmajoral(at)cttc.cat
* Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Javier Arribas, 2011. jarribas(at)cttc.es
*
* Code DLL + carrier PLL according to the algorithms described in:
* K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency Approach,
* Birkhauser, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA_SC_H
#define GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA_SC_H
#include <fstream>
#include <map>
#include <string>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <gnuradio/block.h>
#include <volk/volk.h>
#include "gps_sdr_signal_processing.h"
#include "gnss_synchro.h"
#include "tracking_2nd_DLL_filter.h"
#include "tracking_FLL_PLL_filter.h"
#include "fpga_multicorrelator_8sc.h"
class gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc;
typedef boost::shared_ptr<gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc>
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr;
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr
gps_l1_ca_dll_pll_c_aid_make_tracking_fpga_sc(long if_freq,
long fs_in, unsigned
int vector_length,
bool dump,
std::string dump_filename,
float pll_bw_hz,
float dll_bw_hz,
float pll_bw_narrow_hz,
float dll_bw_narrow_hz,
int extend_correlation_ms,
float early_late_space_chips);
/*!
* \brief This class implements a DLL + PLL tracking loop block
*/
class gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc: public gr::block
{
public:
~gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc();
void set_channel(unsigned int channel);
void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro);
void start_tracking();
int general_work (int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private:
friend gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc_sptr
gps_l1_ca_dll_pll_c_aid_make_tracking_fpga_sc(long if_freq,
long fs_in, unsigned
int vector_length,
bool dump,
std::string dump_filename,
float pll_bw_hz,
float dll_bw_hz,
float pll_bw_narrow_hz,
float dll_bw_narrow_hz,
int extend_correlation_ms,
float early_late_space_chips);
gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc(long if_freq,
long fs_in, unsigned
int vector_length,
bool dump,
std::string dump_filename,
float pll_bw_hz,
float dll_bw_hz,
float pll_bw_narrow_hz,
float dll_bw_narrow_hz,
int extend_correlation_ms,
float early_late_space_chips);
// tracking configuration vars
unsigned int d_vector_length;
bool d_dump;
Gnss_Synchro* d_acquisition_gnss_synchro;
unsigned int d_channel;
long d_if_freq;
long d_fs_in;
double d_early_late_spc_chips;
int d_n_correlator_taps;
gr_complex* d_ca_code;
lv_16sc_t* d_ca_code_16sc;
float* d_local_code_shift_chips;
//gr_complex* d_correlator_outs;
lv_16sc_t* d_correlator_outs_16sc;
fpga_multicorrelator_8sc multicorrelator_fpga_8sc;
// remaining code phase and carrier phase between tracking loops
double d_rem_code_phase_samples;
double d_rem_code_phase_chips;
double d_rem_carrier_phase_rad;
int d_rem_code_phase_integer_samples;
// PLL and DLL filter library
Tracking_2nd_DLL_filter d_code_loop_filter;
Tracking_FLL_PLL_filter d_carrier_loop_filter;
// acquisition
double d_acq_code_phase_samples;
double d_acq_carrier_doppler_hz;
// tracking vars
float d_dll_bw_hz;
float d_pll_bw_hz;
float d_dll_bw_narrow_hz;
float d_pll_bw_narrow_hz;
double d_code_freq_chips;
double d_code_phase_step_chips;
double d_carrier_doppler_hz;
double d_carrier_phase_step_rad;
double d_acc_carrier_phase_cycles;
double d_code_phase_samples;
double d_pll_to_dll_assist_secs_Ti;
double d_carr_phase_error_secs_Ti;
double d_code_error_chips_Ti;
double d_preamble_timestamp_s;
int d_extend_correlation_ms;
bool d_enable_extended_integration;
bool d_preamble_synchronized;
double d_code_error_filt_chips_s;
double d_code_error_filt_chips_Ti;
void msg_handler_preamble_index(pmt::pmt_t msg);
// symbol history to detect bit transition
std::deque<lv_16sc_t> d_E_history;
std::deque<lv_16sc_t> d_P_history;
std::deque<lv_16sc_t> d_L_history;
//Integration period in samples
int d_correlation_length_samples;
//processing samples counters
unsigned long int d_sample_counter;
unsigned long int d_acq_sample_stamp;
// CN0 estimation and lock detector
int d_cn0_estimation_counter;
gr_complex* d_Prompt_buffer;
double d_carrier_lock_test;
double d_CN0_SNV_dB_Hz;
double d_carrier_lock_threshold;
int d_carrier_lock_fail_counter;
// control vars
bool d_enable_tracking;
bool d_pull_in;
// file dump
std::string d_dump_filename;
std::ofstream d_dump_file;
std::map<std::string, std::string> systemName;
std::string sys;
};
#endif //GNSS_SDR_GPS_L1_CA_DLL_PLL_C_AID_TRACKING_FPGA_SC_H

View File

@ -30,9 +30,10 @@ if(ENABLE_CUDA)
endif(ENABLE_CUDA)
set(TRACKING_LIB_SOURCES
cpu_multicorrelator.cc
cpu_multicorrelator_16sc.cc
cpu_multicorrelator_16sc.cc
lock_detectors.cc
tcp_communication.cc
tcp_packet_data.cc
@ -43,6 +44,10 @@ set(TRACKING_LIB_SOURCES
tracking_loop_filter.cc
)
if(ENABLE_FPGA)
SET(TRACKING_LIB_SOURCES ${TRACKING_LIB_SOURCES} fpga_multicorrelator_8sc.cc)
endif(ENABLE_FPGA)
include_directories(
$(CMAKE_CURRENT_SOURCE_DIR)
${CMAKE_SOURCE_DIR}/src/core/system_parameters

View File

@ -0,0 +1,425 @@
/*!
* \file fpga_multicorrelator_8sc.cc
* \brief High optimized FPGA vector correlator class
* \authors <ul>
* <li> Marc Majoral, 2017. mmajoral(at)cttc.cat
* <li> Javier Arribas, 2015. jarribas(at)cttc.es
* </ul>
*
* Class that controls and executes a high optimized vector correlator
* class in the FPGA
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "fpga_multicorrelator_8sc.h"
#include <cmath>
// FPGA stuff
#include <new>
// libraries used by DMA test code and GIPO test code
#include <stdio.h>
#include <fcntl.h>
#include <unistd.h>
#include <errno.h>
// libraries used by DMA test code
#include <sys/stat.h>
#include <stdint.h>
#include <unistd.h>
#include <assert.h>
// libraries used by GPIO test code
#include <stdlib.h>
#include <signal.h>
#include <sys/mman.h>
// logging
#include <glog/logging.h>
#define PAGE_SIZE 0x10000
#define MAX_LENGTH_DEVICEIO_NAME 50
#define CODE_RESAMPLER_NUM_BITS_PRECISION 20
#define CODE_PHASE_STEP_CHIPS_NUM_NBITS CODE_RESAMPLER_NUM_BITS_PRECISION
#define pwrtwo(x) (1 << (x))
#define MAX_CODE_RESAMPLER_COUNTER pwrtwo(CODE_PHASE_STEP_CHIPS_NUM_NBITS) // 2^CODE_PHASE_STEP_CHIPS_NUM_NBITS
#define PHASE_CARR_NBITS 32
#define PHASE_CARR_NBITS_INT 1
#define PHASE_CARR_NBITS_FRAC PHASE_CARR_NBITS - PHASE_CARR_NBITS_INT
bool fpga_multicorrelator_8sc::init(
int max_signal_length_samples,
int n_correlators)
{
size_t size = max_signal_length_samples * sizeof(lv_16sc_t);
d_n_correlators = n_correlators;
// instantiate variable length vectors
d_initial_index = static_cast<unsigned*>(volk_gnsssdr_malloc(n_correlators * sizeof(unsigned), volk_gnsssdr_get_alignment()));
d_initial_interp_counter = static_cast<unsigned*>(volk_gnsssdr_malloc(n_correlators * sizeof(unsigned), volk_gnsssdr_get_alignment()));
return true;
}
void fpga_multicorrelator_8sc::set_initial_sample(int samples_offset)
{
d_initial_sample_counter = samples_offset;
}
bool fpga_multicorrelator_8sc::set_local_code_and_taps(
int code_length_chips,
const lv_16sc_t* local_code_in,
float *shifts_chips)
{
d_local_code_in = local_code_in;
d_shifts_chips = shifts_chips;
d_code_length_chips = code_length_chips;
fpga_multicorrelator_8sc::fpga_configure_tracking_gps_local_code();
return true;
}
bool fpga_multicorrelator_8sc::set_output_vectors(lv_16sc_t* corr_out)
{
// Save CPU pointers
d_corr_out = corr_out;
return true;
}
void fpga_multicorrelator_8sc::update_local_code(int correlator_length_samples, float rem_code_phase_chips, float code_phase_step_chips)
{
d_rem_code_phase_chips = rem_code_phase_chips;
fpga_multicorrelator_8sc::fpga_compute_code_shift_parameters();
fpga_multicorrelator_8sc::fpga_configure_code_parameters_in_fpga();
}
bool fpga_multicorrelator_8sc::Carrier_wipeoff_multicorrelator_resampler(
float rem_carrier_phase_in_rad,
float phase_step_rad,
float rem_code_phase_chips,
float code_phase_step_chips,
int signal_length_samples)
{
update_local_code(signal_length_samples, rem_code_phase_chips, code_phase_step_chips);
d_rem_carrier_phase_in_rad = rem_carrier_phase_in_rad;
d_code_phase_step_chips = code_phase_step_chips;
d_phase_step_rad = phase_step_rad;
d_correlator_length_samples = signal_length_samples;
fpga_multicorrelator_8sc::fpga_compute_signal_parameters_in_fpga();
fpga_multicorrelator_8sc::fpga_configure_signal_parameters_in_fpga();
fpga_multicorrelator_8sc::fpga_launch_multicorrelator_fpga();
int irq_count;
ssize_t nb;
// wait for interrupt
nb=read(d_fd, &irq_count, sizeof(irq_count));
if (nb != sizeof(irq_count))
{
printf("Tracking_module Read failed to retrive 4 bytes!\n");
printf("Tracking_module Interrupt number %d\n", irq_count);
}
fpga_multicorrelator_8sc::read_tracking_gps_results();
return true;
}
fpga_multicorrelator_8sc::fpga_multicorrelator_8sc()
{
d_local_code_in = nullptr;
d_shifts_chips = nullptr;
d_corr_out = nullptr;
d_code_length_chips = 0;
d_n_correlators = 0;
}
fpga_multicorrelator_8sc::~fpga_multicorrelator_8sc()
{
close(d_fd);
}
bool fpga_multicorrelator_8sc::free()
{
// unlock the hardware
fpga_multicorrelator_8sc::unlock_channel(); // unlock the channel
// free the FPGA dynamically created variables
if (d_initial_index != nullptr)
{
volk_gnsssdr_free(d_initial_index);
d_initial_index = nullptr;
}
if (d_initial_interp_counter != nullptr)
{
volk_gnsssdr_free(d_initial_interp_counter);
d_initial_interp_counter = nullptr;
}
return true;
}
void fpga_multicorrelator_8sc::set_channel(unsigned int channel)
{
d_channel = channel;
snprintf(d_device_io_name, MAX_LENGTH_DEVICEIO_NAME, "/dev/uio%d",d_channel);
printf("Opening Device Name : %s\n", d_device_io_name);
if ((d_fd = open(d_device_io_name, O_RDWR | O_SYNC )) == -1)
{
LOG(WARNING) << "Cannot open deviceio" << d_device_io_name;
}
d_map_base = (volatile unsigned *)mmap(NULL, PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED, d_fd,0);
if (d_map_base == (void *) -1)
{
LOG(WARNING) << "Cannot map the FPGA tracking module " << d_channel << "into user memory";
}
// sanity check : check test register
unsigned writeval = 0x55AA;
unsigned readval;
readval = fpga_multicorrelator_8sc::fpga_acquisition_test_register(writeval);
if (writeval != readval)
{
LOG(WARNING) << "Test register sanity check failed";
}
else
{
LOG(INFO) << "Test register sanity check success !";
}
}
unsigned fpga_multicorrelator_8sc::fpga_acquisition_test_register(unsigned writeval)
{
unsigned readval;
// write value to test register
d_map_base[15] = writeval;
// read value from test register
readval = d_map_base[15];
// return read value
return readval;
}
void fpga_multicorrelator_8sc::fpga_configure_tracking_gps_local_code(void)
{
int k,s;
unsigned temp;
unsigned *ena_write_signals;
ena_write_signals = new unsigned[d_n_correlators];
ena_write_signals[0] = 0x00000000;
ena_write_signals[1] = 0x20000000;
for (s = 2; s < d_n_correlators; s++)
{
ena_write_signals[s]= ena_write_signals[s-1]*2; //0x40000000;
}
for (s = 0; s < d_n_correlators; s++)
{
// clear memory address counter
d_map_base[11] = 0x10000000;
// write correlator 0
for (k = 0; k < d_code_length_chips; k++)
{
if (lv_creal(d_local_code_in[k]) == 1)
{
temp = 1;
}
else
{
temp = 0;
}
d_map_base[11] = 0x0C000000 | (temp & 0xFFFF) | ena_write_signals[s];
}
}
delete [] ena_write_signals;
}
void fpga_multicorrelator_8sc::fpga_compute_code_shift_parameters(void)
{
float tempvalues[3];
float tempvalues2[3];
float tempvalues3[3];
int i;
for (i = 0; i < d_n_correlators; i++)
{
// initial index calculation
tempvalues[i] = floor(d_shifts_chips[i] + d_rem_code_phase_chips);
if (tempvalues[i] < 0)
{
tempvalues2[i] = tempvalues[i] + d_code_length_chips; // % operator does not work as in Matlab with negative numbers
}
else
{
tempvalues2[i] = tempvalues[i];
}
d_initial_index[i] = (unsigned) ((int) tempvalues2[i]) % d_code_length_chips;
// initial interpolator counter calculation
tempvalues3[i] = fmod(d_shifts_chips[i]+ d_rem_code_phase_chips,1.0);
if (tempvalues3[i] < 0)
{
tempvalues3[i] = tempvalues3[i] + 1.0; // fmod operator does not work as in Matlab with negative numbers
}
d_initial_interp_counter[i] = (unsigned) floor(MAX_CODE_RESAMPLER_COUNTER * tempvalues3[i]);
}
}
void fpga_multicorrelator_8sc::fpga_configure_code_parameters_in_fpga(void)
{
int i;
for (i = 0; i < d_n_correlators; i++)
{
d_map_base[1+i] = d_initial_index[i];
d_map_base[1 + d_n_correlators + i] = d_initial_interp_counter[i];
}
d_map_base[8] = d_code_length_chips - 1; // number of samples - 1
}
void fpga_multicorrelator_8sc::fpga_compute_signal_parameters_in_fpga(void)
{
float d_rem_carrier_phase_in_rad_temp;
float d_phase_step_rad_int_temp;
d_code_phase_step_chips_num = (unsigned) roundf(MAX_CODE_RESAMPLER_COUNTER * d_code_phase_step_chips);
if (d_rem_carrier_phase_in_rad > M_PI)
{
d_rem_carrier_phase_in_rad_temp = -2*M_PI + d_rem_carrier_phase_in_rad;
}
else if (d_rem_carrier_phase_in_rad < - M_PI)
{
d_rem_carrier_phase_in_rad_temp = 2*M_PI + d_rem_carrier_phase_in_rad;
}
else
{
d_rem_carrier_phase_in_rad_temp = d_rem_carrier_phase_in_rad;
}
d_rem_carr_phase_rad_int = (int) roundf((fabs(d_rem_carrier_phase_in_rad_temp)/M_PI)*pow(2, PHASE_CARR_NBITS_FRAC));
if (d_rem_carrier_phase_in_rad_temp < 0)
{
d_rem_carr_phase_rad_int = -d_rem_carr_phase_rad_int;
}
d_phase_step_rad_int = (int) roundf((fabs(d_phase_step_rad)/M_PI)*pow(2, PHASE_CARR_NBITS_FRAC)); // the FPGA accepts a range for the phase step between -pi and +pi
if (d_phase_step_rad < 0)
{
d_phase_step_rad_int = -d_phase_step_rad_int;
}
}
void fpga_multicorrelator_8sc::fpga_configure_signal_parameters_in_fpga(void)
{
d_map_base[0] = d_code_phase_step_chips_num;
d_map_base[7] = d_correlator_length_samples - 1;
d_map_base[9] = d_rem_carr_phase_rad_int;
d_map_base[10] = d_phase_step_rad_int;
d_map_base[12] = 0; // lock the channel
d_map_base[13] = d_initial_sample_counter;
}
void fpga_multicorrelator_8sc::fpga_launch_multicorrelator_fpga(void)
{
// enable interrupts
int reenable = 1;
write(d_fd, (void *)&reenable, sizeof(int));
d_map_base[14] = 0; // writing anything to reg 14 launches the tracking
}
void fpga_multicorrelator_8sc::read_tracking_gps_results(void)
{
int *readval_real;
int *readval_imag;
int k;
readval_real = new int[d_n_correlators];
readval_imag = new int[d_n_correlators];
for (k =0 ; k < d_n_correlators; k++)
{
readval_real[k] = d_map_base[1 + k];
if (readval_real[k] >= 1048576) // 0x100000 (21 bits two's complement)
{
readval_real[k] = -2097152 + readval_real[k];
}
readval_real[k] = readval_real[k] * 2; // the results are shifted two bits to the left due to the complex multiplier in the FPGA
}
for (k = 0; k < d_n_correlators; k++)
{
readval_imag[k] = d_map_base[1 + d_n_correlators + k];
if (readval_imag[k] >= 1048576) // 0x100000 (21 bits two's complement)
{
readval_imag[k] = -2097152 + readval_imag[k];
}
readval_imag[k] = readval_imag[k] * 2; // the results are shifted two bits to the left due to the complex multiplier in the FPGA
}
for (k = 0; k < d_n_correlators; k++)
{
d_corr_out[k] = lv_cmake(readval_real[k], readval_imag[k]);
}
delete[] readval_real;
delete[] readval_imag;
}
void fpga_multicorrelator_8sc::unlock_channel(void)
{
// unlock the channel to let the next samples go through
d_map_base[12] = 1; // unlock the channel
}

View File

@ -0,0 +1,105 @@
/*!
* \file fpga_multicorrelator_8sc.h
* \brief High optimized FPGA vector correlator class for lv_16sc_t (short int complex)
* \authors <ul>
* <li> Marc Majoral, 2017. mmajoral(at)cttc.cat
* <li> Javier Arribas, 2016. jarribas(at)cttc.es
* </ul>
*
* Class that controls and executes a high optimized vector correlator
* class in the FPGA
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_FPGA_MULTICORRELATOR_8SC_H_
#define GNSS_SDR_FPGA_MULTICORRELATOR_8SC_H_
#include <volk_gnsssdr/volk_gnsssdr.h>
#define MAX_LENGTH_DEVICEIO_NAME 50
/*!
* \brief Class that implements carrier wipe-off and correlators.
*/
class fpga_multicorrelator_8sc
{
public:
fpga_multicorrelator_8sc();
~fpga_multicorrelator_8sc();
bool init(int max_signal_length_samples, int n_correlators);
bool set_local_code_and_taps(int code_length_chips, const lv_16sc_t* local_code_in, float *shifts_chips);
bool set_output_vectors(lv_16sc_t* corr_out);
void update_local_code(int correlator_length_samples, float rem_code_phase_chips, float code_phase_step_chips);
bool Carrier_wipeoff_multicorrelator_resampler(float rem_carrier_phase_in_rad, float phase_step_rad, float rem_code_phase_chips, float code_phase_step_chips, int signal_length_samples);
bool free();
void set_channel(unsigned int channel);
void set_initial_sample(int samples_offset);
private:
const lv_16sc_t *d_local_code_in;
lv_16sc_t *d_corr_out;
float *d_shifts_chips;
int d_code_length_chips;
int d_n_correlators;
// data related to the hardware module and the driver
char d_device_io_name[MAX_LENGTH_DEVICEIO_NAME]; // driver io name
int d_fd; // driver descriptor
volatile unsigned *d_map_base; // driver memory map
// configuration data received from the interface
unsigned int d_channel; // channel number
unsigned d_ncorrelators; // number of correlators
unsigned d_correlator_length_samples;
float d_rem_code_phase_chips;
float d_code_phase_step_chips;
float d_rem_carrier_phase_in_rad;
float d_phase_step_rad;
// configuration data computed in the format that the FPGA expects
unsigned *d_initial_index;
unsigned *d_initial_interp_counter;
unsigned d_code_phase_step_chips_num;
int d_rem_carr_phase_rad_int;
int d_phase_step_rad_int;
unsigned d_initial_sample_counter;
// FPGA private functions
unsigned fpga_acquisition_test_register(unsigned writeval);
void fpga_configure_tracking_gps_local_code(void);
void fpga_compute_code_shift_parameters(void);
void fpga_configure_code_parameters_in_fpga(void);
void fpga_compute_signal_parameters_in_fpga(void);
void fpga_configure_signal_parameters_in_fpga(void);
void fpga_launch_multicorrelator_fpga(void);
void read_tracking_gps_results(void);
void unlock_channel(void);
};
#endif /* GNSS_SDR_FPGA_MULTICORRELATOR_H_ */

View File

@ -40,16 +40,14 @@ endif(GTEST_INCLUDE_DIRS)
set(GTEST_COMPILER -DCMAKE_CXX_COMPILER=${CMAKE_CXX_COMPILER} -DCMAKE_C_COMPILER=${CMAKE_C_COMPILER})
set(TOOLCHAIN_ARG "")
if(EXISTS $ENV{OECORE_TARGET_SYSROOT})
set(GTEST_COMPILER "")
set(TOOLCHAIN_ARG "-DCMAKE_TOOLCHAIN_FILE=${CMAKE_CURRENT_SOURCE_DIR}/../../cmake/Toolchains/oe-sdk_cross.cmake")
endif(EXISTS $ENV{OECORE_TARGET_SYSROOT})
if(NOT ${GTEST_DIR_LOCAL})
# if GTEST_DIR is not defined, we download and build it
set(gtest_RELEASE 1.8.0)
if(EXISTS $ENV{OECORE_TARGET_SYSROOT})
set(GTEST_COMPILER "")
set(TOOLCHAIN_ARG -DCMAKE_TOOLCHAIN_FILE=${CMAKE_CURRENT_SOURCE_DIR}/../../cmake/Toolchains/oe-sdk_cross.cmake)
endif(EXISTS $ENV{OECORE_TARGET_SYSROOT})
ExternalProject_Add(
gtest-${gtest_RELEASE}
GIT_REPOSITORY https://github.com/google/googletest
@ -132,60 +130,88 @@ if(OPENCL_FOUND)
add_definitions(-DOPENCL_BLOCKS_TEST=1)
endif(OPENCL_FOUND)
if (ENABLE_CUDA)
add_definitions(-DCUDA_BLOCKS_TEST=1)
if(ENABLE_CUDA)
add_definitions(-DCUDA_BLOCKS_TEST=1)
endif(ENABLE_CUDA)
if(ENABLE_FPGA)
add_definitions(-DFPGA_BLOCKS_TEST=1)
endif(ENABLE_FPGA)
################################################################################
# Optional generator
################################################################################
if(ENABLE_UNIT_TESTING_EXTRA OR ENABLE_SYSTEM_TESTING_EXTRA)
if(ENABLE_UNIT_TESTING_EXTRA OR ENABLE_SYSTEM_TESTING_EXTRA OR ENABLE_FPGA)
if(ENABLE_FPGA)
set(CROSS_INSTALL_DIR "-DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}")
if(EXISTS $ENV{OECORE_TARGET_SYSROOT})
set(CROSS_INSTALL_DIR "${CROSS_INSTALL_DIR} -DBOOST_ROOT=$ENV{OECORE_TARGET_SYSROOT}/usr")
endif(EXISTS $ENV{OECORE_TARGET_SYSROOT})
else(ENABLE_FPGA)
set(CROSS_INSTALL_DIR "")
endif(ENABLE_FPGA)
ExternalProject_Add(
gnss-sim
GIT_REPOSITORY https://bitbucket.org/jarribas/gnss-simulator
GIT_TAG master
SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gnss-sim
BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/../../gnss-sim
CMAKE_ARGS ${GTEST_COMPILER} ${TOOLCHAIN_ARG}
CMAKE_ARGS ${GTEST_COMPILER} ${TOOLCHAIN_ARG} ${CROSS_INSTALL_DIR}
UPDATE_COMMAND ""
PATCH_COMMAND ""
INSTALL_COMMAND ""
)
set(SW_GENERATOR_BIN ${CMAKE_CURRENT_BINARY_DIR}/../../gnss-sim/gnss_sim)
add_definitions(-DSW_GENERATOR_BIN="${SW_GENERATOR_BIN}")
add_definitions(-DDEFAULT_RINEX_NAV="${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/brdc3540.14n")
add_definitions(-DDEFAULT_POSITION_FILE="${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/circle.csv")
if(ENABLE_INSTALL_TESTS)
install(PROGRAMS ${CMAKE_CURRENT_BINARY_DIR}/../../gnss-sim/gnss_sim DESTINATION bin)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/brdc3540.14n DESTINATION share/gnss-sim)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/circle.csv DESTINATION share/gnss-sim)
set(SW_GENERATOR_BIN ${CMAKE_INSTALL_PREFIX}/bin/gnss_sim)
add_definitions(-DSW_GENERATOR_BIN="${SW_GENERATOR_BIN}")
add_definitions(-DDEFAULT_RINEX_NAV="${CMAKE_INSTALL_PREFIX}/share/gnss-sim/brdc3540.14n")
add_definitions(-DDEFAULT_POSITION_FILE="${CMAKE_INSTALL_PREFIX}/share/gnss-sim/circle.csv")
else(ENABLE_INSTALL_TESTS)
set(SW_GENERATOR_BIN ${CMAKE_CURRENT_BINARY_DIR}/../../gnss-sim/gnss_sim)
add_definitions(-DSW_GENERATOR_BIN="${SW_GENERATOR_BIN}")
add_definitions(-DDEFAULT_RINEX_NAV="${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/brdc3540.14n")
add_definitions(-DDEFAULT_POSITION_FILE="${CMAKE_CURRENT_BINARY_DIR}/../../../thirdparty/gnss-sim/circle.csv")
endif(ENABLE_INSTALL_TESTS)
################################################################################
# Local installation of GPSTk http://www.gpstk.org/
################################################################################
find_package(GPSTK)
if(NOT GPSTK_FOUND OR ENABLE_OWN_GPSTK)
set(gpstk_RELEASE "2.9")
ExternalProject_Add(
gpstk-${gpstk_RELEASE}
GIT_REPOSITORY https://github.com/SGL-UT/GPSTk
GIT_TAG v${gpstk_RELEASE}
SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}
BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/../../gpstk-${gpstk_RELEASE}
CMAKE_ARGS ${GTEST_COMPILER} ${TOOLCHAIN_ARG} -DCMAKE_INSTALL_PREFIX=${CMAKE_SOURCE_DIR}/thirdparty/gpstk-${gpstk_RELEASE}/install -DBUILD_EXT=OFF -DBUILD_PYTHON=OFF
UPDATE_COMMAND ""
PATCH_COMMAND ""
)
set(GPSTK_INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/include CACHE PATH "Local GPSTK headers")
add_library(gpstk UNKNOWN IMPORTED)
set_property(TARGET gpstk PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/lib/${CMAKE_FIND_LIBRARY_PREFIXES}gpstk${CMAKE_SHARED_LIBRARY_SUFFIX})
add_dependencies(gpstk gpstk-${gpstk_RELEASE})
set(GPSTK_BINDIR ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/bin/ )
add_definitions(-DGPSTK_BINDIR="${GPSTK_BINDIR}")
set(gpstk_libs gpstk)
if(NOT ENABLE_FPGA)
set(gpstk_RELEASE "2.9")
ExternalProject_Add(
gpstk-${gpstk_RELEASE}
GIT_REPOSITORY https://github.com/SGL-UT/GPSTk
GIT_TAG v${gpstk_RELEASE}
SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}
BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/../../gpstk-${gpstk_RELEASE}
CMAKE_ARGS ${GTEST_COMPILER} ${TOOLCHAIN_ARG} -DCMAKE_INSTALL_PREFIX=${CMAKE_SOURCE_DIR}/thirdparty/gpstk-${gpstk_RELEASE}/install -DBUILD_EXT=OFF -DBUILD_PYTHON=OFF
UPDATE_COMMAND ""
PATCH_COMMAND ""
)
set(GPSTK_INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/include CACHE PATH "Local GPSTK headers")
add_library(gpstk UNKNOWN IMPORTED)
set_property(TARGET gpstk PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/lib/${CMAKE_FIND_LIBRARY_PREFIXES}gpstk${CMAKE_SHARED_LIBRARY_SUFFIX})
add_dependencies(gpstk gpstk-${gpstk_RELEASE})
set(GPSTK_BINDIR ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/gpstk-${gpstk_RELEASE}/install/bin/ )
add_definitions(-DGPSTK_BINDIR="${GPSTK_BINDIR}")
set(gpstk_libs gpstk)
set(OWN_GPSTK True)
else(NOT ENABLE_FPGA)
message(STATUS "GPSTk has not been found, try to install it on target.")
message(STATUS "Some extra tests requiring GPSTk will not be built.")
endif(NOT ENABLE_FPGA)
else(NOT GPSTK_FOUND OR ENABLE_OWN_GPSTK)
set(gpstk_libs ${GPSTK_LIBRARIES})
set(GPSTK_INCLUDE_DIRS ${GPSTK_INCLUDE_DIR})
set(GPSTK_BINDIR ${GPSTK_LIBRARY}/../bin/ )
add_definitions(-DGPSTK_BINDIR="${GPSTK_BINDIR}")
endif(NOT GPSTK_FOUND OR ENABLE_OWN_GPSTK)
endif(ENABLE_UNIT_TESTING_EXTRA OR ENABLE_SYSTEM_TESTING_EXTRA)
endif(ENABLE_UNIT_TESTING_EXTRA OR ENABLE_SYSTEM_TESTING_EXTRA OR ENABLE_FPGA)
if(ENABLE_UNIT_TESTING_EXTRA)
@ -194,14 +220,24 @@ if(ENABLE_UNIT_TESTING_EXTRA)
message(STATUS "Downloading some data files for testing...")
file(DOWNLOAD https://sourceforge.net/projects/gnss-sdr/files/data/gps_l2c_m_prn7_5msps.dat ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/signal_samples/gps_l2c_m_prn7_5msps.dat
SHOW_PROGRESS
EXPECTED_HASH MD5=a6fcbefe155137945d3c33c5ef7bd0f9 )
EXPECTED_HASH MD5=a6fcbefe155137945d3c33c5ef7bd0f9 )
endif(NOT EXISTS ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples/gps_l2c_m_prn7_5msps.dat)
if(ENABLE_INSTALL_TESTS)
install(FILES ${CMAKE_CURRENT_SOURCE_DIR}/../../thirdparty/signal_samples/gps_l2c_m_prn7_5msps.dat DESTINATION share/gnss-sdr/signal_samples)
endif(ENABLE_INSTALL_TESTS)
endif(ENABLE_UNIT_TESTING_EXTRA)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GSoC_CTTC_capture_2012_07_26_4Msps_4ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/Galileo_E1_ID_1_Fs_4Msps_8ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GPS_L1_CA_ID_1_Fs_4Msps_2ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
add_definitions(-DTEST_PATH="${CMAKE_SOURCE_DIR}/thirdparty/")
if(ENABLE_INSTALL_TESTS)
install(FILES ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GSoC_CTTC_capture_2012_07_26_4Msps_4ms.dat DESTINATION share/gnss-sdr/signal_samples)
install(FILES ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/Galileo_E1_ID_1_Fs_4Msps_8ms.dat DESTINATION share/gnss-sdr/signal_samples)
install(FILES ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GPS_L1_CA_ID_1_Fs_4Msps_2ms.dat DESTINATION share/gnss-sdr/signal_samples)
add_definitions(-DTEST_PATH="${CMAKE_INSTALL_PREFIX}/share/gnss-sdr/")
else(ENABLE_INSTALL_TESTS)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GSoC_CTTC_capture_2012_07_26_4Msps_4ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/Galileo_E1_ID_1_Fs_4Msps_8ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
file(COPY ${CMAKE_SOURCE_DIR}/src/tests/signal_samples/GPS_L1_CA_ID_1_Fs_4Msps_2ms.dat DESTINATION ${CMAKE_SOURCE_DIR}/thirdparty/signal_samples)
add_definitions(-DTEST_PATH="${CMAKE_SOURCE_DIR}/thirdparty/")
endif(ENABLE_INSTALL_TESTS)
include_directories(
${GTEST_INCLUDE_DIRECTORIES}
@ -254,13 +290,9 @@ include_directories(
if(ENABLE_UNIT_TESTING)
if( ${ARMADILLO_VERSION_STRING} STRGREATER "5.300") # make sure interp1 is present
add_definitions(-DMODERN_ARMADILLO)
endif( ${ARMADILLO_VERSION_STRING} STRGREATER "5.300")
endif( ${ARMADILLO_VERSION_STRING} STRGREATER "5.300")
add_executable(run_tests ${CMAKE_CURRENT_SOURCE_DIR}/test_main.cc)
add_custom_command(TARGET run_tests POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:run_tests>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:run_tests>)
target_link_libraries(run_tests ${CLANG_FLAGS}
${Boost_LIBRARIES}
${GFlags_LIBS}
@ -286,8 +318,117 @@ if(ENABLE_UNIT_TESTING)
if(NOT ${GTEST_DIR_LOCAL})
add_dependencies(run_tests gtest-${gtest_RELEASE})
endif(NOT ${GTEST_DIR_LOCAL})
if(ENABLE_INSTALL_TESTS)
if(EXISTS ${CMAKE_SOURCE_DIR}/install/run_tests)
file(REMOVE ${CMAKE_SOURCE_DIR}/install/run_tests)
endif(EXISTS ${CMAKE_SOURCE_DIR}/install/run_tests)
install(TARGETS run_tests RUNTIME DESTINATION bin COMPONENT "run_tests")
else(ENABLE_INSTALL_TESTS)
add_custom_command(TARGET run_tests POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:run_tests>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:run_tests>)
endif(ENABLE_INSTALL_TESTS)
endif(ENABLE_UNIT_TESTING)
if(ENABLE_FPGA)
add_executable(gps_l1_ca_dll_pll_tracking_test_fpga
${CMAKE_CURRENT_SOURCE_DIR}/single_test_main.cc
${CMAKE_CURRENT_SOURCE_DIR}/unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc )
target_link_libraries(gps_l1_ca_dll_pll_tracking_test_fpga
${Boost_LIBRARIES}
${GFlags_LIBS}
${GLOG_LIBRARIES}
${GTEST_LIBRARIES}
${GNURADIO_RUNTIME_LIBRARIES}
${GNURADIO_BLOCKS_LIBRARIES}
${ARMADILLO_LIBRARIES}
${VOLK_LIBRARIES}
channel_fsm
gnss_sp_libs
gnss_rx
gnss_system_parameters
signal_processing_testing_lib
)
install(TARGETS gps_l1_ca_dll_pll_tracking_test_fpga
RUNTIME DESTINATION bin
COMPONENT "fpga-test" )
endif(ENABLE_FPGA)
################################################################################
# System testing
################################################################################
if(ENABLE_SYSTEM_TESTING)
set(HOST_SYSTEM "Unknown")
if(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
set(HOST_SYSTEM "GNU/Linux ${LINUX_DISTRIBUTION} ${LINUX_VER} ${ARCH_}")
endif(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
set(HOST_SYSTEM "MacOS")
endif(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
add_definitions(-DHOST_SYSTEM="${HOST_SYSTEM}")
add_executable(ttff
${CMAKE_CURRENT_SOURCE_DIR}/system-tests/ttff_gps_l1.cc )
if(NOT ${GTEST_DIR_LOCAL})
add_dependencies(ttff gtest-${gtest_RELEASE})
else(NOT ${GTEST_DIR_LOCAL})
add_dependencies(ttff gtest)
endif(NOT ${GTEST_DIR_LOCAL})
target_link_libraries(ttff
${Boost_LIBRARIES}
${GFlags_LIBS}
${GLOG_LIBRARIES}
${GTEST_LIBRARIES}
${GNURADIO_RUNTIME_LIBRARIES}
${GNURADIO_BLOCKS_LIBRARIES}
${GNURADIO_FILTER_LIBRARIES}
${GNURADIO_ANALOG_LIBRARIES}
${VOLK_GNSSSDR_LIBRARIES}
gnss_sp_libs
gnss_rx
gnss_system_parameters
)
if(ENABLE_INSTALL_TESTS)
if(EXISTS ${CMAKE_SOURCE_DIR}/install/ttff)
file(REMOVE ${CMAKE_SOURCE_DIR}/install/ttff)
endif(EXISTS ${CMAKE_SOURCE_DIR}/install/ttff)
install(TARGETS ttff RUNTIME DESTINATION bin COMPONENT "ttff")
else(ENABLE_INSTALL_TESTS)
add_custom_command(TARGET ttff POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:ttff>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:ttff> )
endif(ENABLE_INSTALL_TESTS)
if(ENABLE_SYSTEM_TESTING_EXTRA)
if(GPSTK_FOUND OR OWN_GPSTK)
add_executable(obs_gps_l1_system_test ${CMAKE_CURRENT_SOURCE_DIR}/system-tests/obs_gps_l1_system_test.cc)
if(NOT ${GTEST_DIR_LOCAL})
add_dependencies(obs_gps_l1_system_test gtest-${gtest_RELEASE} )
else(NOT ${GTEST_DIR_LOCAL})
add_dependencies(obs_gps_l1_system_test gtest)
endif(NOT ${GTEST_DIR_LOCAL})
include_directories(${GPSTK_INCLUDE_DIRS})
target_link_libraries(obs_gps_l1_system_test ${GFlags_LIBS}
${GLOG_LIBRARIES}
${GTEST_LIBRARIES}
gnss_sp_libs
gnss_rx
${gpstk_libs})
if(ENABLE_INSTALL_TESTS)
if(EXISTS ${CMAKE_SOURCE_DIR}/install/obs_gps_l1_system_test)
file(REMOVE ${CMAKE_SOURCE_DIR}/install/obs_gps_l1_system_test)
endif(EXISTS ${CMAKE_SOURCE_DIR}/install/obs_gps_l1_system_test)
install(TARGETS obs_gps_l1_system_test RUNTIME DESTINATION bin COMPONENT "obs_gps_l1_system_test")
else(ENABLE_INSTALL_TESTS)
add_custom_command(TARGET obs_gps_l1_system_test POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:obs_gps_l1_system_test>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:obs_gps_l1_system_test> )
endif(ENABLE_INSTALL_TESTS)
endif(GPSTK_FOUND OR OWN_GPSTK)
endif(ENABLE_SYSTEM_TESTING_EXTRA)
endif(ENABLE_SYSTEM_TESTING)
#########################################################
@ -466,64 +607,3 @@ endif(NOT ${GTEST_DIR_LOCAL})
add_dependencies(check control_thread_test flowgraph_test gnss_block_test
gnuradio_block_test trk_test)
################################################################################
# System testing
################################################################################
if(ENABLE_SYSTEM_TESTING)
set(HOST_SYSTEM "Unknown")
if(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
set(HOST_SYSTEM "GNU/Linux ${LINUX_DISTRIBUTION} ${LINUX_VER} ${ARCH_}")
endif(${CMAKE_SYSTEM_NAME} MATCHES "Linux")
if(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
set(HOST_SYSTEM "MacOS")
endif(${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
add_definitions(-DHOST_SYSTEM="${HOST_SYSTEM}")
add_executable(ttff
${CMAKE_CURRENT_SOURCE_DIR}/system-tests/ttff_gps_l1.cc )
if(NOT ${GTEST_DIR_LOCAL})
add_dependencies(ttff gtest-${gtest_RELEASE})
else(NOT ${GTEST_DIR_LOCAL})
add_dependencies(ttff gtest)
endif(NOT ${GTEST_DIR_LOCAL})
target_link_libraries(ttff
${Boost_LIBRARIES}
${GFlags_LIBS}
${GLOG_LIBRARIES}
${GTEST_LIBRARIES}
${GNURADIO_RUNTIME_LIBRARIES}
${GNURADIO_BLOCKS_LIBRARIES}
${GNURADIO_FILTER_LIBRARIES}
${GNURADIO_ANALOG_LIBRARIES}
${VOLK_GNSSSDR_LIBRARIES}
gnss_sp_libs
gnss_rx
gnss_system_parameters
)
add_custom_command(TARGET ttff POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:ttff>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:ttff>
)
if(ENABLE_SYSTEM_TESTING_EXTRA)
add_executable(obs_gps_l1_system_test ${CMAKE_CURRENT_SOURCE_DIR}/system-tests/obs_gps_l1_system_test.cc)
if(NOT ${GTEST_DIR_LOCAL})
add_dependencies(obs_gps_l1_system_test gtest-${gtest_RELEASE} )
else(NOT ${GTEST_DIR_LOCAL})
add_dependencies(obs_gps_l1_system_test gtest)
endif(NOT ${GTEST_DIR_LOCAL})
include_directories(${GPSTK_INCLUDE_DIRS})
target_link_libraries(obs_gps_l1_system_test ${GFlags_LIBS}
${GLOG_LIBRARIES}
${GTEST_LIBRARIES}
gnss_sp_libs
gnss_rx
${gpstk_libs})
add_custom_command(TARGET obs_gps_l1_system_test POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy $<TARGET_FILE:obs_gps_l1_system_test>
${CMAKE_SOURCE_DIR}/install/$<TARGET_FILE_NAME:obs_gps_l1_system_test>
)
endif(ENABLE_SYSTEM_TESTING_EXTRA)
endif(ENABLE_SYSTEM_TESTING)

View File

@ -57,11 +57,24 @@ concurrent_queue<Gps_Acq_Assist> global_gps_acq_assist_queue;
concurrent_map<Gps_Acq_Assist> global_gps_acq_assist_map;
using google::LogMessage;
DECLARE_string(log_dir);
int main(int argc, char **argv)
{
google::ParseCommandLineFlags(&argc, &argv, true);
testing::InitGoogleTest(&argc, argv);
google::InitGoogleLogging(argv[0]);
return RUN_ALL_TESTS();
int res = 0;
try
{
res = RUN_ALL_TESTS();
}
catch(...)
{
LOG(WARNING) << "Unexpected catch";
}
google::ShutDownCommandLineFlags();
return res;
}

View File

@ -119,6 +119,10 @@ DECLARE_string(log_dir);
#include "unit-tests/signal-processing-blocks/tracking/gpu_multicorrelator_test.cc"
#endif
#if FPGA_BLOCKS_TEST
#include "unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test_fpga.cc"
#endif
#include "unit-tests/signal-processing-blocks/pvt/rtcm_test.cc"
#include "unit-tests/signal-processing-blocks/pvt/rtcm_printer_test.cc"
#include "unit-tests/signal-processing-blocks/pvt/rinex_printer_test.cc"
@ -132,6 +136,8 @@ DECLARE_string(log_dir);
#endif
#endif
// For GPS NAVIGATION (L1)
concurrent_queue<Gps_Acq_Assist> global_gps_acq_assist_queue;
concurrent_map<Gps_Acq_Assist> global_gps_acq_assist_map;

View File

@ -54,7 +54,7 @@ bool tracking_dump_reader::read_binary_obs()
d_dump_file.read((char *) &aux2, sizeof(double));
}
catch (const std::ifstream::failure &e)
catch (const std::exception &e)
{
return false;
}

View File

@ -40,7 +40,7 @@ bool tracking_true_obs_reader::read_binary_obs()
d_dump_file.read((char *) &prn_delay_chips, sizeof(double));
d_dump_file.read((char *) &tow, sizeof(double));
}
catch (const std::ifstream::failure &e)
catch (const std::exception &e)
{
return false;
}

View File

@ -50,7 +50,8 @@
#include "tracking_interface.h"
#include "in_memory_configuration.h"
#include "gnss_synchro.h"
#include "gps_l1_ca_dll_pll_tracking.h"
//#include "gps_l1_ca_dll_pll_tracking.h"
#include "gps_l1_ca_dll_pll_c_aid_tracking.h"
#include "tracking_true_obs_reader.h"
#include "tracking_dump_reader.h"
#include "signal_generator_flags.h"
@ -353,8 +354,8 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
}) << "Failure opening true observables file" << std::endl;
top_block = gr::make_top_block("Tracking test");
std::shared_ptr<TrackingInterface> tracking = std::make_shared<GpsL1CaDllPllTracking>(config.get(), "Tracking_1C", 1, 1);
//std::shared_ptr<TrackingInterface> tracking = std::make_shared<GpsL1CaDllPllCAidTracking>(config.get(), "Tracking_1C", 1, 1);
//std::shared_ptr<TrackingInterface> tracking = std::make_shared<GpsL1CaDllPllTracking>(config.get(), "Tracking_1C", 1, 1);
std::shared_ptr<TrackingInterface> tracking = std::make_shared<GpsL1CaDllPllCAidTracking>(config.get(), "Tracking_1C", 1, 1);
boost::shared_ptr<GpsL1CADllPllTrackingTest_msg_rx> msg_rx = GpsL1CADllPllTrackingTest_msg_rx_make();
@ -400,6 +401,7 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
tracking->start_tracking();
EXPECT_NO_THROW( {
gettimeofday(&tv, NULL);
begin = tv.tv_sec * 1000000 + tv.tv_usec;
@ -413,28 +415,37 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
long int nepoch = true_obs_data.num_epochs();
std::cout << "True observation epochs=" << nepoch << std::endl;
arma::vec true_timestamp_s = arma::zeros(nepoch, 1);
arma::vec true_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
arma::vec true_Doppler_Hz = arma::zeros(nepoch, 1);
arma::vec true_prn_delay_chips = arma::zeros(nepoch, 1);
arma::vec true_tow_s = arma::zeros(nepoch, 1);
long int epoch_counter = 0;
while(true_obs_data.read_binary_obs())
{
true_timestamp_s(epoch_counter) = true_obs_data.signal_timestamp_s;
true_acc_carrier_phase_cycles(epoch_counter) = true_obs_data.acc_carrier_phase_cycles;
true_Doppler_Hz(epoch_counter) = true_obs_data.doppler_l1_hz;
true_prn_delay_chips(epoch_counter) = true_obs_data.prn_delay_chips;
true_tow_s(epoch_counter) = true_obs_data.tow;
epoch_counter++;
}
//load the measured values
tracking_dump_reader trk_dump;
ASSERT_NO_THROW({
if (trk_dump.open_obs_file(std::string("./tracking_ch_0.dat")) == false)
{
throw std::exception();
};
}) << "Failure opening tracking dump file" << std::endl;
@ -442,11 +453,12 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
nepoch = trk_dump.num_epochs();
std::cout << "Measured observation epochs=" << nepoch << std::endl;
arma::vec trk_timestamp_s = arma::zeros(nepoch, 1);
arma::vec trk_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
arma::vec trk_Doppler_Hz = arma::zeros(nepoch, 1);
arma::vec trk_prn_delay_chips = arma::zeros(nepoch, 1);
epoch_counter = 0;
while(trk_dump.read_binary_obs())
{

View File

@ -0,0 +1,585 @@
/*!
* \file gps_l1_ca_dll_pll_tracking_test.cc
* \brief This class implements a tracking test for Galileo_E5a_DLL_PLL_Tracking
* implementation based on some input parameters.
* \author Marc Majoral, 2017. mmajoral(at)cttc.cat
* \author Javier Arribas, 2017. jarribas(at)cttc.es
*
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2012-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <ctime>
#include <iostream>
#include <unistd.h>
#include <armadillo>
#include <boost/thread.hpp>// to test the FPGA we have to create a simultaneous task to send the samples using the DMA and stop the test
#include <boost/chrono.hpp> // temporary for debugging
#include <stdio.h>// FPGA read input file
#include <gnuradio/top_block.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/analog/sig_source_waveform.h>
#include <gnuradio/analog/sig_source_c.h>
#include <gnuradio/blocks/interleaved_char_to_complex.h>
#include <gnuradio/blocks/null_sink.h>
#include <gnuradio/blocks/skiphead.h>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include <gtest/gtest.h>
#include <sys/wait.h>
#include "GPS_L1_CA.h"
#include "gnss_block_factory.h"
#include "gnss_block_interface.h"
#include "tracking_interface.h"
#include "in_memory_configuration.h"
#include "gnss_synchro.h"
#include "gps_l1_ca_dll_pll_c_aid_tracking_fpga.h"
#include "tracking_true_obs_reader.h"
#include "tracking_dump_reader.h"
#include "signal_generator_flags.h"
#include "interleaved_byte_to_complex_short.h"
#define MAX_NUM_TEST_CASES 20
#define MAX_INPUT_SAMPLES_PER_TEST_CASE (8184)
#define MAX_INPUT_SAMPLES_TOTAL MAX_INPUT_SAMPLES_PER_TEST_CASE*MAX_NUM_TEST_CASES
#define DMA_TRANSFER_SIZE 2046
#define MIN_SAMPLES_REMAINING 20000 // number of remaining samples in the DMA that causes the CPU to stop the flowgraph (it has to be a bit alrger than 2x max packet size)
void wait(int seconds)
{
boost::this_thread::sleep_for(boost::chrono::seconds{seconds});
}
void send_tracking_gps_input_samples(FILE *ptr_myfile, int num_remaining_samples, gr::top_block_sptr top_block)
{
int sample_pointer;
int num_samples_transferred = 0;
static int flowgraph_stopped = 0;
char *buffer;
// DMA descriptor
int tx_fd;
tx_fd = open("/dev/loop_tx", O_WRONLY);
if ( tx_fd < 0 )
{
printf("can't open loop device\n");
exit(1);
}
buffer = (char *)malloc(DMA_TRANSFER_SIZE);
if (!buffer)
{
fprintf(stderr, "Memory error!");
}
while(num_remaining_samples > 0)
{
if (num_remaining_samples < MIN_SAMPLES_REMAINING)
{
if (flowgraph_stopped == 0)
{
// stop top module
top_block->stop();
flowgraph_stopped = 1;
}
}
if (num_remaining_samples > DMA_TRANSFER_SIZE)
{
fread(buffer, DMA_TRANSFER_SIZE, 1, ptr_myfile);
assert( DMA_TRANSFER_SIZE == write(tx_fd, &buffer[0], DMA_TRANSFER_SIZE) );
num_remaining_samples = num_remaining_samples - DMA_TRANSFER_SIZE;
num_samples_transferred = num_samples_transferred + DMA_TRANSFER_SIZE;
}
else
{
fread(buffer, num_remaining_samples, 1, ptr_myfile);
assert( num_remaining_samples == write(tx_fd, &buffer[0], num_remaining_samples) );
num_samples_transferred = num_samples_transferred + num_remaining_samples;
num_remaining_samples = 0;
}
}
free(buffer);
close(tx_fd);
}
// thread that sends the samples to the FPGA
void thread(gr::top_block_sptr top_block, const char * file_name)
{
// file descriptor
FILE *ptr_myfile;
int fileLen;
ptr_myfile = fopen(file_name,"rb");
if (!ptr_myfile)
{
printf("Unable to open file!");
}
fseek(ptr_myfile, 0, SEEK_END);
fileLen = ftell(ptr_myfile);
fseek(ptr_myfile, 0, SEEK_SET);
wait(20); // wait for some time to give time to the other thread to program the device
//send_tracking_gps_input_samples(tx_fd, ptr_myfile, fileLen);
send_tracking_gps_input_samples(ptr_myfile, fileLen, top_block);
fclose(ptr_myfile);
}
// ######## GNURADIO BLOCK MESSAGE RECEVER #########
class GpsL1CADllPllTrackingTestFpga_msg_rx;
typedef boost::shared_ptr<GpsL1CADllPllTrackingTestFpga_msg_rx> GpsL1CADllPllTrackingTestFpga_msg_rx_sptr;
GpsL1CADllPllTrackingTestFpga_msg_rx_sptr GpsL1CADllPllTrackingTestFpga_msg_rx_make();
class GpsL1CADllPllTrackingTestFpga_msg_rx : public gr::block
{
private:
friend GpsL1CADllPllTrackingTestFpga_msg_rx_sptr GpsL1CADllPllTrackingTestFpga_msg_rx_make();
void msg_handler_events(pmt::pmt_t msg);
GpsL1CADllPllTrackingTestFpga_msg_rx();
public:
int rx_message;
~GpsL1CADllPllTrackingTestFpga_msg_rx(); //!< Default destructor
};
GpsL1CADllPllTrackingTestFpga_msg_rx_sptr GpsL1CADllPllTrackingTestFpga_msg_rx_make()
{
return GpsL1CADllPllTrackingTestFpga_msg_rx_sptr(new GpsL1CADllPllTrackingTestFpga_msg_rx());
}
void GpsL1CADllPllTrackingTestFpga_msg_rx::msg_handler_events(pmt::pmt_t msg)
{
try
{
long int message = pmt::to_long(msg);
rx_message = message;
}
catch(boost::bad_any_cast& e)
{
LOG(WARNING) << "msg_handler_telemetry Bad any cast!";
rx_message = 0;
}
}
GpsL1CADllPllTrackingTestFpga_msg_rx::GpsL1CADllPllTrackingTestFpga_msg_rx() :
gr::block("GpsL1CADllPllTrackingTestFpga_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0))
{
this->message_port_register_in(pmt::mp("events"));
this->set_msg_handler(pmt::mp("events"), boost::bind(&GpsL1CADllPllTrackingTestFpga_msg_rx::msg_handler_events, this, _1));
rx_message = 0;
}
GpsL1CADllPllTrackingTestFpga_msg_rx::~GpsL1CADllPllTrackingTestFpga_msg_rx()
{}
// ###########################################################
class GpsL1CADllPllTrackingTestFpga: public ::testing::Test
{
public:
std::string generator_binary;
std::string p1;
std::string p2;
std::string p3;
std::string p4;
std::string p5;
const int baseband_sampling_freq = FLAGS_fs_gen_hz;
std::string filename_rinex_obs = FLAGS_filename_rinex_obs;
std::string filename_raw_data = FLAGS_filename_raw_data;
int configure_generator();
int generate_signal();
void check_results_doppler(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value);
void check_results_acc_carrier_phase(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value);
void check_results_codephase(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value);
GpsL1CADllPllTrackingTestFpga()
{
factory = std::make_shared<GNSSBlockFactory>();
config = std::make_shared<InMemoryConfiguration>();
item_size = sizeof(gr_complex);
gnss_synchro = Gnss_Synchro();
}
~GpsL1CADllPllTrackingTestFpga()
{}
void configure_receiver();
gr::top_block_sptr top_block;
std::shared_ptr<GNSSBlockFactory> factory;
std::shared_ptr<InMemoryConfiguration> config;
Gnss_Synchro gnss_synchro;
size_t item_size;
};
int GpsL1CADllPllTrackingTestFpga::configure_generator()
{
// Configure signal generator
generator_binary = FLAGS_generator_binary;
p1 = std::string("-rinex_nav_file=") + FLAGS_rinex_nav_file;
if(FLAGS_dynamic_position.empty())
{
p2 = std::string("-static_position=") + FLAGS_static_position + std::string(",") + std::to_string(FLAGS_duration * 10);
}
else
{
p2 = std::string("-obs_pos_file=") + std::string(FLAGS_dynamic_position);
}
p3 = std::string("-rinex_obs_file=") + FLAGS_filename_rinex_obs; // RINEX 2.10 observation file output
p4 = std::string("-sig_out_file=") + FLAGS_filename_raw_data; // Baseband signal output file. Will be stored in int8_t IQ multiplexed samples
p5 = std::string("-sampling_freq=") + std::to_string(baseband_sampling_freq); //Baseband sampling frequency [MSps]
return 0;
}
int GpsL1CADllPllTrackingTestFpga::generate_signal()
{
int child_status;
char *const parmList[] = { &generator_binary[0], &generator_binary[0], &p1[0], &p2[0], &p3[0], &p4[0], &p5[0], NULL };
int pid;
if ((pid = fork()) == -1)
perror("fork err");
else if (pid == 0)
{
execv(&generator_binary[0], parmList);
std::cout << "Return not expected. Must be an execv err." << std::endl;
std::terminate();
}
waitpid(pid, &child_status, 0);
std::cout << "Signal and Observables RINEX and RAW files created." << std::endl;
return 0;
}
void GpsL1CADllPllTrackingTestFpga::configure_receiver()
{
gnss_synchro.Channel_ID = 0;
gnss_synchro.System = 'G';
std::string signal = "1C";
signal.copy(gnss_synchro.Signal, 2, 0);
gnss_synchro.PRN = FLAGS_test_satellite_PRN;
config->set_property("GNSS-SDR.internal_fs_hz", std::to_string(baseband_sampling_freq));
// Set Tracking
config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_C_Aid_Tracking_Fpga");
config->set_property("Tracking_1C.item_type", "cshort");
config->set_property("Tracking_1C.if", "0");
config->set_property("Tracking_1C.dump", "true");
config->set_property("Tracking_1C.dump_filename", "./tracking_ch_");
config->set_property("Tracking_1C.pll_bw_hz", "30.0");
config->set_property("Tracking_1C.dll_bw_hz", "2.0");
config->set_property("Tracking_1C.early_late_space_chips", "0.5");
}
void GpsL1CADllPllTrackingTestFpga::check_results_doppler(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value)
{
//1. True value interpolation to match the measurement times
arma::vec true_value_interp;
arma::interp1(true_time_s, true_value, meas_time_s, true_value_interp);
//2. RMSE
arma::vec err;
err = meas_value - true_value_interp;
arma::vec err2 = arma::square(err);
double rmse = sqrt(arma::mean(err2));
//3. Mean err and variance
double error_mean = arma::mean(err);
double error_var = arma::var(err);
// 5. Peaks
double max_error = arma::max(err);
double min_error = arma::min(err);
//5. report
std::cout << std::setprecision(10) << "TRK Doppler RMSE=" << rmse
<< ", mean=" << error_mean
<< ", stdev="<< sqrt(error_var) << " (max,min)=" << max_error << "," << min_error << " [Hz]" << std::endl;
}
void GpsL1CADllPllTrackingTestFpga::check_results_acc_carrier_phase(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value)
{
//1. True value interpolation to match the measurement times
arma::vec true_value_interp;
arma::interp1(true_time_s, true_value, meas_time_s, true_value_interp);
//2. RMSE
arma::vec err;
err = meas_value - true_value_interp;
arma::vec err2 = arma::square(err);
double rmse = sqrt(arma::mean(err2));
//3. Mean err and variance
double error_mean = arma::mean(err);
double error_var = arma::var(err);
// 4. Peaks
double max_error = arma::max(err);
double min_error = arma::min(err);
//5. report
std::cout << std::setprecision(10) << "TRK acc carrier phase RMSE=" << rmse
<< ", mean=" << error_mean
<< ", stdev=" << sqrt(error_var) << " (max,min)=" << max_error << "," << min_error << " [Hz]" << std::endl;
}
void GpsL1CADllPllTrackingTestFpga::check_results_codephase(arma::vec true_time_s,
arma::vec true_value,
arma::vec meas_time_s,
arma::vec meas_value)
{
//1. True value interpolation to match the measurement times
arma::vec true_value_interp;
arma::interp1(true_time_s, true_value, meas_time_s, true_value_interp);
//2. RMSE
arma::vec err;
err = meas_value - true_value_interp;
arma::vec err2 = arma::square(err);
double rmse = sqrt(arma::mean(err2));
//3. Mean err and variance
double error_mean = arma::mean(err);
double error_var = arma::var(err);
// 4. Peaks
double max_error = arma::max(err);
double min_error = arma::min(err);
//5. report
std::cout << std::setprecision(10) << "TRK code phase RMSE=" << rmse
<< ", mean=" << error_mean
<< ", stdev=" << sqrt(error_var) << " (max,min)=" << max_error << "," << min_error << " [Chips]" << std::endl;
}
TEST_F(GpsL1CADllPllTrackingTestFpga, ValidationOfResultsFpga)
{
configure_generator();
// DO not generate signal raw signal samples and observations RINEX file by default
//generate_signal();
struct timeval tv;
long long int begin = 0;
long long int end = 0;
configure_receiver();
//open true observables log file written by the simulator
tracking_true_obs_reader true_obs_data;
int test_satellite_PRN = FLAGS_test_satellite_PRN;
std::cout << "Testing satellite PRN=" << test_satellite_PRN << std::endl;
std::string true_obs_file = std::string("./gps_l1_ca_obs_prn");
true_obs_file.append(std::to_string(test_satellite_PRN));
true_obs_file.append(".dat");
ASSERT_NO_THROW({
if (true_obs_data.open_obs_file(true_obs_file) == false)
{
throw std::exception();
};
}) << "Failure opening true observables file" << std::endl;
top_block = gr::make_top_block("Tracking test");
std::shared_ptr<TrackingInterface> tracking = std::make_shared<GpsL1CaDllPllCAidTrackingFpga>(config.get(), "Tracking_1C", 1, 1);
boost::shared_ptr<GpsL1CADllPllTrackingTestFpga_msg_rx> msg_rx = GpsL1CADllPllTrackingTestFpga_msg_rx_make();
// load acquisition data based on the first epoch of the true observations
ASSERT_NO_THROW({
if (true_obs_data.read_binary_obs() == false)
{
throw std::exception();
};
}) << "Failure reading true observables file" << std::endl;
//restart the epoch counter
true_obs_data.restart();
std::cout << "Initial Doppler [Hz]=" << true_obs_data.doppler_l1_hz << " Initial code delay [Chips]=" << true_obs_data.prn_delay_chips << std::endl;
gnss_synchro.Acq_delay_samples = (GPS_L1_CA_CODE_LENGTH_CHIPS - true_obs_data.prn_delay_chips / GPS_L1_CA_CODE_LENGTH_CHIPS) * baseband_sampling_freq * GPS_L1_CA_CODE_PERIOD;
gnss_synchro.Acq_doppler_hz = true_obs_data.doppler_l1_hz;
gnss_synchro.Acq_samplestamp_samples = 0;
ASSERT_NO_THROW( {
tracking->set_channel(gnss_synchro.Channel_ID);
}) << "Failure setting channel." << std::endl;
ASSERT_NO_THROW( {
tracking->set_gnss_synchro(&gnss_synchro);
}) << "Failure setting gnss_synchro." << std::endl;
ASSERT_NO_THROW( {
tracking->connect(top_block);
}) << "Failure connecting tracking to the top_block." << std::endl;
ASSERT_NO_THROW( {
gr::blocks::null_sink::sptr sink = gr::blocks::null_sink::make(sizeof(Gnss_Synchro));
top_block->connect(tracking->get_right_block(), 0, sink, 0);
top_block->msg_connect(tracking->get_right_block(), pmt::mp("events"), msg_rx, pmt::mp("events"));
}) << "Failure connecting the blocks of tracking test." << std::endl;
tracking->start_tracking();
// assemble again the file name in a null terminated string (not available by default in the main program flow)
std::string file = "./" + filename_raw_data;
const char * file_name = file.c_str();
// start thread that sends the DMA samples to the FPGA
boost::thread t{thread, top_block, file_name};
EXPECT_NO_THROW( {
gettimeofday(&tv, NULL);
begin = tv.tv_sec * 1000000 + tv.tv_usec;
top_block->run(); // Start threads and wait
tracking.reset();
gettimeofday(&tv, NULL);
end = tv.tv_sec * 1000000 + tv.tv_usec;
}) << "Failure running the top_block." << std::endl;
// wait until child thread terminates
t.join();
//check results
//load the true values
long int nepoch = true_obs_data.num_epochs();
std::cout << "True observation epochs=" << nepoch << std::endl;
arma::vec true_timestamp_s = arma::zeros(nepoch, 1);
arma::vec true_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
arma::vec true_Doppler_Hz = arma::zeros(nepoch, 1);
arma::vec true_prn_delay_chips = arma::zeros(nepoch, 1);
arma::vec true_tow_s = arma::zeros(nepoch, 1);
long int epoch_counter = 0;
while(true_obs_data.read_binary_obs())
{
true_timestamp_s(epoch_counter) = true_obs_data.signal_timestamp_s;
true_acc_carrier_phase_cycles(epoch_counter) = true_obs_data.acc_carrier_phase_cycles;
true_Doppler_Hz(epoch_counter) = true_obs_data.doppler_l1_hz;
true_prn_delay_chips(epoch_counter) = true_obs_data.prn_delay_chips;
true_tow_s(epoch_counter) = true_obs_data.tow;
epoch_counter++;
}
//load the measured values
tracking_dump_reader trk_dump;
ASSERT_NO_THROW({
if (trk_dump.open_obs_file(std::string("./tracking_ch_0.dat")) == false)
{
throw std::exception();
};
}) << "Failure opening tracking dump file" << std::endl;
nepoch = trk_dump.num_epochs();
std::cout << "Measured observation epochs=" << nepoch << std::endl;
arma::vec trk_timestamp_s = arma::zeros(nepoch, 1);
arma::vec trk_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
arma::vec trk_Doppler_Hz = arma::zeros(nepoch, 1);
arma::vec trk_prn_delay_chips = arma::zeros(nepoch, 1);
epoch_counter = 0;
while(trk_dump.read_binary_obs())
{
trk_timestamp_s(epoch_counter) = static_cast<double>(trk_dump.PRN_start_sample_count) / static_cast<double>(baseband_sampling_freq);
trk_acc_carrier_phase_cycles(epoch_counter) = trk_dump.acc_carrier_phase_rad / GPS_TWO_PI;
trk_Doppler_Hz(epoch_counter) = trk_dump.carrier_doppler_hz;
double delay_chips = GPS_L1_CA_CODE_LENGTH_CHIPS
- GPS_L1_CA_CODE_LENGTH_CHIPS
* (fmod((static_cast<double>(trk_dump.PRN_start_sample_count) + trk_dump.aux1) / static_cast<double>(baseband_sampling_freq), 1.0e-3) /1.0e-3);
trk_prn_delay_chips(epoch_counter) = delay_chips;
epoch_counter++;
}
//Align initial measurements and cut the tracking pull-in transitory
double pull_in_offset_s = 1.0;
arma::uvec initial_meas_point = arma::find(trk_timestamp_s >= (true_timestamp_s(0) + pull_in_offset_s), 1, "first");
trk_timestamp_s = trk_timestamp_s.subvec(initial_meas_point(0), trk_timestamp_s.size() - 1);
trk_acc_carrier_phase_cycles = trk_acc_carrier_phase_cycles.subvec(initial_meas_point(0), trk_acc_carrier_phase_cycles.size() - 1);
trk_Doppler_Hz = trk_Doppler_Hz.subvec(initial_meas_point(0), trk_Doppler_Hz.size() - 1);
trk_prn_delay_chips = trk_prn_delay_chips.subvec(initial_meas_point(0), trk_prn_delay_chips.size() - 1);
check_results_doppler(true_timestamp_s, true_Doppler_Hz, trk_timestamp_s, trk_Doppler_Hz);
check_results_codephase(true_timestamp_s, true_prn_delay_chips, trk_timestamp_s, trk_prn_delay_chips);
check_results_acc_carrier_phase(true_timestamp_s, true_acc_carrier_phase_cycles, trk_timestamp_s, trk_acc_carrier_phase_cycles);
std::cout << "Signal tracking completed in " << (end - begin) << " microseconds" << std::endl;
}