mirror of
https://github.com/gnss-sdr/gnss-sdr
synced 2024-12-16 05:00:35 +00:00
Modify dump file pcps acquisition
This commit is contained in:
parent
08abbc6752
commit
ba38f8286d
@ -42,6 +42,7 @@
|
|||||||
#include <volk_gnsssdr/volk_gnsssdr.h>
|
#include <volk_gnsssdr/volk_gnsssdr.h>
|
||||||
#include "control_message_factory.h"
|
#include "control_message_factory.h"
|
||||||
#include "GPS_L1_CA.h" //GPS_TWO_PI
|
#include "GPS_L1_CA.h" //GPS_TWO_PI
|
||||||
|
#include <matio.h>
|
||||||
|
|
||||||
|
|
||||||
using google::LogMessage;
|
using google::LogMessage;
|
||||||
@ -95,9 +96,6 @@ pcps_acquisition_cc::pcps_acquisition_cc(
|
|||||||
d_code_phase = 0;
|
d_code_phase = 0;
|
||||||
d_test_statistics = 0.0;
|
d_test_statistics = 0.0;
|
||||||
d_channel = 0;
|
d_channel = 0;
|
||||||
d_doppler_freq = 0.0;
|
|
||||||
|
|
||||||
//set_relative_rate( 1.0/d_fft_size );
|
|
||||||
|
|
||||||
// COD:
|
// COD:
|
||||||
// Experimenting with the overlap/save technique for handling bit trannsitions
|
// Experimenting with the overlap/save technique for handling bit trannsitions
|
||||||
@ -110,10 +108,10 @@ pcps_acquisition_cc::pcps_acquisition_cc(
|
|||||||
// We can avoid this by doing linear correlation, effectively doubling the
|
// We can avoid this by doing linear correlation, effectively doubling the
|
||||||
// size of the input buffer and padding the code with zeros.
|
// size of the input buffer and padding the code with zeros.
|
||||||
if( d_bit_transition_flag )
|
if( d_bit_transition_flag )
|
||||||
{
|
{
|
||||||
d_fft_size *= 2;
|
d_fft_size *= 2;
|
||||||
d_max_dwells = 1; //Activation of d_bit_transition_flag invalidates the value of d_max_dwells
|
d_max_dwells = 1; //Activation of d_bit_transition_flag invalidates the value of d_max_dwells
|
||||||
}
|
}
|
||||||
|
|
||||||
d_fft_codes = static_cast<gr_complex*>(volk_gnsssdr_malloc(d_fft_size * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
|
d_fft_codes = static_cast<gr_complex*>(volk_gnsssdr_malloc(d_fft_size * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
|
||||||
d_magnitude = static_cast<float*>(volk_gnsssdr_malloc(d_fft_size * sizeof(float), volk_gnsssdr_get_alignment()));
|
d_magnitude = static_cast<float*>(volk_gnsssdr_malloc(d_fft_size * sizeof(float), volk_gnsssdr_get_alignment()));
|
||||||
@ -132,6 +130,7 @@ pcps_acquisition_cc::pcps_acquisition_cc(
|
|||||||
d_blocking = blocking;
|
d_blocking = blocking;
|
||||||
d_worker_active = false;
|
d_worker_active = false;
|
||||||
d_data_buffer = static_cast<gr_complex*>(volk_gnsssdr_malloc(d_fft_size * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
|
d_data_buffer = static_cast<gr_complex*>(volk_gnsssdr_malloc(d_fft_size * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
|
||||||
|
grid_ = arma::fmat();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -145,18 +144,11 @@ pcps_acquisition_cc::~pcps_acquisition_cc()
|
|||||||
}
|
}
|
||||||
delete[] d_grid_doppler_wipeoffs;
|
delete[] d_grid_doppler_wipeoffs;
|
||||||
}
|
}
|
||||||
|
|
||||||
volk_gnsssdr_free(d_fft_codes);
|
volk_gnsssdr_free(d_fft_codes);
|
||||||
volk_gnsssdr_free(d_magnitude);
|
volk_gnsssdr_free(d_magnitude);
|
||||||
|
|
||||||
delete d_ifft;
|
delete d_ifft;
|
||||||
delete d_fft_if;
|
delete d_fft_if;
|
||||||
|
volk_gnsssdr_free(d_data_buffer);
|
||||||
if (d_dump)
|
|
||||||
{
|
|
||||||
d_dump_file.close();
|
|
||||||
}
|
|
||||||
volk_gnsssdr_free( d_data_buffer );
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -217,6 +209,12 @@ void pcps_acquisition_cc::init()
|
|||||||
update_local_carrier(d_grid_doppler_wipeoffs[doppler_index], d_fft_size, d_freq + doppler);
|
update_local_carrier(d_grid_doppler_wipeoffs[doppler_index], d_fft_size, d_freq + doppler);
|
||||||
}
|
}
|
||||||
d_worker_active = false;
|
d_worker_active = false;
|
||||||
|
|
||||||
|
if(d_dump)
|
||||||
|
{
|
||||||
|
unsigned int effective_fft_size = (d_bit_transition_flag ? (d_fft_size / 2) : d_fft_size);
|
||||||
|
grid_ = arma::fmat(effective_fft_size, d_num_doppler_bins, arma::fill::zeros);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -348,6 +346,9 @@ void pcps_acquisition_cc::acquisition_core( unsigned long int samp_count )
|
|||||||
{
|
{
|
||||||
gr::thread::scoped_lock lk(d_setlock);
|
gr::thread::scoped_lock lk(d_setlock);
|
||||||
|
|
||||||
|
mat_t* matfp = NULL;
|
||||||
|
matvar_t* matvar = NULL;
|
||||||
|
|
||||||
// initialize acquisition algorithm
|
// initialize acquisition algorithm
|
||||||
int doppler;
|
int doppler;
|
||||||
uint32_t indext = 0;
|
uint32_t indext = 0;
|
||||||
@ -440,26 +441,39 @@ void pcps_acquisition_cc::acquisition_core( unsigned long int samp_count )
|
|||||||
}
|
}
|
||||||
// Record results to file if required
|
// Record results to file if required
|
||||||
if (d_dump)
|
if (d_dump)
|
||||||
|
{
|
||||||
|
if(doppler_index == 0)
|
||||||
{
|
{
|
||||||
std::stringstream filename;
|
std::string filename = d_dump_filename;
|
||||||
std::streamsize n = 2 * sizeof(float) * (d_fft_size); // complex file write
|
filename.append("_");
|
||||||
filename.str("");
|
filename.append(1, d_gnss_synchro->System);
|
||||||
boost::filesystem::path p = d_dump_filename;
|
filename.append("_sat_");
|
||||||
filename << p.parent_path().string()
|
filename.append(std::to_string(d_gnss_synchro->PRN));
|
||||||
<< boost::filesystem::path::preferred_separator
|
filename.append(".mat");
|
||||||
<< p.stem().string()
|
|
||||||
<< "_" << d_gnss_synchro->System
|
|
||||||
<<"_" << d_gnss_synchro->Signal << "_sat_"
|
|
||||||
<< d_gnss_synchro->PRN << "_doppler_"
|
|
||||||
<< doppler
|
|
||||||
<< p.extension().string();
|
|
||||||
|
|
||||||
DLOG(INFO) << "Writing ACQ out to " << filename.str();
|
matfp = Mat_CreateVer(filename.c_str(), NULL, MAT_FT_MAT73);
|
||||||
|
|
||||||
d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary);
|
|
||||||
d_dump_file.write(reinterpret_cast<char*>(d_ifft->get_outbuf()), n); //write directly |abs(x)|^2 in this Doppler bin?
|
|
||||||
d_dump_file.close();
|
|
||||||
}
|
}
|
||||||
|
memcpy(grid_.colptr(doppler_index), d_magnitude, sizeof(float) * effective_fft_size);
|
||||||
|
if(doppler_index == (d_num_doppler_bins - 1))
|
||||||
|
{
|
||||||
|
size_t dims[2] = {static_cast<size_t>(effective_fft_size), static_cast<size_t>(d_num_doppler_bins)};
|
||||||
|
matvar = Mat_VarCreate("grid", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, grid_.memptr(), 0);
|
||||||
|
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
|
||||||
|
Mat_VarFree(matvar);
|
||||||
|
|
||||||
|
dims[0] = static_cast<size_t>(1);
|
||||||
|
dims[1] = static_cast<size_t>(1);
|
||||||
|
matvar = Mat_VarCreate("doppler_max", MAT_C_SINGLE, MAT_T_UINT32, 1, dims, &d_doppler_max, 0);
|
||||||
|
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
|
||||||
|
Mat_VarFree(matvar);
|
||||||
|
|
||||||
|
matvar = Mat_VarCreate("doppler_step", MAT_C_SINGLE, MAT_T_UINT32, 1, dims, &d_doppler_step, 0);
|
||||||
|
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
|
||||||
|
Mat_VarFree(matvar);
|
||||||
|
|
||||||
|
Mat_Close(matfp);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
lk.lock();
|
lk.lock();
|
||||||
if (!d_bit_transition_flag)
|
if (!d_bit_transition_flag)
|
||||||
|
@ -59,6 +59,7 @@
|
|||||||
#include <gnuradio/fft/fft.h>
|
#include <gnuradio/fft/fft.h>
|
||||||
#include "gnss_synchro.h"
|
#include "gnss_synchro.h"
|
||||||
#include <glog/logging.h>
|
#include <glog/logging.h>
|
||||||
|
#include <armadillo>
|
||||||
|
|
||||||
class pcps_acquisition_cc;
|
class pcps_acquisition_cc;
|
||||||
|
|
||||||
@ -81,6 +82,7 @@ pcps_make_acquisition_cc(unsigned int sampled_ms, unsigned int max_dwells,
|
|||||||
class pcps_acquisition_cc: public gr::block
|
class pcps_acquisition_cc: public gr::block
|
||||||
{
|
{
|
||||||
private:
|
private:
|
||||||
|
|
||||||
friend pcps_acquisition_cc_sptr
|
friend pcps_acquisition_cc_sptr
|
||||||
pcps_make_acquisition_cc(unsigned int sampled_ms, unsigned int max_dwells,
|
pcps_make_acquisition_cc(unsigned int sampled_ms, unsigned int max_dwells,
|
||||||
unsigned int doppler_max, long freq, long fs_in,
|
unsigned int doppler_max, long freq, long fs_in,
|
||||||
@ -101,145 +103,143 @@ private:
|
|||||||
void acquisition_core( unsigned long int samp_count );
|
void acquisition_core( unsigned long int samp_count );
|
||||||
|
|
||||||
void send_negative_acquisition();
|
void send_negative_acquisition();
|
||||||
|
|
||||||
void send_positive_acquisition();
|
void send_positive_acquisition();
|
||||||
|
|
||||||
|
bool d_bit_transition_flag;
|
||||||
|
bool d_use_CFAR_algorithm_flag;
|
||||||
|
bool d_active;
|
||||||
|
bool d_dump;
|
||||||
|
bool d_worker_active;
|
||||||
|
bool d_blocking;
|
||||||
|
float d_threshold;
|
||||||
|
float d_mag;
|
||||||
|
float d_input_power;
|
||||||
|
float d_test_statistics;
|
||||||
|
float* d_magnitude;
|
||||||
long d_fs_in;
|
long d_fs_in;
|
||||||
long d_freq;
|
long d_freq;
|
||||||
int d_samples_per_ms;
|
int d_samples_per_ms;
|
||||||
int d_samples_per_code;
|
int d_samples_per_code;
|
||||||
//unsigned int d_doppler_resolution;
|
int d_state;
|
||||||
float d_threshold;
|
unsigned int d_channel;
|
||||||
unsigned int d_doppler_max;
|
unsigned int d_doppler_max;
|
||||||
unsigned int d_doppler_step;
|
unsigned int d_doppler_step;
|
||||||
unsigned int d_sampled_ms;
|
unsigned int d_sampled_ms;
|
||||||
unsigned int d_max_dwells;
|
unsigned int d_max_dwells;
|
||||||
unsigned int d_well_count;
|
unsigned int d_well_count;
|
||||||
unsigned int d_fft_size;
|
unsigned int d_fft_size;
|
||||||
|
unsigned int d_num_doppler_bins;
|
||||||
|
unsigned int d_code_phase;
|
||||||
unsigned long int d_sample_counter;
|
unsigned long int d_sample_counter;
|
||||||
gr_complex** d_grid_doppler_wipeoffs;
|
gr_complex** d_grid_doppler_wipeoffs;
|
||||||
unsigned int d_num_doppler_bins;
|
|
||||||
gr_complex* d_fft_codes;
|
gr_complex* d_fft_codes;
|
||||||
|
gr_complex* d_data_buffer;
|
||||||
gr::fft::fft_complex* d_fft_if;
|
gr::fft::fft_complex* d_fft_if;
|
||||||
gr::fft::fft_complex* d_ifft;
|
gr::fft::fft_complex* d_ifft;
|
||||||
Gnss_Synchro *d_gnss_synchro;
|
Gnss_Synchro* d_gnss_synchro;
|
||||||
unsigned int d_code_phase;
|
|
||||||
float d_doppler_freq;
|
|
||||||
float d_mag;
|
|
||||||
float* d_magnitude;
|
|
||||||
float d_input_power;
|
|
||||||
float d_test_statistics;
|
|
||||||
bool d_bit_transition_flag;
|
|
||||||
bool d_use_CFAR_algorithm_flag;
|
|
||||||
std::ofstream d_dump_file;
|
|
||||||
bool d_active;
|
|
||||||
int d_state;
|
|
||||||
bool d_dump;
|
|
||||||
unsigned int d_channel;
|
|
||||||
std::string d_dump_filename;
|
std::string d_dump_filename;
|
||||||
bool d_worker_active;
|
arma::fmat grid_;
|
||||||
bool d_blocking;
|
|
||||||
gr_complex *d_data_buffer;
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/*!
|
|
||||||
* \brief Default destructor.
|
~pcps_acquisition_cc();
|
||||||
*/
|
|
||||||
~pcps_acquisition_cc();
|
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Set acquisition/tracking common Gnss_Synchro object pointer
|
* \brief Set acquisition/tracking common Gnss_Synchro object pointer
|
||||||
* to exchange synchronization data between acquisition and tracking blocks.
|
* to exchange synchronization data between acquisition and tracking blocks.
|
||||||
* \param p_gnss_synchro Satellite information shared by the processing blocks.
|
* \param p_gnss_synchro Satellite information shared by the processing blocks.
|
||||||
*/
|
*/
|
||||||
inline void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
|
inline void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_gnss_synchro = p_gnss_synchro;
|
d_gnss_synchro = p_gnss_synchro;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Returns the maximum peak of grid search.
|
* \brief Returns the maximum peak of grid search.
|
||||||
*/
|
*/
|
||||||
inline unsigned int mag() const
|
inline unsigned int mag() const
|
||||||
{
|
{
|
||||||
return d_mag;
|
return d_mag;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Initializes acquisition algorithm.
|
* \brief Initializes acquisition algorithm.
|
||||||
*/
|
*/
|
||||||
void init();
|
void init();
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Sets local code for PCPS acquisition algorithm.
|
* \brief Sets local code for PCPS acquisition algorithm.
|
||||||
* \param code - Pointer to the PRN code.
|
* \param code - Pointer to the PRN code.
|
||||||
*/
|
*/
|
||||||
void set_local_code(std::complex<float> * code);
|
void set_local_code(std::complex<float> * code);
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Starts acquisition algorithm, turning from standby mode to
|
* \brief Starts acquisition algorithm, turning from standby mode to
|
||||||
* active mode
|
* active mode
|
||||||
* \param active - bool that activates/deactivates the block.
|
* \param active - bool that activates/deactivates the block.
|
||||||
*/
|
*/
|
||||||
inline void set_active(bool active)
|
inline void set_active(bool active)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_active = active;
|
d_active = active;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief If set to 1, ensures that acquisition starts at the
|
* \brief If set to 1, ensures that acquisition starts at the
|
||||||
* first available sample.
|
* first available sample.
|
||||||
* \param state - int=1 forces start of acquisition
|
* \param state - int=1 forces start of acquisition
|
||||||
*/
|
*/
|
||||||
void set_state(int state);
|
void set_state(int state);
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Set acquisition channel unique ID
|
* \brief Set acquisition channel unique ID
|
||||||
* \param channel - receiver channel.
|
* \param channel - receiver channel.
|
||||||
*/
|
*/
|
||||||
inline void set_channel(unsigned int channel)
|
inline void set_channel(unsigned int channel)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_channel = channel;
|
d_channel = channel;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Set statistics threshold of PCPS algorithm.
|
* \brief Set statistics threshold of PCPS algorithm.
|
||||||
* \param threshold - Threshold for signal detection (check \ref Navitec2012,
|
* \param threshold - Threshold for signal detection (check \ref Navitec2012,
|
||||||
* Algorithm 1, for a definition of this threshold).
|
* Algorithm 1, for a definition of this threshold).
|
||||||
*/
|
*/
|
||||||
inline void set_threshold(float threshold)
|
inline void set_threshold(float threshold)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_threshold = threshold;
|
d_threshold = threshold;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Set maximum Doppler grid search
|
* \brief Set maximum Doppler grid search
|
||||||
* \param doppler_max - Maximum Doppler shift considered in the grid search [Hz].
|
* \param doppler_max - Maximum Doppler shift considered in the grid search [Hz].
|
||||||
*/
|
*/
|
||||||
inline void set_doppler_max(unsigned int doppler_max)
|
inline void set_doppler_max(unsigned int doppler_max)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_doppler_max = doppler_max;
|
d_doppler_max = doppler_max;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Set Doppler steps for the grid search
|
* \brief Set Doppler steps for the grid search
|
||||||
* \param doppler_step - Frequency bin of the search grid [Hz].
|
* \param doppler_step - Frequency bin of the search grid [Hz].
|
||||||
*/
|
*/
|
||||||
inline void set_doppler_step(unsigned int doppler_step)
|
inline void set_doppler_step(unsigned int doppler_step)
|
||||||
{
|
{
|
||||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||||
d_doppler_step = doppler_step;
|
d_doppler_step = doppler_step;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* \brief Parallel Code Phase Search Acquisition signal processing.
|
* \brief Parallel Code Phase Search Acquisition signal processing.
|
||||||
*/
|
*/
|
||||||
int general_work(int noutput_items, gr_vector_int &ninput_items,
|
int general_work(int noutput_items, gr_vector_int &ninput_items,
|
||||||
gr_vector_const_void_star &input_items,
|
gr_vector_const_void_star &input_items,
|
||||||
gr_vector_void_star &output_items);
|
gr_vector_void_star &output_items);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
62
src/utils/matlab/plot_acq_grid.m
Normal file
62
src/utils/matlab/plot_acq_grid.m
Normal file
@ -0,0 +1,62 @@
|
|||||||
|
% /*!
|
||||||
|
% * \file plot_acq_grid.m
|
||||||
|
% * \brief Read GNSS-SDR Acquisition dump .mat file using the provided
|
||||||
|
% function and plot acquisition grid of acquisition statistic of PRN sat
|
||||||
|
%
|
||||||
|
%
|
||||||
|
% * \author Antonio Ramos, 2017. antonio.ramos(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/>.
|
||||||
|
% *
|
||||||
|
% * -------------------------------------------------------------------------
|
||||||
|
% */
|
||||||
|
|
||||||
|
%%%%%%%%% ¡¡¡ CONFIGURE !!! %%%%%%%%%%%%%
|
||||||
|
sat = 27;
|
||||||
|
n_chips = 1023;
|
||||||
|
system = 'G'; % GPS = 'G', Galileo = 'E'
|
||||||
|
%%% True for light grid representation
|
||||||
|
lite_view = true;
|
||||||
|
%%% If lite_view, it sets the number of samples per chip in the graphical representation
|
||||||
|
n_samples_per_chip = 4;
|
||||||
|
|
||||||
|
|
||||||
|
path='/home/aramos/signals/';
|
||||||
|
file=['acq_' system '_sat_' num2str(sat) '.mat'];
|
||||||
|
|
||||||
|
load([path file]);
|
||||||
|
[n_fft n_dop_bins] = size(grid);
|
||||||
|
freq = (0 : n_dop_bins - 1) * doppler_step - doppler_max;
|
||||||
|
delay = (0 : n_fft - 1) / n_fft * n_chips;
|
||||||
|
figure(1)
|
||||||
|
if(lite_view == false)
|
||||||
|
mesh(freq, delay, grid)
|
||||||
|
else
|
||||||
|
delay_interp = (0 : n_samples_per_chip * n_chips - 1) / n_samples_per_chip;
|
||||||
|
grid_interp = spline(delay, grid', delay_interp)';
|
||||||
|
mesh(freq, delay_interp, grid_interp)
|
||||||
|
end
|
||||||
|
xlabel('Doppler shift / Hz')
|
||||||
|
ylabel('Code delay / chips')
|
||||||
|
zlabel('Test statistics')
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue
Block a user