1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-12-15 20:50:33 +00:00

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

This commit is contained in:
Carles Fernandez 2018-04-23 14:29:18 +02:00
commit ed5cb61764
46 changed files with 1976 additions and 1588 deletions

View File

@ -75,7 +75,7 @@ the actual username of your GitHub account):
4. Your forked repository https://github.com/YOUR_USERNAME/gnss-sdr
will receive the default name of `origin`. You can also add the original
gnss-sdr repository, which is usually called `upstream`:
gnss-sdr repository, which is usually referred to as `upstream`:
$ cd gnss-sdr
$ git remote add upstream https://github.com/gnss-sdr/gnss-sdr.git

View File

@ -22,6 +22,28 @@ FIND_LIBRARY(
/usr/local/lib64
/usr/lib
/usr/lib64
/usr/lib/x86_64-linux-gnu
/usr/lib/alpha-linux-gnu
/usr/lib/aarch64-linux-gnu
/usr/lib/arm-linux-gnueabi
/usr/lib/arm-linux-gnueabihf
/usr/lib/hppa-linux-gnu
/usr/lib/i686-gnu
/usr/lib/i686-linux-gnu
/usr/lib/x86_64-kfreebsd-gnu
/usr/lib/i686-kfreebsd-gnu
/usr/lib/m68k-linux-gnu
/usr/lib/mips-linux-gnu
/usr/lib/mips64el-linux-gnuabi64
/usr/lib/mipsel-linux-gnu
/usr/lib/powerpc-linux-gnu
/usr/lib/powerpc-linux-gnuspe
/usr/lib/powerpc64-linux-gnu
/usr/lib/powerpc64le-linux-gnu
/usr/lib/s390x-linux-gnu
/usr/lib/sparc64-linux-gnu
/usr/lib/x86_64-linux-gnux32
/usr/lib/sh4-linux-gnu
)
INCLUDE(FindPackageHandleStandardArgs)

View File

@ -3,7 +3,7 @@ PKG_CHECK_MODULES(PC_LIBIIO libiio)
FIND_PATH(
LIBIIO_INCLUDE_DIRS
NAMES gnuradio/iio/api.h
NAMES iio.h
HINTS $ENV{LIBIIO_DIR}/include
${PC_LIBIIO_INCLUDEDIR}
PATHS ${CMAKE_INSTALL_PREFIX}/include
@ -14,7 +14,7 @@ FIND_PATH(
FIND_LIBRARY(
LIBIIO_LIBRARIES
NAMES libiio.so iio
NAMES iio libiio.so.0
HINTS $ENV{LIBIIO_DIR}/lib
${PC_LIBIIO_LIBDIR}
PATHS ${CMAKE_INSTALL_PREFIX}/lib
@ -24,27 +24,27 @@ FIND_LIBRARY(
/usr/lib
/usr/lib64
/usr/lib/x86_64-linux-gnu
/usr/lib/gcc/alpha-linux-gnu
/usr/lib/gcc/aarch64-linux-gnu
/usr/lib/gcc/arm-linux-gnueabi
/usr/lib/gcc/arm-linux-gnueabihf
/usr/lib/gcc/hppa-linux-gnu
/usr/lib/gcc/i686-gnu
/usr/lib/gcc/i686-linux-gnu
/usr/lib/gcc/x86_64-kfreebsd-gnu
/usr/lib/gcc/i686-kfreebsd-gnu
/usr/lib/gcc/m68k-linux-gnu
/usr/lib/gcc/mips-linux-gnu
/usr/lib/gcc/mips64el-linux-gnuabi64
/usr/lib/gcc/mipsel-linux-gnu
/usr/lib/gcc/powerpc-linux-gnu
/usr/lib/gcc/powerpc-linux-gnuspe
/usr/lib/gcc/powerpc64-linux-gnu
/usr/lib/gcc/powerpc64le-linux-gnu
/usr/lib/gcc/s390x-linux-gnu
/usr/lib/gcc/sparc64-linux-gnu
/usr/lib/gcc/x86_64-linux-gnux32
/usr/lib/gcc/sh4-linux-gnu
/usr/lib/alpha-linux-gnu
/usr/lib/aarch64-linux-gnu
/usr/lib/arm-linux-gnueabi
/usr/lib/arm-linux-gnueabihf
/usr/lib/hppa-linux-gnu
/usr/lib/i686-gnu
/usr/lib/i686-linux-gnu
/usr/lib/x86_64-kfreebsd-gnu
/usr/lib/i686-kfreebsd-gnu
/usr/lib/m68k-linux-gnu
/usr/lib/mips-linux-gnu
/usr/lib/mips64el-linux-gnuabi64
/usr/lib/mipsel-linux-gnu
/usr/lib/powerpc-linux-gnu
/usr/lib/powerpc-linux-gnuspe
/usr/lib/powerpc64-linux-gnu
/usr/lib/powerpc64le-linux-gnu
/usr/lib/s390x-linux-gnu
/usr/lib/sparc64-linux-gnu
/usr/lib/x86_64-linux-gnux32
/usr/lib/sh4-linux-gnu
/Library/Frameworks/iio.framework/
)

View File

@ -335,84 +335,6 @@ void pcps_acquisition::send_negative_acquisition()
}
int pcps_acquisition::general_work(int noutput_items __attribute__((unused)),
gr_vector_int& ninput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items __attribute__((unused)))
{
/*
* By J.Arribas, L.Esteve and M.Molina
* Acquisition strategy (Kay Borre book + CFAR threshold):
* 1. Compute the input signal power estimation
* 2. Doppler serial search loop
* 3. Perform the FFT-based circular convolution (parallel time search)
* 4. Record the maximum peak and the associated synchronization parameters
* 5. Compute the test statistics and compare to the threshold
* 6. Declare positive or negative acquisition using a message port
*/
gr::thread::scoped_lock lk(d_setlock);
if (!d_active or d_worker_active)
{
d_sample_counter += d_fft_size * ninput_items[0];
consume_each(ninput_items[0]);
if (d_step_two)
{
d_doppler_center_step_two = static_cast<float>(d_gnss_synchro->Acq_doppler_hz);
update_grid_doppler_wipeoffs_step2();
d_state = 0;
d_active = true;
}
return 0;
}
switch (d_state)
{
case 0:
{
//restart acquisition variables
d_gnss_synchro->Acq_delay_samples = 0.0;
d_gnss_synchro->Acq_doppler_hz = 0.0;
d_gnss_synchro->Acq_samplestamp_samples = 0;
d_well_count = 0;
d_mag = 0.0;
d_input_power = 0.0;
d_test_statistics = 0.0;
d_state = 1;
d_sample_counter += d_fft_size * ninput_items[0]; // sample counter
consume_each(ninput_items[0]);
break;
}
case 1:
{
// Copy the data to the core and let it know that new data is available
if (d_cshort)
{
memcpy(d_data_buffer_sc, input_items[0], d_fft_size * sizeof(lv_16sc_t));
}
else
{
memcpy(d_data_buffer, input_items[0], d_fft_size * sizeof(gr_complex));
}
if (acq_parameters.blocking)
{
lk.unlock();
acquisition_core(d_sample_counter);
}
else
{
gr::thread::thread d_worker(&pcps_acquisition::acquisition_core, this, d_sample_counter);
d_worker_active = true;
}
d_sample_counter += d_fft_size;
consume_each(1);
break;
}
}
return 0;
}
void pcps_acquisition::acquisition_core(unsigned long int samp_count)
{
gr::thread::scoped_lock lk(d_setlock);
@ -686,3 +608,81 @@ void pcps_acquisition::acquisition_core(unsigned long int samp_count)
}
d_worker_active = false;
}
int pcps_acquisition::general_work(int noutput_items __attribute__((unused)),
gr_vector_int& ninput_items, gr_vector_const_void_star& input_items,
gr_vector_void_star& output_items __attribute__((unused)))
{
/*
* By J.Arribas, L.Esteve and M.Molina
* Acquisition strategy (Kay Borre book + CFAR threshold):
* 1. Compute the input signal power estimation
* 2. Doppler serial search loop
* 3. Perform the FFT-based circular convolution (parallel time search)
* 4. Record the maximum peak and the associated synchronization parameters
* 5. Compute the test statistics and compare to the threshold
* 6. Declare positive or negative acquisition using a message port
*/
gr::thread::scoped_lock lk(d_setlock);
if (!d_active or d_worker_active)
{
d_sample_counter += d_fft_size * ninput_items[0];
consume_each(ninput_items[0]);
if (d_step_two)
{
d_doppler_center_step_two = static_cast<float>(d_gnss_synchro->Acq_doppler_hz);
update_grid_doppler_wipeoffs_step2();
d_state = 0;
d_active = true;
}
return 0;
}
switch (d_state)
{
case 0:
{
//restart acquisition variables
d_gnss_synchro->Acq_delay_samples = 0.0;
d_gnss_synchro->Acq_doppler_hz = 0.0;
d_gnss_synchro->Acq_samplestamp_samples = 0;
d_well_count = 0;
d_mag = 0.0;
d_input_power = 0.0;
d_test_statistics = 0.0;
d_state = 1;
d_sample_counter += d_fft_size * ninput_items[0]; // sample counter
consume_each(ninput_items[0]);
break;
}
case 1:
{
// Copy the data to the core and let it know that new data is available
if (d_cshort)
{
memcpy(d_data_buffer_sc, input_items[0], d_fft_size * sizeof(lv_16sc_t));
}
else
{
memcpy(d_data_buffer, input_items[0], d_fft_size * sizeof(gr_complex));
}
if (acq_parameters.blocking)
{
lk.unlock();
acquisition_core(d_sample_counter);
}
else
{
gr::thread::thread d_worker(&pcps_acquisition::acquisition_core, this, d_sample_counter);
d_worker_active = true;
}
d_sample_counter += d_fft_size;
consume_each(1);
break;
}
}
return 0;
}

View File

@ -108,8 +108,6 @@ Channel::Channel(ConfigurationInterface* configuration, unsigned int channel,
// Destructor
Channel::~Channel() {}
void Channel::connect(gr::top_block_sptr top_block)
{
if (connected_)
@ -137,8 +135,6 @@ void Channel::connect(gr::top_block_sptr top_block)
DLOG(INFO) << "tracking -> telemetry_decoder";
// Message ports
top_block->msg_connect(nav_->get_left_block(), pmt::mp("preamble_timestamp_s"), trk_->get_right_block(), pmt::mp("preamble_timestamp_s"));
DLOG(INFO) << "MSG FEEDBACK CHANNEL telemetry_decoder -> tracking";
top_block->msg_connect(acq_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));
top_block->msg_connect(trk_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));

View File

@ -0,0 +1,135 @@
/*!
* \file gnss_circular_deque.h
* \brief This class implements a circular deque for Gnss_Synchro
*
* \author Antonio Ramos, 2018. antonio.ramosdet(at)gmail.com
*
* Detailed description of the file here if needed.
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2018 (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_CIRCULAR_DEQUE_H_
#define GNSS_SDR_CIRCULAR_DEQUE_H_
#include <vector>
#include <boost/circular_buffer.hpp>
template <class T>
class Gnss_circular_deque
{
public:
Gnss_circular_deque(); // Default constructor
Gnss_circular_deque(const unsigned int max_size, const unsigned int nchann); // nchann = number of channels; max_size = channel capacity
unsigned int size(const unsigned int ch); // Returns the number of available elements in a channel
T& at(const unsigned int ch, const unsigned int pos); // Returns a reference to an element
T& front(const unsigned int ch); // Returns a reference to the first element in the deque
T& back(const unsigned int ch); // Returns a reference to the last element in the deque
void push_back(const unsigned int ch, const T& new_data); // Inserts an element at the end of the deque
void pop_front(const unsigned int ch); // Removes the first element of the deque
void clear(const unsigned int ch); // Removes all the elements of the deque (Sets size to 0). Capacity is not modified
void reset(const unsigned int max_size, const unsigned int nchann); // Removes all the elements in all the channels. Re-sets the number of channels and their capacity
void reset(); // Removes all the channels (Sets nchann to 0)
private:
std::vector<boost::circular_buffer<T>> d_data;
};
template <class T>
Gnss_circular_deque<T>::Gnss_circular_deque()
{
reset();
}
template <class T>
Gnss_circular_deque<T>::Gnss_circular_deque(const unsigned int max_size, const unsigned int nchann)
{
reset(max_size, nchann);
}
template <class T>
unsigned int Gnss_circular_deque<T>::size(const unsigned int ch)
{
return d_data.at(ch).size();
}
template <class T>
T& Gnss_circular_deque<T>::back(const unsigned int ch)
{
return d_data.at(ch).back();
}
template <class T>
T& Gnss_circular_deque<T>::front(const unsigned int ch)
{
return d_data.at(ch).front();
}
template <class T>
T& Gnss_circular_deque<T>::at(const unsigned int ch, const unsigned int pos)
{
return d_data.at(ch).at(pos);
}
template <class T>
void Gnss_circular_deque<T>::clear(const unsigned int ch)
{
d_data.at(ch).clear();
}
template <class T>
void Gnss_circular_deque<T>::reset(const unsigned int max_size, const unsigned int nchann)
{
d_data.clear();
if (max_size > 0 and nchann > 0)
{
for (unsigned int i = 0; i < nchann; i++)
{
d_data.push_back(boost::circular_buffer<T>(max_size));
}
}
}
template <class T>
void Gnss_circular_deque<T>::reset()
{
d_data.clear();
}
template <class T>
void Gnss_circular_deque<T>::pop_front(const unsigned int ch)
{
d_data.at(ch).pop_front();
}
template <class T>
void Gnss_circular_deque<T>::push_back(const unsigned int ch, const T& new_data)
{
d_data.at(ch).push_back(new_data);
}
#endif /* GNSS_SDR_CIRCULAR_DEQUE_H_ */

View File

@ -62,6 +62,7 @@ endif(CMAKE_CXX_COMPILER_ID MATCHES "Clang")
# Enable C++17 support in GCC >= 8.0.0
# Enable C++14 support in 8.0.0 > GCC >= 6.1.1
# Fallback to C++11 when using GCC < 6.1.1
if(CMAKE_COMPILER_IS_GNUCXX AND NOT WIN32)
if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "6.1.1")
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11")
@ -75,8 +76,8 @@ if(CMAKE_COMPILER_IS_GNUCXX AND NOT WIN32)
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -Wall -Wextra") #Add warning flags: For "-Wall" see http://gcc.gnu.org/onlinedocs/gcc/Warning-Options.html
endif(CMAKE_COMPILER_IS_GNUCXX AND NOT WIN32)
# Enable C++17 support in Clang >= 6.0.0 or AppleClang >= 900
# Enable C++14 support in 6.0.0 > Clang >= 3.5.0 or 900 > AppleClang >= 600
# Enable C++17 support in Clang >= 6.0.0
# Enable C++14 support in 6.0.0 > Clang >= 3.5.0 or AppleClang >= 600
# Fallback to C++11 if older version
if(CMAKE_CXX_COMPILER_ID MATCHES "Clang")
if(CMAKE_SYSTEM_NAME MATCHES "Darwin")
@ -84,11 +85,7 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "Clang")
if(CLANG_VERSION VERSION_LESS "600")
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++11")
else(CLANG_VERSION VERSION_LESS "600")
if(CLANG_VERSION VERSION_LESS "900")
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++14")
else(CLANG_VERSION VERSION_LESS "900")
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++17")
endif(CLANG_VERSION VERSION_LESS "900")
set(MY_CXX_FLAGS "${MY_CXX_FLAGS} -std=c++14")
endif(CLANG_VERSION VERSION_LESS "600")
else(CMAKE_SYSTEM_NAME MATCHES "Darwin")
if(CMAKE_CXX_COMPILER_VERSION VERSION_LESS "3.5.0")

View File

@ -26,6 +26,7 @@ include_directories(
${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/observables/gnuradio_blocks
${CMAKE_SOURCE_DIR}/src/algorithms/libs
${CMAKE_SOURCE_DIR}/src/algorithms/PVT/libs
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}

View File

@ -39,8 +39,8 @@ list(SORT OBS_GR_BLOCKS_HEADERS)
add_library(obs_gr_blocks ${OBS_GR_BLOCKS_SOURCES} ${OBS_GR_BLOCKS_HEADERS})
source_group(Headers FILES ${OBS_GR_BLOCKS_HEADERS})
if(MATIO_FOUND)
add_dependencies(obs_gr_blocks glog-${glog_RELEASE} armadillo-${armadillo_RELEASE})
add_dependencies(obs_gr_blocks gnss_sp_libs glog-${glog_RELEASE} armadillo-${armadillo_RELEASE})
else(MATIO_FOUND)
add_dependencies(obs_gr_blocks glog-${glog_RELEASE} armadillo-${armadillo_RELEASE} matio-${GNSSSDR_MATIO_LOCAL_VERSION})
add_dependencies(obs_gr_blocks gnss_sp_libs glog-${glog_RELEASE} armadillo-${armadillo_RELEASE} matio-${GNSSSDR_MATIO_LOCAL_VERSION})
endif(MATIO_FOUND)
target_link_libraries(obs_gr_blocks ${GNURADIO_RUNTIME_LIBRARIES} ${ARMADILLO_LIBRARIES} ${MATIO_LIBRARIES})
target_link_libraries(obs_gr_blocks gnss_sp_libs ${GNURADIO_RUNTIME_LIBRARIES} ${ARMADILLO_LIBRARIES} ${MATIO_LIBRARIES})

View File

@ -63,14 +63,11 @@ hybrid_observables_cc::hybrid_observables_cc(unsigned int nchannels_in,
d_dump_filename = dump_filename;
T_rx_s = 0.0;
T_rx_step_s = 0.001; // 1 ms
max_delta = 0.15; // 150 ms
max_delta = 1.5; // 1.5 s
d_latency = 0.3; // 300 ms
valid_channels.resize(d_nchannels, false);
d_num_valid_channels = 0;
for (unsigned int i = 0; i < d_nchannels; i++)
{
d_gnss_synchro_history.push_back(std::deque<Gnss_Synchro>());
}
d_gnss_synchro_history = new Gnss_circular_deque<Gnss_Synchro>(static_cast<unsigned int>(max_delta * 1000.0), d_nchannels);
// ############# ENABLE DATA FILE LOG #################
if (d_dump)
@ -95,6 +92,7 @@ hybrid_observables_cc::hybrid_observables_cc(unsigned int nchannels_in,
hybrid_observables_cc::~hybrid_observables_cc()
{
delete d_gnss_synchro_history;
if (d_dump_file.is_open())
{
try
@ -302,40 +300,26 @@ int hybrid_observables_cc::save_matfile()
}
bool hybrid_observables_cc::interpolate_data(Gnss_Synchro &out, std::deque<Gnss_Synchro> &data, const double &ti)
bool hybrid_observables_cc::interpolate_data(Gnss_Synchro &out, const unsigned int &ch, const double &ti)
{
if ((ti < data.front().RX_time) or (ti > data.back().RX_time))
if ((ti < d_gnss_synchro_history->front(ch).RX_time) or (ti > d_gnss_synchro_history->back(ch).RX_time))
{
return false;
}
std::deque<Gnss_Synchro>::iterator it;
find_interp_elements(ch, ti);
arma::vec t = arma::vec(data.size());
arma::vec dop = t;
arma::vec cph = t;
arma::vec tow = t;
arma::vec tiv = arma::vec(1);
arma::vec result;
tiv(0) = ti;
//Linear interpolation: y(t) = y(t1) + (y(t2) - y(t1)) * (t - t1) / (t2 - t1)
unsigned int aux = 0;
for (it = data.begin(); it != data.end(); it++)
{
t(aux) = it->RX_time;
dop(aux) = it->Carrier_Doppler_hz;
cph(aux) = it->Carrier_phase_rads;
tow(aux) = it->TOW_at_current_symbol_s;
// CARRIER PHASE INTERPOLATION
out.Carrier_phase_rads = d_gnss_synchro_history->at(ch, 0).Carrier_phase_rads + (d_gnss_synchro_history->at(ch, 1).Carrier_phase_rads - d_gnss_synchro_history->at(ch, 0).Carrier_phase_rads) * (ti - d_gnss_synchro_history->at(ch, 0).RX_time) / (d_gnss_synchro_history->at(ch, 1).RX_time - d_gnss_synchro_history->at(ch, 0).RX_time);
aux++;
}
arma::interp1(t, dop, tiv, result);
out.Carrier_Doppler_hz = result(0);
arma::interp1(t, cph, tiv, result);
out.Carrier_phase_rads = result(0);
arma::interp1(t, tow, tiv, result);
out.TOW_at_current_symbol_s = result(0);
// CARRIER DOPPLER INTERPOLATION
out.Carrier_Doppler_hz = d_gnss_synchro_history->at(ch, 0).Carrier_Doppler_hz + (d_gnss_synchro_history->at(ch, 1).Carrier_Doppler_hz - d_gnss_synchro_history->at(ch, 0).Carrier_Doppler_hz) * (ti - d_gnss_synchro_history->at(ch, 0).RX_time) / (d_gnss_synchro_history->at(ch, 1).RX_time - d_gnss_synchro_history->at(ch, 0).RX_time);
return result.is_finite();
// TOW INTERPOLATION
out.TOW_at_current_symbol_s = d_gnss_synchro_history->at(ch, 0).TOW_at_current_symbol_s + (d_gnss_synchro_history->at(ch, 1).TOW_at_current_symbol_s - d_gnss_synchro_history->at(ch, 0).TOW_at_current_symbol_s) * (ti - d_gnss_synchro_history->at(ch, 0).RX_time) / (d_gnss_synchro_history->at(ch, 1).RX_time - d_gnss_synchro_history->at(ch, 0).RX_time);
return true;
}
@ -351,25 +335,60 @@ double hybrid_observables_cc::compute_T_rx_s(const Gnss_Synchro &a)
}
}
void hybrid_observables_cc::find_interp_elements(const unsigned int &ch, const double &ti)
{
unsigned int closest = 0;
double dif = std::numeric_limits<double>::max();
double dt = 0.0;
for (unsigned int i = 0; i < d_gnss_synchro_history->size(ch); i++)
{
dt = std::fabs(ti - d_gnss_synchro_history->at(ch, i).RX_time);
if (dt < dif)
{
closest = i;
dif = dt;
}
else
{
break;
}
}
if (ti > d_gnss_synchro_history->at(ch, closest).RX_time)
{
while (closest > 0)
{
d_gnss_synchro_history->pop_front(ch);
closest--;
}
}
else
{
while (closest > 1)
{
d_gnss_synchro_history->pop_front(ch);
closest--;
}
}
}
void hybrid_observables_cc::forecast(int noutput_items __attribute__((unused)),
gr_vector_int &ninput_items_required)
void hybrid_observables_cc::forecast(int noutput_items, gr_vector_int &ninput_items_required)
{
for (unsigned int i = 0; i < d_nchannels; i++)
{
ninput_items_required[i] = 0;
}
ninput_items_required[d_nchannels] = 1;
ninput_items_required[d_nchannels] = noutput_items;
}
void hybrid_observables_cc::clean_history(std::deque<Gnss_Synchro> &data)
void hybrid_observables_cc::clean_history(unsigned int pos)
{
while (data.size() > 0)
while (d_gnss_synchro_history->size(pos) > 0)
{
if ((T_rx_s - data.front().RX_time) > max_delta)
if ((T_rx_s - d_gnss_synchro_history->front(pos).RX_time) > max_delta)
{
data.pop_front();
d_gnss_synchro_history->pop_front(pos);
}
else
{
@ -439,157 +458,161 @@ int hybrid_observables_cc::general_work(int noutput_items __attribute__((unused)
Gnss_Synchro **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]);
unsigned int i;
unsigned int returned_elements = 0;
int total_input_items = 0;
for (i = 0; i < d_nchannels; i++)
{
total_input_items += ninput_items[i];
}
consume(d_nchannels, 1);
T_rx_s += T_rx_step_s;
//////////////////////////////////////////////////////////////////////////
if ((total_input_items == 0) and (d_num_valid_channels == 0))
for (int epoch = 0; epoch < ninput_items[d_nchannels]; epoch++)
{
return 0;
}
//////////////////////////////////////////////////////////////////////////
T_rx_s += T_rx_step_s;
std::vector<std::deque<Gnss_Synchro>>::iterator it;
if (total_input_items > 0)
{
i = 0;
for (it = d_gnss_synchro_history.begin(); it != d_gnss_synchro_history.end(); it++)
//////////////////////////////////////////////////////////////////////////
if ((total_input_items == 0) and (d_num_valid_channels == 0))
{
if (ninput_items[i] > 0)
consume(d_nchannels, epoch + 1);
return returned_elements;
}
//////////////////////////////////////////////////////////////////////////
if (total_input_items > 0 and epoch == 0)
{
for (i = 0; i < d_nchannels; i++)
{
// Add the new Gnss_Synchros to their corresponding deque
for (int aux = 0; aux < ninput_items[i]; aux++)
if (ninput_items[i] > 0)
{
if (in[i][aux].Flag_valid_word)
// Add the new Gnss_Synchros to their corresponding deque
for (int aux = 0; aux < ninput_items[i]; aux++)
{
it->push_back(in[i][aux]);
it->back().RX_time = compute_T_rx_s(in[i][aux]);
// Check if the last Gnss_Synchro comes from the same satellite as the previous ones
if (it->size() > 1)
if (in[i][aux].Flag_valid_word)
{
if (it->front().PRN != it->back().PRN)
d_gnss_synchro_history->push_back(i, in[i][aux]);
d_gnss_synchro_history->back(i).RX_time = compute_T_rx_s(in[i][aux]);
// Check if the last Gnss_Synchro comes from the same satellite as the previous ones
if (d_gnss_synchro_history->size(i) > 1)
{
it->clear();
if (d_gnss_synchro_history->front(i).PRN != d_gnss_synchro_history->back(i).PRN)
{
d_gnss_synchro_history->clear(i);
}
}
}
}
consume(i, ninput_items[i]);
}
consume(i, ninput_items[i]);
}
i++;
}
}
for (i = 0; i < d_nchannels; i++)
{
if (d_gnss_synchro_history.at(i).size() > 2)
{
valid_channels[i] = true;
}
else
{
valid_channels[i] = false;
}
}
d_num_valid_channels = valid_channels.count();
// Check if there is any valid channel after reading the new incoming Gnss_Synchro data
if (d_num_valid_channels == 0)
{
return 0;
}
for (i = 0; i < d_nchannels; i++) //Discard observables with T_rx higher than the threshold
{
if (valid_channels[i])
{
clean_history(d_gnss_synchro_history.at(i));
if (d_gnss_synchro_history.at(i).size() < 2)
{
valid_channels[i] = false;
}
}
}
// Check if there is any valid channel after computing the time distance between the Gnss_Synchro data and the receiver time
d_num_valid_channels = valid_channels.count();
double T_rx_s_out = T_rx_s - (max_delta / 2.0);
if ((d_num_valid_channels == 0) or (T_rx_s_out < 0.0))
{
return 0;
}
std::vector<Gnss_Synchro> epoch_data;
i = 0;
for (it = d_gnss_synchro_history.begin(); it != d_gnss_synchro_history.end(); it++)
{
if (valid_channels[i])
for (i = 0; i < d_nchannels; i++)
{
Gnss_Synchro interpolated_gnss_synchro = it->back();
if (interpolate_data(interpolated_gnss_synchro, *it, T_rx_s_out))
if (d_gnss_synchro_history->size(i) > 2)
{
epoch_data.push_back(interpolated_gnss_synchro);
valid_channels[i] = true;
}
else
{
valid_channels[i] = false;
}
}
i++;
}
d_num_valid_channels = valid_channels.count();
if (d_num_valid_channels == 0)
{
return 0;
}
correct_TOW_and_compute_prange(epoch_data);
std::vector<Gnss_Synchro>::iterator it2 = epoch_data.begin();
for (i = 0; i < d_nchannels; i++)
{
if (valid_channels[i])
d_num_valid_channels = valid_channels.count();
// Check if there is any valid channel after reading the new incoming Gnss_Synchro data
if (d_num_valid_channels == 0)
{
out[i][0] = (*it2);
out[i][0].Flag_valid_pseudorange = true;
it2++;
consume(d_nchannels, epoch + 1);
return returned_elements;
}
else
for (i = 0; i < d_nchannels; i++) //Discard observables with T_rx higher than the threshold
{
out[i][0] = Gnss_Synchro();
out[i][0].Flag_valid_pseudorange = false;
}
}
if (d_dump)
{
// MULTIPLEXED FILE RECORDING - Record results to file
try
{
double tmp_double;
for (i = 0; i < d_nchannels; i++)
if (valid_channels[i])
{
tmp_double = out[i][0].RX_time;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][0].TOW_at_current_symbol_s;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][0].Carrier_Doppler_hz;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][0].Carrier_phase_rads / GPS_TWO_PI;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][0].Pseudorange_m;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = static_cast<double>(out[i][0].PRN);
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = static_cast<double>(out[i][0].Flag_valid_pseudorange);
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
clean_history(i);
if (d_gnss_synchro_history->size(i) < 2)
{
valid_channels[i] = false;
}
}
}
catch (const std::ifstream::failure &e)
// Check if there is any valid channel after computing the time distance between the Gnss_Synchro data and the receiver time
d_num_valid_channels = valid_channels.count();
double T_rx_s_out = T_rx_s - d_latency;
if ((d_num_valid_channels == 0) or (T_rx_s_out < 0.0))
{
LOG(WARNING) << "Exception writing observables dump file " << e.what();
d_dump = false;
consume(d_nchannels, epoch + 1);
return returned_elements;
}
std::vector<Gnss_Synchro> epoch_data;
for (i = 0; i < d_nchannels; i++)
{
if (valid_channels[i])
{
Gnss_Synchro interpolated_gnss_synchro = d_gnss_synchro_history->back(i);
if (interpolate_data(interpolated_gnss_synchro, i, T_rx_s_out))
{
epoch_data.push_back(interpolated_gnss_synchro);
}
else
{
valid_channels[i] = false;
}
}
}
d_num_valid_channels = valid_channels.count();
if (d_num_valid_channels == 0)
{
consume(d_nchannels, epoch + 1);
return returned_elements;
}
correct_TOW_and_compute_prange(epoch_data);
std::vector<Gnss_Synchro>::iterator it = epoch_data.begin();
for (i = 0; i < d_nchannels; i++)
{
if (valid_channels[i])
{
out[i][epoch] = (*it);
out[i][epoch].Flag_valid_pseudorange = true;
it++;
}
else
{
out[i][epoch] = Gnss_Synchro();
out[i][epoch].Flag_valid_pseudorange = false;
}
}
if (d_dump)
{
// MULTIPLEXED FILE RECORDING - Record results to file
try
{
double tmp_double;
for (i = 0; i < d_nchannels; i++)
{
tmp_double = out[i][epoch].RX_time;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][epoch].TOW_at_current_symbol_s;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][epoch].Carrier_Doppler_hz;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][epoch].Carrier_phase_rads / GPS_TWO_PI;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = out[i][epoch].Pseudorange_m;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = static_cast<double>(out[i][epoch].PRN);
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_double = static_cast<double>(out[i][epoch].Flag_valid_pseudorange);
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
}
}
catch (const std::ifstream::failure &e)
{
LOG(WARNING) << "Exception writing observables dump file " << e.what();
d_dump = false;
}
}
returned_elements++;
}
return 1;
consume(d_nchannels, ninput_items[d_nchannels]);
return returned_elements;
}

View File

@ -35,12 +35,12 @@
#define GNSS_SDR_HYBRID_OBSERVABLES_CC_H
#include "gnss_synchro.h"
#include "gnss_circular_deque.h"
#include <gnuradio/block.h>
#include <boost/dynamic_bitset.hpp>
#include <fstream>
#include <string>
#include <vector>
#include <deque>
#include <utility>
class hybrid_observables_cc;
@ -65,18 +65,20 @@ private:
friend hybrid_observables_cc_sptr
hybrid_make_observables_cc(unsigned int nchannels_in, unsigned int nchannels_out, bool dump, std::string dump_filename);
hybrid_observables_cc(unsigned int nchannels_in, unsigned int nchannels_out, bool dump, std::string dump_filename);
void clean_history(std::deque<Gnss_Synchro>& data);
void clean_history(unsigned int pos);
double compute_T_rx_s(const Gnss_Synchro& a);
bool interpolate_data(Gnss_Synchro& out, std::deque<Gnss_Synchro>& data, const double& ti);
bool interpolate_data(Gnss_Synchro& out, const unsigned int& ch, const double& ti);
void find_interp_elements(const unsigned int& ch, const double& ti);
void correct_TOW_and_compute_prange(std::vector<Gnss_Synchro>& data);
int save_matfile();
//Tracking observable history
std::vector<std::deque<Gnss_Synchro>> d_gnss_synchro_history;
Gnss_circular_deque<Gnss_Synchro>* d_gnss_synchro_history;
boost::dynamic_bitset<> valid_channels;
double T_rx_s;
double T_rx_step_s;
double max_delta;
double d_latency;
bool d_dump;
unsigned int d_nchannels;
unsigned int d_num_valid_channels;

View File

@ -158,41 +158,6 @@ rtl_tcp_signal_source_c::~rtl_tcp_signal_source_c()
}
int rtl_tcp_signal_source_c::work(int noutput_items,
gr_vector_const_void_star & /*input_items*/,
gr_vector_void_star &output_items)
{
gr_complex *out = reinterpret_cast<gr_complex *>(output_items[0]);
int i = 0;
if (io_service_.stopped())
{
return -1;
}
{
boost::mutex::scoped_lock lock(mutex_);
not_empty_.wait(lock, boost::bind(&rtl_tcp_signal_source_c::not_empty,
this));
for (; i < noutput_items && unread_ > 1; i++)
{
float re = buffer_[--unread_];
float im = buffer_[--unread_];
if (flip_iq_)
{
out[i] = gr_complex(im, re);
}
else
{
out[i] = gr_complex(re, im);
}
}
}
not_full_.notify_one();
return i == 0 ? -1 : i;
}
void rtl_tcp_signal_source_c::set_frequency(int frequency)
{
boost::system::error_code ec =
@ -359,3 +324,38 @@ void rtl_tcp_signal_source_c::handle_read(const boost::system::error_code &ec,
this, _1, _2));
}
}
int rtl_tcp_signal_source_c::work(int noutput_items,
gr_vector_const_void_star & /*input_items*/,
gr_vector_void_star &output_items)
{
gr_complex *out = reinterpret_cast<gr_complex *>(output_items[0]);
int i = 0;
if (io_service_.stopped())
{
return -1;
}
{
boost::mutex::scoped_lock lock(mutex_);
not_empty_.wait(lock, boost::bind(&rtl_tcp_signal_source_c::not_empty,
this));
for (; i < noutput_items && unread_ > 1; i++)
{
float re = buffer_[--unread_];
float im = buffer_[--unread_];
if (flip_iq_)
{
out[i] = gr_complex(im, re);
}
else
{
out[i] = gr_complex(re, im);
}
}
}
not_full_.notify_one();
return i == 0 ? -1 : i;
}

View File

@ -57,6 +57,21 @@ unpack_spir_gss6450_samples::~unpack_spir_gss6450_samples()
}
int unpack_spir_gss6450_samples::compute_two_complement(unsigned long data)
{
int res = 0;
if (static_cast<int>(data) < two_compl_thres)
{
res = static_cast<int>(data);
}
else
{
res = static_cast<int>(data) - adc_bits_two_pow;
}
return res;
}
int unpack_spir_gss6450_samples::work(int noutput_items,
gr_vector_const_void_star& input_items, gr_vector_void_star& output_items)
{
@ -86,17 +101,3 @@ int unpack_spir_gss6450_samples::work(int noutput_items,
}
return noutput_items;
}
int unpack_spir_gss6450_samples::compute_two_complement(unsigned long data)
{
int res = 0;
if (static_cast<int>(data) < two_compl_thres)
{
res = static_cast<int>(data);
}
else
{
res = static_cast<int>(data) - adc_bits_two_pow;
}
return res;
}

View File

@ -37,10 +37,15 @@ include_directories(
${GFlags_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GNURADIO_RUNTIME_INCLUDE_DIRS}
${VOLK_GNSSSDR_INCLUDE_DIRS}
)
file(GLOB TELEMETRY_DECODER_GR_BLOCKS_HEADERS "*.h")
list(SORT TELEMETRY_DECODER_GR_BLOCKS_HEADERS)
add_library(telemetry_decoder_gr_blocks ${TELEMETRY_DECODER_GR_BLOCKS_SOURCES} ${TELEMETRY_DECODER_GR_BLOCKS_HEADERS})
source_group(Headers FILES ${TELEMETRY_DECODER_GR_BLOCKS_HEADERS})
target_link_libraries(telemetry_decoder_gr_blocks telemetry_decoder_libswiftcnav telemetry_decoder_lib gnss_system_parameters ${GNURADIO_RUNTIME_LIBRARIES})
target_link_libraries(telemetry_decoder_gr_blocks telemetry_decoder_libswiftcnav telemetry_decoder_lib gnss_system_parameters ${GNURADIO_RUNTIME_LIBRARIES} ${VOLK_GNSSSDR_LIBRARIES})
if(NOT VOLK_GNSSSDR_FOUND)
add_dependencies(telemetry_decoder_gr_blocks volk_gnsssdr_module)
endif(NOT VOLK_GNSSSDR_FOUND)

View File

@ -37,6 +37,7 @@
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#include <iostream>
@ -54,38 +55,8 @@ galileo_e1b_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump
void galileo_e1b_telemetry_decoder_cc::viterbi_decoder(double *page_part_symbols, int *page_part_bits)
{
int CodeLength = 240;
int DataLength;
int nn, KK, mm, max_states;
int g_encoder[2];
nn = 2; // Coding rate 1/n
KK = 7; // Constraint Length
g_encoder[0] = 121; // Polynomial G1
g_encoder[1] = 91; // Polynomial G2
mm = KK - 1;
max_states = 1 << mm; /* 2^mm */
DataLength = (CodeLength / nn) - mm;
/* create appropriate transition matrices */
int *out0, *out1, *state0, *state1;
out0 = static_cast<int *>(calloc(max_states, sizeof(int)));
out1 = static_cast<int *>(calloc(max_states, sizeof(int)));
state0 = static_cast<int *>(calloc(max_states, sizeof(int)));
state1 = static_cast<int *>(calloc(max_states, sizeof(int)));
nsc_transit(out0, state0, 0, g_encoder, KK, nn);
nsc_transit(out1, state1, 1, g_encoder, KK, nn);
Viterbi(page_part_bits, out0, state0, out1, state1,
page_part_symbols, KK, nn, DataLength);
/* Clean up memory */
free(out0);
free(out1);
free(state0);
free(state1);
}
@ -106,8 +77,6 @@ galileo_e1b_telemetry_decoder_cc::galileo_e1b_telemetry_decoder_cc(
bool dump) : gr::block("galileo_e1b_telemetry_decoder_cc", gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -124,7 +93,7 @@ galileo_e1b_telemetry_decoder_cc::galileo_e1b_telemetry_decoder_cc(
memcpy(static_cast<unsigned short int *>(this->d_preambles_bits), static_cast<unsigned short int *>(preambles_bits), GALILEO_INAV_PREAMBLE_LENGTH_BITS * sizeof(unsigned short int));
// preamble bits to sampled symbols
d_preambles_symbols = static_cast<signed int *>(malloc(sizeof(signed int) * d_symbols_per_preamble));
d_preambles_symbols = static_cast<int *>(volk_gnsssdr_malloc(d_symbols_per_preamble * sizeof(int), volk_gnsssdr_get_alignment()));
int n = 0;
for (int i = 0; i < GALILEO_INAV_PREAMBLE_LENGTH_BITS; i++)
{
@ -155,12 +124,28 @@ galileo_e1b_telemetry_decoder_cc::galileo_e1b_telemetry_decoder_cc(
d_flag_preamble = false;
d_channel = 0;
flag_TOW_set = false;
// vars for Viterbi decoder
int max_states = 1 << mm; /* 2^mm */
g_encoder[0] = 121; // Polynomial G1
g_encoder[1] = 91; // Polynomial G2
out0 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
out1 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
state0 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
state1 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
/* create appropriate transition matrices */
nsc_transit(out0, state0, 0, g_encoder, KK, nn);
nsc_transit(out1, state1, 1, g_encoder, KK, nn);
}
galileo_e1b_telemetry_decoder_cc::~galileo_e1b_telemetry_decoder_cc()
{
delete d_preambles_symbols;
volk_gnsssdr_free(d_preambles_symbols);
volk_gnsssdr_free(out0);
volk_gnsssdr_free(out1);
volk_gnsssdr_free(state0);
volk_gnsssdr_free(state1);
if (d_dump_file.is_open() == true)
{
try
@ -215,13 +200,13 @@ void galileo_e1b_telemetry_decoder_cc::decode_word(double *page_part_symbols, in
d_nav.split_page(page_String, flag_even_word_arrived);
if (d_nav.flag_CRC_test == true)
{
LOG(INFO) << "Galileo E1 CRC correct on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "Galileo E1 CRC correct in channel " << d_channel << " from satellite " << d_satellite;
//std::cout << "Galileo E1 CRC correct on channel " << d_channel << " from satellite " << d_satellite << std::endl;
}
else
{
std::cout << "Galileo E1 CRC error on channel " << d_channel << " from satellite " << d_satellite << std::endl;
LOG(INFO) << "Galileo E1 CRC error on channel " << d_channel << " from satellite " << d_satellite;
std::cout << "Galileo E1 CRC error in channel " << d_channel << " from satellite " << d_satellite << std::endl;
LOG(INFO) << "Galileo E1 CRC error in channel " << d_channel << " from satellite " << d_satellite;
}
flag_even_word_arrived = 0;
}
@ -237,21 +222,21 @@ void galileo_e1b_telemetry_decoder_cc::decode_word(double *page_part_symbols, in
{
// get object for this SV (mandatory)
std::shared_ptr<Galileo_Ephemeris> tmp_obj = std::make_shared<Galileo_Ephemeris>(d_nav.get_ephemeris());
std::cout << "New Galileo E1 I/NAV message received: ephemeris from satellite " << d_satellite << std::endl;
std::cout << "New Galileo E1 I/NAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_iono_and_GST() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Galileo_Iono> tmp_obj = std::make_shared<Galileo_Iono>(d_nav.get_iono());
std::cout << "New Galileo E1 I/NAV message received: iono/GST model parameters from satellite " << d_satellite << std::endl;
std::cout << "New Galileo E1 I/NAV message received in channel " << d_channel << ": iono/GST model parameters from satellite " << d_satellite << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_utc_model() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Galileo_Utc_Model> tmp_obj = std::make_shared<Galileo_Utc_Model>(d_nav.get_utc_model());
std::cout << "New Galileo E1 I/NAV message received: UTC model parameters from satellite " << d_satellite << std::endl;
std::cout << "New Galileo E1 I/NAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_almanac() == true)
@ -259,7 +244,7 @@ void galileo_e1b_telemetry_decoder_cc::decode_word(double *page_part_symbols, in
std::shared_ptr<Galileo_Almanac> tmp_obj = std::make_shared<Galileo_Almanac>(d_nav.get_almanac());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
//debug
std::cout << "Galileo E1 I/NAV almanac received!" << std::endl;
std::cout << "Galileo E1 I/NAV almanac received in channel " << d_channel << " from satellite " << d_satellite << std::endl;
DLOG(INFO) << "GPS_to_Galileo time conversion:";
DLOG(INFO) << "A0G=" << tmp_obj->A_0G_10;
DLOG(INFO) << "A1G=" << tmp_obj->A_1G_10;
@ -274,6 +259,41 @@ void galileo_e1b_telemetry_decoder_cc::decode_word(double *page_part_symbols, in
}
void galileo_e1b_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void galileo_e1b_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}
int galileo_e1b_telemetry_decoder_cc::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)
{
@ -469,38 +489,3 @@ int galileo_e1b_telemetry_decoder_cc::general_work(int noutput_items __attribute
//std::cout<<"GPS L1 TLM output on CH="<<this->d_channel << " SAMPLE STAMP="<<d_sample_counter/d_decimation_output_factor<<std::endl;
return 1;
}
void galileo_e1b_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void galileo_e1b_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}

View File

@ -112,6 +112,15 @@ private:
std::string d_dump_filename;
std::ofstream d_dump_file;
// vars for Viterbi decoder
int *out0, *out1, *state0, *state1;
int g_encoder[2];
const int nn = 2; // Coding rate 1/n
const int KK = 7; // Constraint Length
int mm = KK - 1;
const int CodeLength = 240;
int DataLength = (CodeLength / nn) - mm;
};
#endif

View File

@ -37,9 +37,11 @@
#include "galileo_e5a_telemetry_decoder_cc.h"
#include "control_message_factory.h"
#include "convolutional.h"
#include "display.h"
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#include <cmath>
#include <iostream>
@ -58,42 +60,8 @@ galileo_e5a_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump
void galileo_e5a_telemetry_decoder_cc::viterbi_decoder(double *page_part_symbols, int *page_part_bits)
{
// int CodeLength = 240;
int CodeLength = 488;
int DataLength;
int nn, KK, mm, max_states;
int g_encoder[2];
nn = 2; // Coding rate 1/n
KK = 7; // Constraint Length
g_encoder[0] = 121; // Polynomial G1
g_encoder[1] = 91; // Polynomial G2
// g_encoder[0] = 171; // Polynomial G1
// g_encoder[1] = 133; // Polynomial G2
mm = KK - 1;
max_states = 1 << mm; // 2^mm
DataLength = (CodeLength / nn) - mm;
//create appropriate transition matrices
int *out0, *out1, *state0, *state1;
out0 = static_cast<int *>(calloc(max_states, sizeof(int)));
out1 = static_cast<int *>(calloc(max_states, sizeof(int)));
state0 = static_cast<int *>(calloc(max_states, sizeof(int)));
state1 = static_cast<int *>(calloc(max_states, sizeof(int)));
nsc_transit(out0, state0, 0, g_encoder, KK, nn);
nsc_transit(out1, state1, 1, g_encoder, KK, nn);
Viterbi(page_part_bits, out0, state0, out1, state1,
page_part_symbols, KK, nn, DataLength);
//Clean up memory
free(out0);
free(out1);
free(state0);
free(state1);
}
@ -147,32 +115,32 @@ void galileo_e5a_telemetry_decoder_cc::decode_word(double *page_symbols, int fra
d_nav.split_page(page_String);
if (d_nav.flag_CRC_test == true)
{
LOG(INFO) << "Galileo E5a CRC correct on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "Galileo E5a CRC correct in channel " << d_channel << " from satellite " << d_satellite;
//std::cout << "Galileo E5a CRC correct on channel " << d_channel << " from satellite " << d_satellite << std::endl;
}
else
{
std::cout << "Galileo E5a CRC error on channel " << d_channel << " from satellite " << d_satellite << std::endl;
LOG(INFO) << "Galileo E5a CRC error on channel " << d_channel << " from satellite " << d_satellite;
std::cout << "Galileo E5a CRC error in channel " << d_channel << " from satellite " << d_satellite << std::endl;
LOG(INFO) << "Galileo E5a CRC error in channel " << d_channel << " from satellite " << d_satellite;
}
// 4. Push the new navigation data to the queues
if (d_nav.have_new_ephemeris() == true)
{
std::shared_ptr<Galileo_Ephemeris> tmp_obj = std::make_shared<Galileo_Ephemeris>(d_nav.get_ephemeris());
std::cout << "New Galileo E5a F/NAV message received: ephemeris from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New Galileo E5a F/NAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_iono_and_GST() == true)
{
std::shared_ptr<Galileo_Iono> tmp_obj = std::make_shared<Galileo_Iono>(d_nav.get_iono());
std::cout << "New Galileo E5a F/NAV message received: iono/GST model parameters from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New Galileo E5a F/NAV message received in channel " << d_channel << ": iono/GST model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_utc_model() == true)
{
std::shared_ptr<Galileo_Utc_Model> tmp_obj = std::make_shared<Galileo_Utc_Model>(d_nav.get_utc_model());
std::cout << "New Galileo E5a F/NAV message received: UTC model parameters from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New Galileo E5a F/NAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
}
@ -183,8 +151,6 @@ galileo_e5a_telemetry_decoder_cc::galileo_e5a_telemetry_decoder_cc(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -228,11 +194,27 @@ galileo_e5a_telemetry_decoder_cc::galileo_e5a_telemetry_decoder_cc(
flag_bit_start = false;
new_symbol = false;
required_symbols = GALILEO_FNAV_SYMBOLS_PER_PAGE + GALILEO_FNAV_PREAMBLE_LENGTH_BITS;
// vars for Viterbi decoder
int max_states = 1 << mm; /* 2^mm */
g_encoder[0] = 121; // Polynomial G1
g_encoder[1] = 91; // Polynomial G2
out0 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
out1 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
state0 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
state1 = static_cast<int *>(volk_gnsssdr_malloc(max_states * sizeof(int), volk_gnsssdr_get_alignment()));
/* create appropriate transition matrices */
nsc_transit(out0, state0, 0, g_encoder, KK, nn);
nsc_transit(out1, state1, 1, g_encoder, KK, nn);
}
galileo_e5a_telemetry_decoder_cc::~galileo_e5a_telemetry_decoder_cc()
{
volk_gnsssdr_free(out0);
volk_gnsssdr_free(out1);
volk_gnsssdr_free(state0);
volk_gnsssdr_free(state1);
if (d_dump_file.is_open() == true)
{
try
@ -247,6 +229,41 @@ galileo_e5a_telemetry_decoder_cc::~galileo_e5a_telemetry_decoder_cc()
}
void galileo_e5a_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void galileo_e5a_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}
int galileo_e5a_telemetry_decoder_cc::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)
{
@ -493,38 +510,3 @@ int galileo_e5a_telemetry_decoder_cc::general_work(int noutput_items __attribute
return 0;
}
}
void galileo_e5a_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void galileo_e5a_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}

View File

@ -112,6 +112,15 @@ private:
Gnss_Satellite d_satellite;
// navigation message vars
Galileo_Fnav_Message d_nav;
// vars for Viterbi decoder
int *out0, *out1, *state0, *state1;
int g_encoder[2];
const int nn = 2; // Coding rate 1/n
const int KK = 7; // Constraint Length
int mm = KK - 1;
const int CodeLength = 488;
int DataLength = (CodeLength / nn) - mm;
};
#endif /* GNSS_SDR_GALILEO_E5A_TELEMETRY_DECODER_CC_H_ */

View File

@ -54,8 +54,6 @@ glonass_l1_ca_telemetry_decoder_cc::glonass_l1_ca_telemetry_decoder_cc(
bool dump) : gr::block("glonass_l1_ca_telemetry_decoder_cc", gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -183,11 +181,11 @@ void glonass_l1_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
// 3. Check operation executed correctly
if (d_nav.flag_CRC_test == true)
{
LOG(INFO) << "GLONASS GNAV CRC correct on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV CRC correct in channel " << d_channel << " from satellite " << d_satellite;
}
else
{
LOG(INFO) << "GLONASS GNAV CRC error on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV CRC error in channel " << d_channel << " from satellite " << d_satellite;
}
// 4. Push the new navigation data to the queues
if (d_nav.have_new_ephemeris() == true)
@ -196,26 +194,29 @@ void glonass_l1_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
d_nav.gnav_ephemeris.i_satellite_freq_channel = d_satellite.get_rf_link();
std::shared_ptr<Glonass_Gnav_Ephemeris> tmp_obj = std::make_shared<Glonass_Gnav_Ephemeris>(d_nav.get_ephemeris());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV Ephemeris have been received on channel" << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV Ephemeris have been received in channel" << d_channel << " from satellite " << d_satellite;
std::cout << "New GLONASS L1 GNAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << std::endl;
}
if (d_nav.have_new_utc_model() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Glonass_Gnav_Utc_Model> tmp_obj = std::make_shared<Glonass_Gnav_Utc_Model>(d_nav.get_utc_model());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV UTC Model have been received on channel" << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV UTC Model have been received in channel" << d_channel << " from satellite " << d_satellite;
std::cout << "New GLONASS L1 GNAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << std::endl;
}
if (d_nav.have_new_almanac() == true)
{
unsigned int slot_nbr = d_nav.i_alm_satellite_slot_number;
std::shared_ptr<Glonass_Gnav_Almanac> tmp_obj = std::make_shared<Glonass_Gnav_Almanac>(d_nav.get_almanac(slot_nbr));
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV Almanac have been received on channel" << d_channel << " in slot number " << slot_nbr;
LOG(INFO) << "GLONASS GNAV Almanac have been received in channel" << d_channel << " in slot number " << slot_nbr;
std::cout << "New GLONASS L1 GNAV almanac received in channel " << d_channel << " from satellite " << d_satellite << std::endl;
}
// 5. Update satellite information on system
if (d_nav.flag_update_slot_number == true)
{
LOG(INFO) << "GLONASS GNAV Slot Number Identified on channel " << d_channel;
LOG(INFO) << "GLONASS GNAV Slot Number Identified in channel " << d_channel;
d_satellite.update_PRN(d_nav.gnav_ephemeris.d_n);
d_satellite.what_block(d_satellite.get_system(), d_nav.gnav_ephemeris.d_n);
d_nav.flag_update_slot_number = false;
@ -223,6 +224,41 @@ void glonass_l1_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
}
void glonass_l1_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void glonass_l1_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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 Glonass TLM dump file. " << e.what();
}
}
}
}
int glonass_l1_ca_telemetry_decoder_cc::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)
{
@ -285,9 +321,6 @@ int glonass_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribu
LOG(INFO) << "Starting string decoder for GLONASS L1 C/A SAT " << this->d_satellite;
d_preamble_index = d_sample_counter; //record the preamble sample stamp
d_stat = 2;
// send asynchronous message to tracking to inform of frame sync and extend correlation time
pmt::pmt_t value = pmt::from_double(static_cast<double>(d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs) - 0.001);
this->message_port_pub(pmt::mp("preamble_timestamp_s"), value);
}
else
{
@ -413,38 +446,3 @@ int glonass_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribu
return 1;
}
void glonass_l1_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void glonass_l1_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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 Glonass TLM dump file. " << e.what();
}
}
}
}

View File

@ -31,9 +31,10 @@
#include "glonass_l2_ca_telemetry_decoder_cc.h"
#include "display.h"
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#define CRC_ERROR_LIMIT 6
@ -53,8 +54,6 @@ glonass_l2_ca_telemetry_decoder_cc::glonass_l2_ca_telemetry_decoder_cc(
bool dump) : gr::block("glonass_l2_ca_telemetry_decoder_cc", gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -182,11 +181,11 @@ void glonass_l2_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
// 3. Check operation executed correctly
if (d_nav.flag_CRC_test == true)
{
LOG(INFO) << "GLONASS GNAV CRC correct on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV CRC correct in channel " << d_channel << " from satellite " << d_satellite;
}
else
{
LOG(INFO) << "GLONASS GNAV CRC error on channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV CRC error in channel " << d_channel << " from satellite " << d_satellite;
}
// 4. Push the new navigation data to the queues
if (d_nav.have_new_ephemeris() == true)
@ -195,26 +194,29 @@ void glonass_l2_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
d_nav.gnav_ephemeris.i_satellite_freq_channel = d_satellite.get_rf_link();
std::shared_ptr<Glonass_Gnav_Ephemeris> tmp_obj = std::make_shared<Glonass_Gnav_Ephemeris>(d_nav.get_ephemeris());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV Ephemeris have been received on channel" << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV Ephemeris have been received in channel" << d_channel << " from satellite " << d_satellite;
std::cout << TEXT_CYAN << "New GLONASS L2 GNAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << TEXT_RESET << std::endl;
}
if (d_nav.have_new_utc_model() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Glonass_Gnav_Utc_Model> tmp_obj = std::make_shared<Glonass_Gnav_Utc_Model>(d_nav.get_utc_model());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV UTC Model have been received on channel" << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "GLONASS GNAV UTC Model have been received in channel" << d_channel << " from satellite " << d_satellite;
std::cout << TEXT_CYAN << "New GLONASS L2 GNAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
}
if (d_nav.have_new_almanac() == true)
{
unsigned int slot_nbr = d_nav.i_alm_satellite_slot_number;
std::shared_ptr<Glonass_Gnav_Almanac> tmp_obj = std::make_shared<Glonass_Gnav_Almanac>(d_nav.get_almanac(slot_nbr));
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "GLONASS GNAV Almanac have been received on channel" << d_channel << " in slot number " << slot_nbr;
LOG(INFO) << "GLONASS GNAV Almanac have been received in channel" << d_channel << " in slot number " << slot_nbr;
std::cout << TEXT_CYAN << "New GLONASS L2 GNAV almanac received in channel " << d_channel << " from satellite " << d_satellite << TEXT_RESET << std::endl;
}
// 5. Update satellite information on system
if (d_nav.flag_update_slot_number == true)
{
LOG(INFO) << "GLONASS GNAV Slot Number Identified on channel " << d_channel;
LOG(INFO) << "GLONASS GNAV Slot Number Identified in channel " << d_channel;
d_satellite.update_PRN(d_nav.gnav_ephemeris.d_n);
d_satellite.what_block(d_satellite.get_system(), d_nav.gnav_ephemeris.d_n);
d_nav.flag_update_slot_number = false;
@ -222,6 +224,41 @@ void glonass_l2_ca_telemetry_decoder_cc::decode_string(double *frame_symbols, in
}
void glonass_l2_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void glonass_l2_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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 Glonass TLM dump file. " << e.what();
}
}
}
}
int glonass_l2_ca_telemetry_decoder_cc::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)
{
@ -284,9 +321,6 @@ int glonass_l2_ca_telemetry_decoder_cc::general_work(int noutput_items __attribu
LOG(INFO) << "Starting string decoder for GLONASS L2 C/A SAT " << this->d_satellite;
d_preamble_index = d_sample_counter; //record the preamble sample stamp
d_stat = 2;
// send asynchronous message to tracking to inform of frame sync and extend correlation time
pmt::pmt_t value = pmt::from_double(static_cast<double>(d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs) - 0.001);
this->message_port_pub(pmt::mp("preamble_timestamp_s"), value);
}
else
{
@ -412,38 +446,3 @@ int glonass_l2_ca_telemetry_decoder_cc::general_work(int noutput_items __attribu
return 1;
}
void glonass_l2_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void glonass_l2_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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 Glonass TLM dump file. " << e.what();
}
}
}
}

View File

@ -32,8 +32,9 @@
#include "gps_l1_ca_telemetry_decoder_cc.h"
#include "control_message_factory.h"
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#ifndef _rotl
@ -54,8 +55,6 @@ gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
bool dump) : gr::block("gps_navigation_cc", gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -65,10 +64,8 @@ gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
// set the preamble
unsigned short int preambles_bits[GPS_CA_PREAMBLE_LENGTH_BITS] = GPS_PREAMBLE;
//memcpy((unsigned short int*)this->d_preambles_bits, (unsigned short int*)preambles_bits, GPS_CA_PREAMBLE_LENGTH_BITS*sizeof(unsigned short int));
// preamble bits to sampled symbols
d_preambles_symbols = static_cast<signed int *>(malloc(sizeof(signed int) * GPS_CA_PREAMBLE_LENGTH_SYMBOLS));
d_preambles_symbols = static_cast<int *>(volk_gnsssdr_malloc(GPS_CA_PREAMBLE_LENGTH_SYMBOLS * sizeof(int), volk_gnsssdr_get_alignment()));
int n = 0;
for (int i = 0; i < GPS_CA_PREAMBLE_LENGTH_BITS; i++)
{
@ -105,12 +102,16 @@ gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
flag_PLL_180_deg_phase_locked = false;
d_preamble_time_samples = 0;
d_TOW_at_current_symbol_ms = 0;
d_symbol_history.resize(GPS_CA_PREAMBLE_LENGTH_SYMBOLS + 1); // Change fixed buffer size
d_symbol_history.clear(); // Clear all the elements in the buffer
d_make_correlation = true;
d_symbol_counter_corr = 0;
}
gps_l1_ca_telemetry_decoder_cc::~gps_l1_ca_telemetry_decoder_cc()
{
delete d_preambles_symbols;
volk_gnsssdr_free(d_preambles_symbols);
if (d_dump_file.is_open() == true)
{
try
@ -150,6 +151,44 @@ bool gps_l1_ca_telemetry_decoder_cc::gps_word_parityCheck(unsigned int gpsword)
}
void gps_l1_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
d_GPS_FSM.i_satellite_PRN = d_satellite.get_PRN();
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void gps_l1_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
d_GPS_FSM.i_channel_ID = channel;
DLOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}
int gps_l1_ca_telemetry_decoder_cc::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)
{
@ -168,7 +207,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
unsigned int required_symbols = GPS_CA_PREAMBLE_LENGTH_SYMBOLS;
d_flag_preamble = false;
if (d_symbol_history.size() > required_symbols)
if ((d_symbol_history.size() > required_symbols) and (d_make_correlation or !d_flag_frame_sync))
{
//******* preamble correlation ********
for (unsigned int i = 0; i < GPS_CA_PREAMBLE_LENGTH_SYMBOLS; i++)
@ -177,19 +216,22 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
{
if (d_symbol_history.at(i).Prompt_I < 0) // symbols clipping
{
corr_value -= d_preambles_symbols[i] * d_symbol_history.at(i).correlation_length_ms;
corr_value -= d_preambles_symbols[i];
}
else
{
corr_value += d_preambles_symbols[i] * d_symbol_history.at(i).correlation_length_ms;
corr_value += d_preambles_symbols[i];
}
}
if (corr_value >= GPS_CA_PREAMBLE_LENGTH_SYMBOLS) break;
}
if (std::abs(corr_value) >= GPS_CA_PREAMBLE_LENGTH_SYMBOLS)
{
d_symbol_counter_corr++;
}
}
//******* frame sync ******************
if (abs(corr_value) == GPS_CA_PREAMBLE_LENGTH_SYMBOLS)
if (std::abs(corr_value) == GPS_CA_PREAMBLE_LENGTH_SYMBOLS)
{
//TODO: Rewrite with state machine
if (d_stat == 0)
@ -206,18 +248,17 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
}
else if (d_stat == 1) //check 6 seconds of preamble separation
{
preamble_diff_ms = round(((static_cast<double>(d_symbol_history.at(0).Tracking_sample_counter) - d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs)) * 1000.0);
if (abs(preamble_diff_ms - GPS_SUBFRAME_MS) < 1)
preamble_diff_ms = std::round(((static_cast<double>(d_symbol_history.at(0).Tracking_sample_counter) - d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs)) * 1000.0);
if (std::abs(preamble_diff_ms - GPS_SUBFRAME_MS) < 1)
{
DLOG(INFO) << "Preamble confirmation for SAT " << this->d_satellite;
d_GPS_FSM.Event_gps_word_preamble();
d_flag_preamble = true;
d_make_correlation = false;
d_symbol_counter_corr = 0;
d_preamble_time_samples = d_symbol_history.at(0).Tracking_sample_counter; // record the PRN start sample index associated to the preamble
if (!d_flag_frame_sync)
{
// send asynchronous message to tracking to inform of frame sync and extend correlation time
pmt::pmt_t value = pmt::from_double(static_cast<double>(d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs) - 0.001);
this->message_port_pub(pmt::mp("preamble_timestamp_s"), value);
d_flag_frame_sync = true;
if (corr_value < 0)
{
@ -236,6 +277,11 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
}
else
{
d_symbol_counter_corr++;
if (d_symbol_counter_corr > (GPS_SUBFRAME_MS - GPS_CA_TELEMETRY_SYMBOLS_PER_BIT))
{
d_make_correlation = true;
}
if (d_stat == 1)
{
preamble_diff_ms = round(((static_cast<double>(d_symbol_history.at(0).Tracking_sample_counter) - static_cast<double>(d_preamble_time_samples)) / static_cast<double>(d_symbol_history.at(0).fs)) * 1000.0);
@ -245,6 +291,8 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
d_stat = 0; //lost of frame sync
d_flag_frame_sync = false;
flag_TOW_set = false;
d_make_correlation = true;
d_symbol_counter_corr = 0;
}
}
}
@ -395,51 +443,8 @@ int gps_l1_ca_telemetry_decoder_cc::general_work(int noutput_items __attribute__
}
}
// remove used symbols from history
if (d_symbol_history.size() > required_symbols)
{
d_symbol_history.pop_front();
}
//3. Make the output (copy the object contents to the GNURadio reserved memory)
*out[0] = current_symbol;
return 1;
}
void gps_l1_ca_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
d_GPS_FSM.i_satellite_PRN = d_satellite.get_PRN();
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void gps_l1_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
d_GPS_FSM.i_channel_ID = channel;
DLOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
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) << "Telemetry decoder 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();
}
}
}
}

View File

@ -36,9 +36,9 @@
#include "gnss_satellite.h"
#include "gnss_synchro.h"
#include <gnuradio/block.h>
#include <deque>
#include <fstream>
#include <string>
#include <boost/circular_buffer.hpp>
class gps_l1_ca_telemetry_decoder_cc;
@ -79,11 +79,15 @@ private:
bool d_flag_frame_sync;
// symbols
std::deque<Gnss_Synchro> d_symbol_history;
boost::circular_buffer<Gnss_Synchro> d_symbol_history;
double d_symbol_accumulator;
short int d_symbol_accumulator_counter;
// symbol counting
bool d_make_correlation;
unsigned int d_symbol_counter_corr;
//bits and frame
unsigned short int d_frame_bit_index;
unsigned int d_GPS_frame_4bytes;

View File

@ -55,8 +55,6 @@ gps_l2c_telemetry_decoder_cc::gps_l2c_telemetry_decoder_cc(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -92,6 +90,41 @@ gps_l2c_telemetry_decoder_cc::~gps_l2c_telemetry_decoder_cc()
}
void gps_l2c_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "GPS L2C CNAV telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
}
void gps_l2c_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "GPS L2C CNAV channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry_L2CM_";
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) << "Telemetry decoder 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 Telemetry GPS L2 dump file " << e.what();
}
}
}
}
int gps_l2c_telemetry_decoder_cc::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)
{
@ -133,20 +166,20 @@ int gps_l2c_telemetry_decoder_cc::general_work(int noutput_items __attribute__((
{
// get ephemeris object for this SV
std::shared_ptr<Gps_CNAV_Ephemeris> tmp_obj = std::make_shared<Gps_CNAV_Ephemeris>(d_CNAV_Message.get_ephemeris());
std::cout << TEXT_BLUE << "New GPS CNAV message received: ephemeris from satellite " << d_satellite << TEXT_RESET << std::endl;
std::cout << TEXT_BLUE << "New GPS CNAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_CNAV_Message.have_new_iono() == true)
{
std::shared_ptr<Gps_CNAV_Iono> tmp_obj = std::make_shared<Gps_CNAV_Iono>(d_CNAV_Message.get_iono());
std::cout << TEXT_BLUE << "New GPS CNAV message received: iono model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
std::cout << TEXT_BLUE << "New GPS CNAV message received in channel " << d_channel << ": iono model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_CNAV_Message.have_new_utc_model() == true)
{
std::shared_ptr<Gps_CNAV_Utc_Model> tmp_obj = std::make_shared<Gps_CNAV_Utc_Model>(d_CNAV_Message.get_utc_model());
std::cout << TEXT_BLUE << "New GPS CNAV message received: UTC model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
std::cout << TEXT_BLUE << "New GPS CNAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
@ -195,38 +228,3 @@ int gps_l2c_telemetry_decoder_cc::general_work(int noutput_items __attribute__((
out[0] = current_synchro_data;
return 1;
}
void gps_l2c_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "GPS L2C CNAV telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
}
void gps_l2c_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "GPS L2C CNAV channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry_L2CM_";
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) << "Telemetry decoder 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 Telemetry GPS L2 dump file " << e.what();
}
}
}
}

View File

@ -1,7 +1,6 @@
/*!
* \file gps_l5_telemetry_decoder_cc.cc
* \brief Implementation of a NAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \brief Implementation of a CNAV message demodulator block
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
*
* -------------------------------------------------------------------------
@ -31,12 +30,13 @@
#include "gps_l5_telemetry_decoder_cc.h"
#include "display.h"
#include "gnss_synchro.h"
#include "gps_cnav_ephemeris.h"
#include "gps_cnav_iono.h"
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <boost/lexical_cast.hpp>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <bitset>
#include <iostream>
#include <sstream>
@ -56,8 +56,6 @@ gps_l5_telemetry_decoder_cc::gps_l5_telemetry_decoder_cc(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -102,6 +100,43 @@ gps_l5_telemetry_decoder_cc::~gps_l5_telemetry_decoder_cc()
}
void gps_l5_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
LOG(INFO) << "GPS L5 CNAV telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
d_CNAV_Message.reset();
}
void gps_l5_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
d_CNAV_Message.reset();
LOG(INFO) << "GPS L5 CNAV channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry_L5_";
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) << "Telemetry decoder 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 Telemetry GPS L5 dump file " << e.what();
}
}
}
}
int gps_l5_telemetry_decoder_cc::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)
{
@ -183,20 +218,20 @@ int gps_l5_telemetry_decoder_cc::general_work(int noutput_items __attribute__((u
{
// get ephemeris object for this SV
std::shared_ptr<Gps_CNAV_Ephemeris> tmp_obj = std::make_shared<Gps_CNAV_Ephemeris>(d_CNAV_Message.get_ephemeris());
std::cout << "New GPS L5 CNAV message received: ephemeris from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New GPS L5 CNAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_CNAV_Message.have_new_iono() == true)
{
std::shared_ptr<Gps_CNAV_Iono> tmp_obj = std::make_shared<Gps_CNAV_Iono>(d_CNAV_Message.get_iono());
std::cout << "New GPS L5 CNAV message received: iono model parameters from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New GPS L5 CNAV message received in channel " << d_channel << ": iono model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_CNAV_Message.have_new_utc_model() == true)
{
std::shared_ptr<Gps_CNAV_Utc_Model> tmp_obj = std::make_shared<Gps_CNAV_Utc_Model>(d_CNAV_Message.get_utc_model());
std::cout << "New GPS L5 CNAV message received: UTC model parameters from satellite " << d_satellite << std::endl;
std::cout << TEXT_MAGENTA << "New GPS L5 CNAV message received in channel " << d_channel << ": UTC model parameters from satellite " << d_satellite << TEXT_RESET << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
@ -245,40 +280,3 @@ int gps_l5_telemetry_decoder_cc::general_work(int noutput_items __attribute__((u
out[0] = current_synchro_data;
return 1;
}
void gps_l5_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
LOG(INFO) << "GPS L5 CNAV telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
d_CNAV_Message.reset();
}
void gps_l5_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
d_CNAV_Message.reset();
LOG(INFO) << "GPS L5 CNAV channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry_L5_";
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) << "Telemetry decoder 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 Telemetry GPS L5 dump file " << e.what();
}
}
}
}

View File

@ -1,7 +1,6 @@
/*!
* \file gps_l5_telemetry_decoder_cc.h
* \brief Interface of a CNAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \brief Interface of a CNAV message demodulator block
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
* -------------------------------------------------------------------------
*
@ -42,7 +41,8 @@
#include <utility>
#include <vector>
extern "C" {
extern "C"
{
#include "cnav_msg.h"
#include "edc.h"
#include "bits.h"

View File

@ -59,8 +59,6 @@ sbas_l1_telemetry_decoder_cc::sbas_l1_telemetry_decoder_cc(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
@ -89,88 +87,6 @@ sbas_l1_telemetry_decoder_cc::~sbas_l1_telemetry_decoder_cc()
}
int sbas_l1_telemetry_decoder_cc::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)
{
VLOG(FLOW) << "general_work(): "
<< "noutput_items=" << noutput_items << "\toutput_items real size=" << output_items.size() << "\tninput_items size=" << ninput_items.size() << "\tinput_items real size=" << input_items.size() << "\tninput_items[0]=" << ninput_items[0];
// get pointers on in- and output gnss-synchro objects
Gnss_Synchro *out = reinterpret_cast<Gnss_Synchro *>(output_items[0]); // Get the output buffer pointer
const Gnss_Synchro *in = reinterpret_cast<const Gnss_Synchro *>(input_items[0]); // Get the input buffer pointer
Gnss_Synchro current_symbol; //structure to save the synchronization information and send the output object to the next block
//1. Copy the current tracking output
current_symbol = in[0];
// copy correlation samples into samples vector
d_sample_buf.push_back(current_symbol.Prompt_I); //add new symbol to the symbol queue
// store the time stamp of the first sample in the processed sample block
double sample_stamp = static_cast<double>(in[0].Tracking_sample_counter) / static_cast<double>(in[0].fs);
// decode only if enough samples in buffer
if (d_sample_buf.size() >= d_block_size)
{
// align correlation samples in pairs
// and obtain the symbols by summing the paired correlation samples
std::vector<double> symbols;
bool sample_alignment = d_sample_aligner.get_symbols(d_sample_buf, symbols);
// align symbols in pairs
// and obtain the bits by decoding the symbol pairs
std::vector<int> bits;
bool symbol_alignment = d_symbol_aligner_and_decoder.get_bits(symbols, bits);
// search for preambles
// and extract the corresponding message candidates
std::vector<msg_candiate_int_t> msg_candidates;
d_frame_detector.get_frame_candidates(bits, msg_candidates);
// verify checksum
// and return the valid messages
std::vector<msg_candiate_char_t> valid_msgs;
d_crc_verifier.get_valid_frames(msg_candidates, valid_msgs);
// compute message sample stamp
// and fill messages in SBAS raw message objects
//std::vector<Sbas_Raw_Msg> sbas_raw_msgs;
for (std::vector<msg_candiate_char_t>::const_iterator it = valid_msgs.cbegin();
it != valid_msgs.cend(); ++it)
{
int message_sample_offset =
(sample_alignment ? 0 : -1) + d_samples_per_symbol * (symbol_alignment ? -1 : 0) + d_samples_per_symbol * d_symbols_per_bit * it->first;
double message_sample_stamp = sample_stamp + static_cast<double>(message_sample_offset) / 1000.0;
VLOG(EVENT) << "message_sample_stamp=" << message_sample_stamp
<< " (sample_stamp=" << sample_stamp
<< " sample_alignment=" << sample_alignment
<< " symbol_alignment=" << symbol_alignment
<< " relative_preamble_start=" << it->first
<< " message_sample_offset=" << message_sample_offset
<< ")";
//Sbas_Raw_Msg sbas_raw_msg(message_sample_stamp, this->d_satellite.get_PRN(), it->second);
//sbas_raw_msgs.push_back(sbas_raw_msg);
}
// parse messages
// and send them to the SBAS raw message queue
//for(std::vector<Sbas_Raw_Msg>::iterator it = sbas_raw_msgs.begin(); it != sbas_raw_msgs.end(); it++)
// {
//std::cout << "SBAS message type " << it->get_msg_type() << " from PRN" << it->get_prn() << " received" << std::endl;
//sbas_telemetry_data.update(*it);
// }
// clear all processed samples in the input buffer
d_sample_buf.clear();
}
// UPDATE GNSS SYNCHRO DATA
// actually the SBAS telemetry decoder doesn't support ranging
current_symbol.Flag_valid_word = false; // indicate to observable block that this synchro object isn't valid for pseudorange computation
out[0] = current_symbol;
consume_each(1); // tell scheduler input items consumed
return 1; // tell scheduler output items produced
}
void sbas_l1_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
@ -186,7 +102,6 @@ void sbas_l1_telemetry_decoder_cc::set_channel(int channel)
// ### helper class for sample alignment ###
sbas_l1_telemetry_decoder_cc::sample_aligner::sample_aligner()
{
d_n_smpls_in_history = 3;
@ -405,12 +320,11 @@ void sbas_l1_telemetry_decoder_cc::frame_detector::get_frame_candidates(const st
// ### helper class for checking the CRC of the message candidates ###
void sbas_l1_telemetry_decoder_cc::crc_verifier::reset()
{
}
void sbas_l1_telemetry_decoder_cc::crc_verifier::get_valid_frames(const std::vector<msg_candiate_int_t> msg_candidates, std::vector<msg_candiate_char_t> &valid_msgs)
{
std::stringstream ss;
@ -502,3 +416,85 @@ void sbas_l1_telemetry_decoder_cc::crc_verifier::zerropad_front_and_convert_to_b
<< std::setfill('0') << std::hex << static_cast<unsigned int>(byte)
<< std::setfill(' ') << std::resetiosflags(std::ios::hex);
}
int sbas_l1_telemetry_decoder_cc::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)
{
VLOG(FLOW) << "general_work(): "
<< "noutput_items=" << noutput_items << "\toutput_items real size=" << output_items.size() << "\tninput_items size=" << ninput_items.size() << "\tinput_items real size=" << input_items.size() << "\tninput_items[0]=" << ninput_items[0];
// get pointers on in- and output gnss-synchro objects
Gnss_Synchro *out = reinterpret_cast<Gnss_Synchro *>(output_items[0]); // Get the output buffer pointer
const Gnss_Synchro *in = reinterpret_cast<const Gnss_Synchro *>(input_items[0]); // Get the input buffer pointer
Gnss_Synchro current_symbol; //structure to save the synchronization information and send the output object to the next block
//1. Copy the current tracking output
current_symbol = in[0];
// copy correlation samples into samples vector
d_sample_buf.push_back(current_symbol.Prompt_I); //add new symbol to the symbol queue
// store the time stamp of the first sample in the processed sample block
double sample_stamp = static_cast<double>(in[0].Tracking_sample_counter) / static_cast<double>(in[0].fs);
// decode only if enough samples in buffer
if (d_sample_buf.size() >= d_block_size)
{
// align correlation samples in pairs
// and obtain the symbols by summing the paired correlation samples
std::vector<double> symbols;
bool sample_alignment = d_sample_aligner.get_symbols(d_sample_buf, symbols);
// align symbols in pairs
// and obtain the bits by decoding the symbol pairs
std::vector<int> bits;
bool symbol_alignment = d_symbol_aligner_and_decoder.get_bits(symbols, bits);
// search for preambles
// and extract the corresponding message candidates
std::vector<msg_candiate_int_t> msg_candidates;
d_frame_detector.get_frame_candidates(bits, msg_candidates);
// verify checksum
// and return the valid messages
std::vector<msg_candiate_char_t> valid_msgs;
d_crc_verifier.get_valid_frames(msg_candidates, valid_msgs);
// compute message sample stamp
// and fill messages in SBAS raw message objects
//std::vector<Sbas_Raw_Msg> sbas_raw_msgs;
for (std::vector<msg_candiate_char_t>::const_iterator it = valid_msgs.cbegin();
it != valid_msgs.cend(); ++it)
{
int message_sample_offset =
(sample_alignment ? 0 : -1) + d_samples_per_symbol * (symbol_alignment ? -1 : 0) + d_samples_per_symbol * d_symbols_per_bit * it->first;
double message_sample_stamp = sample_stamp + static_cast<double>(message_sample_offset) / 1000.0;
VLOG(EVENT) << "message_sample_stamp=" << message_sample_stamp
<< " (sample_stamp=" << sample_stamp
<< " sample_alignment=" << sample_alignment
<< " symbol_alignment=" << symbol_alignment
<< " relative_preamble_start=" << it->first
<< " message_sample_offset=" << message_sample_offset
<< ")";
//Sbas_Raw_Msg sbas_raw_msg(message_sample_stamp, this->d_satellite.get_PRN(), it->second);
//sbas_raw_msgs.push_back(sbas_raw_msg);
}
// parse messages
// and send them to the SBAS raw message queue
//for(std::vector<Sbas_Raw_Msg>::iterator it = sbas_raw_msgs.begin(); it != sbas_raw_msgs.end(); it++)
// {
//std::cout << "SBAS message type " << it->get_msg_type() << " from PRN" << it->get_prn() << " received" << std::endl;
//sbas_telemetry_data.update(*it);
// }
// clear all processed samples in the input buffer
d_sample_buf.clear();
}
// UPDATE GNSS SYNCHRO DATA
// actually the SBAS telemetry decoder doesn't support ranging
current_symbol.Flag_valid_word = false; // indicate to observable block that this synchro object isn't valid for pseudorange computation
out[0] = current_symbol;
consume_each(1); // tell scheduler input items consumed
return 1; // tell scheduler output items produced
}

View File

@ -39,13 +39,16 @@
//************ GPS WORD TO SUBFRAME DECODER STATE MACHINE **********
struct Ev_gps_word_valid : sc::event<Ev_gps_word_valid>
{
};
struct Ev_gps_word_invalid : sc::event<Ev_gps_word_invalid>
{
};
struct Ev_gps_word_preamble : sc::event<Ev_gps_word_preamble>
{
};
@ -245,16 +248,20 @@ void GpsL1CaSubframeFsm::gps_word_to_subframe(int position)
std::memcpy(&d_subframe[position * GPS_WORD_LENGTH], &d_GPS_frame_4bytes, sizeof(char) * GPS_WORD_LENGTH);
}
void GpsL1CaSubframeFsm::clear_flag_new_subframe()
{
d_flag_new_subframe = false;
}
void GpsL1CaSubframeFsm::gps_subframe_to_nav_msg()
{
//int subframe_ID;
// NEW GPS SUBFRAME HAS ARRIVED!
d_subframe_ID = d_nav.subframe_decoder(this->d_subframe); //decode the subframe
std::cout << "New GPS NAV message received: subframe "
std::cout << "New GPS NAV message received in channel " << i_channel_ID << ": "
<< "subframe "
<< d_subframe_ID << " from satellite "
<< Gnss_Satellite(std::string("GPS"), i_satellite_PRN) << std::endl;
d_nav.i_satellite_PRN = i_satellite_PRN;
@ -263,6 +270,7 @@ void GpsL1CaSubframeFsm::gps_subframe_to_nav_msg()
d_flag_new_subframe = true;
}
void GpsL1CaSubframeFsm::Event_gps_word_valid()
{
this->process_event(Ev_gps_word_valid());

View File

@ -82,7 +82,6 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(dllpllconf_t conf_) : gr::block("dl
{
trk_parameters = conf_;
// Telemetry bit synchronization message port input
this->message_port_register_in(pmt::mp("preamble_timestamp_s"));
this->message_port_register_out(pmt::mp("events"));
this->set_relative_rate(1.0 / static_cast<double>(trk_parameters.vector_length));
@ -362,6 +361,16 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(dllpllconf_t conf_) : gr::block("dl
d_code_phase_samples = 0.0;
d_last_prompt = gr_complex(0.0, 0.0);
d_state = 0; // initial state: standby
map_signal_pretty_name["1C"] = "L1 C/A";
map_signal_pretty_name["1B"] = "E1";
map_signal_pretty_name["1G"] = "L1 C/A";
map_signal_pretty_name["2S"] = "L2C";
map_signal_pretty_name["2G"] = "L2 C/A";
map_signal_pretty_name["5X"] = "E5a";
map_signal_pretty_name["L5"] = "L5";
signal_pretty_name = map_signal_pretty_name[signal_type];
}
@ -504,7 +513,7 @@ void dll_pll_veml_tracking::start_tracking()
d_code_loop_filter.set_pdi(static_cast<float>(d_code_period));
// DEBUG OUTPUT
std::cout << "Tracking of " << systemName << " " << signal_type << " signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
std::cout << "Tracking of " << systemName << " " << signal_pretty_name << " signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking pull-in
@ -1256,8 +1265,8 @@ int dll_pll_veml_tracking::general_work(int noutput_items __attribute__((unused)
next_state = acquire_secondary();
if (next_state)
{
std::cout << "Secondary code locked for CH " << d_channel
<< " : Satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
std::cout << systemName << " " << signal_pretty_name << " secondary code locked in channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
}
d_Prompt_buffer_deque.pop_front();

View File

@ -38,6 +38,7 @@
#include <gnuradio/block.h>
#include <fstream>
#include <string>
#include <map>
typedef struct
{
@ -118,6 +119,8 @@ private:
std::string systemName;
std::string signal_type;
std::string *d_secondary_code_string;
std::map<std::string, std::string> map_signal_pretty_name;
std::string signal_pretty_name;
//tracking state machine
int d_state;

View File

@ -99,8 +99,6 @@ Galileo_E1_Tcp_Connector_Tracking_cc::Galileo_E1_Tcp_Connector_Tracking_cc(
size_t port_ch0) : gr::block("Galileo_E1_Tcp_Connector_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
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->message_port_register_out(pmt::mp("events"));
this->set_relative_rate(1.0 / vector_length);
// initialize internal vars
@ -224,7 +222,7 @@ void Galileo_E1_Tcp_Connector_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of Galileo E1 signal started 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;
LOG(INFO) << "Tracking of Galileo E1 signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -263,6 +261,45 @@ Galileo_E1_Tcp_Connector_Tracking_cc::~Galileo_E1_Tcp_Connector_Tracking_cc()
}
void Galileo_E1_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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();
}
}
}
//! Listen for connections on a TCP port
if (d_listen_connection == true)
{
d_port = d_port_ch0 + d_channel;
d_listen_connection = d_tcp_com.listen_tcp_connection(d_port, d_port_ch0);
}
}
void Galileo_E1_Tcp_Connector_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int Galileo_E1_Tcp_Connector_Tracking_cc::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)
{
@ -514,42 +551,3 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
return 0;
}
}
void Galileo_E1_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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();
}
}
}
//! Listen for connections on a TCP port
if (d_listen_connection == true)
{
d_port = d_port_ch0 + d_channel;
d_listen_connection = d_tcp_com.listen_tcp_connection(d_port, d_port_ch0);
}
}
void Galileo_E1_Tcp_Connector_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -295,8 +295,8 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking()
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;
std::cout << "Tracking of GLONASS L1 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Tracking of GLONASS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -558,6 +558,38 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::save_matfile()
}
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int glonass_l1_ca_dll_pll_c_aid_tracking_cc::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)
{
@ -895,35 +927,3 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -292,8 +292,8 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking()
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;
std::cout << "Tracking of GLONASS L1 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Tracking of GLONASS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -551,6 +551,38 @@ glonass_l1_ca_dll_pll_c_aid_tracking_sc::~glonass_l1_ca_dll_pll_c_aid_tracking_s
}
void glonass_l1_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l1_ca_dll_pll_c_aid_tracking_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int glonass_l1_ca_dll_pll_c_aid_tracking_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)
{
@ -886,35 +918,3 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void glonass_l1_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l1_ca_dll_pll_c_aid_tracking_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -94,8 +94,6 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
float early_late_space_chips) : gr::block("Glonass_L1_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
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->message_port_register_out(pmt::mp("events"));
// initialize internal vars
@ -253,7 +251,7 @@ void Glonass_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GLONASS L1 C/A signal started 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;
LOG(INFO) << "Tracking of GLONASS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -512,6 +510,38 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::save_matfile()
}
void Glonass_L1_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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 Glonass_L1_Ca_Dll_Pll_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int Glonass_L1_Ca_Dll_Pll_Tracking_cc::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)
{
@ -738,35 +768,3 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
d_sample_counter += d_current_prn_length_samples; // count for the processed samples
return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void Glonass_L1_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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 Glonass_L1_Ca_Dll_Pll_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -292,8 +292,8 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_cc::start_tracking()
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;
std::cout << "Tracking of GLONASS L2 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Tracking of GLONASS L2 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -555,6 +555,38 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::save_matfile()
}
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int glonass_l2_ca_dll_pll_c_aid_tracking_cc::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)
{
@ -892,35 +924,3 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -290,8 +290,8 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_sc::start_tracking()
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;
std::cout << "Tracking of GLONASS L2 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Tracking of GLONASS L2 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -549,6 +549,38 @@ glonass_l2_ca_dll_pll_c_aid_tracking_sc::~glonass_l2_ca_dll_pll_c_aid_tracking_s
}
void glonass_l2_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l2_ca_dll_pll_c_aid_tracking_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int glonass_l2_ca_dll_pll_c_aid_tracking_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)
{
@ -884,35 +916,3 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void glonass_l2_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
catch (const std::ifstream::failure *e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e->what() << std::endl;
}
}
}
}
void glonass_l2_ca_dll_pll_c_aid_tracking_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -94,8 +94,6 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
float early_late_space_chips) : gr::block("Glonass_L2_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
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->message_port_register_out(pmt::mp("events"));
// initialize internal vars
@ -253,7 +251,7 @@ void Glonass_L2_Ca_Dll_Pll_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GLONASS L2 C/A signal started 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;
LOG(INFO) << "Tracking of GLONASS L2 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -512,6 +510,38 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::save_matfile()
}
void Glonass_L2_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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 Glonass_L2_Ca_Dll_Pll_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int Glonass_L2_Ca_Dll_Pll_Tracking_cc::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)
{
@ -738,35 +768,3 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
d_sample_counter += d_current_prn_length_samples; // count for the processed samples
return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
}
void Glonass_L2_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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 Glonass_L2_Ca_Dll_Pll_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -276,7 +276,7 @@ void gps_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GPS L1 C/A signal started 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;
LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -538,6 +538,38 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::save_matfile()
}
void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
}
}
}
void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int gps_l1_ca_dll_pll_c_aid_tracking_cc::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)
{
@ -843,7 +875,6 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __attrib
tmp_float = 1.0 / (d_carr_phase_error_secs_Ti * CURRENT_INTEGRATION_TIME_S);
d_dump_file.write(reinterpret_cast<char *>(&tmp_float), sizeof(float));
tmp_float = 1.0 / (d_code_error_filt_chips_Ti * CURRENT_INTEGRATION_TIME_S);
;
d_dump_file.write(reinterpret_cast<char *>(&tmp_float), sizeof(float));
// DLL commands
tmp_float = d_code_error_chips_Ti * CURRENT_INTEGRATION_TIME_S;
@ -882,35 +913,3 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __attrib
return 0;
}
}
void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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() << std::endl;
}
}
}
}
void gps_l1_ca_dll_pll_c_aid_tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -268,12 +268,8 @@ void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::start_tracking()
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;
std::cout << "Tracking of GPS L1 C/A signal started on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -333,6 +329,257 @@ gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::~gps_l1_ca_dll_pll_c_aid_tracking_fpga
}
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();
}
}
}
}
int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::save_matfile()
{
// READ DUMP FILE
std::ifstream::pos_type size;
int number_of_double_vars = 11;
int number_of_float_vars = 5;
int epoch_size_bytes = sizeof(unsigned long int) + sizeof(double) * number_of_double_vars +
sizeof(float) * number_of_float_vars + sizeof(unsigned int);
std::ifstream dump_file;
dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit);
try
{
dump_file.open(d_dump_filename.c_str(), std::ios::binary | std::ios::ate);
}
catch (const std::ifstream::failure &e)
{
std::cerr << "Problem opening dump file:" << e.what() << std::endl;
return 1;
}
// count number of epochs and rewind
long int num_epoch = 0;
if (dump_file.is_open())
{
size = dump_file.tellg();
num_epoch = static_cast<long int>(size) / static_cast<long int>(epoch_size_bytes);
dump_file.seekg(0, std::ios::beg);
}
else
{
return 1;
}
float *abs_E = new float[num_epoch];
float *abs_P = new float[num_epoch];
float *abs_L = new float[num_epoch];
float *Prompt_I = new float[num_epoch];
float *Prompt_Q = new float[num_epoch];
unsigned long int *PRN_start_sample_count = new unsigned long int[num_epoch];
double *acc_carrier_phase_rad = new double[num_epoch];
double *carrier_doppler_hz = new double[num_epoch];
double *code_freq_chips = new double[num_epoch];
double *carr_error_hz = new double[num_epoch];
double *carr_error_filt_hz = new double[num_epoch];
double *code_error_chips = new double[num_epoch];
double *code_error_filt_chips = new double[num_epoch];
double *CN0_SNV_dB_Hz = new double[num_epoch];
double *carrier_lock_test = new double[num_epoch];
double *aux1 = new double[num_epoch];
double *aux2 = new double[num_epoch];
unsigned int *PRN = new unsigned int[num_epoch];
try
{
if (dump_file.is_open())
{
for (long int i = 0; i < num_epoch; i++)
{
dump_file.read(reinterpret_cast<char *>(&abs_E[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&abs_P[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&abs_L[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&Prompt_I[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&Prompt_Q[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&PRN_start_sample_count[i]), sizeof(unsigned long int));
dump_file.read(reinterpret_cast<char *>(&acc_carrier_phase_rad[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carrier_doppler_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_freq_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carr_error_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carr_error_filt_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_error_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_error_filt_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&CN0_SNV_dB_Hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carrier_lock_test[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&aux1[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&aux2[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&PRN[i]), sizeof(unsigned int));
}
}
dump_file.close();
}
catch (const std::ifstream::failure &e)
{
std::cerr << "Problem reading dump file:" << e.what() << std::endl;
delete[] abs_E;
delete[] abs_P;
delete[] abs_L;
delete[] Prompt_I;
delete[] Prompt_Q;
delete[] PRN_start_sample_count;
delete[] acc_carrier_phase_rad;
delete[] carrier_doppler_hz;
delete[] code_freq_chips;
delete[] carr_error_hz;
delete[] carr_error_filt_hz;
delete[] code_error_chips;
delete[] code_error_filt_chips;
delete[] CN0_SNV_dB_Hz;
delete[] carrier_lock_test;
delete[] aux1;
delete[] aux2;
delete[] PRN;
return 1;
}
// WRITE MAT FILE
mat_t *matfp;
matvar_t *matvar;
std::string filename = d_dump_filename;
filename.erase(filename.length() - 4, 4);
filename.append(".mat");
matfp = Mat_CreateVer(filename.c_str(), NULL, MAT_FT_MAT73);
if (reinterpret_cast<long *>(matfp) != NULL)
{
size_t dims[2] = {1, static_cast<size_t>(num_epoch)};
matvar = Mat_VarCreate("abs_E", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_E, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("abs_P", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_P, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("abs_L", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_L, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("Prompt_I", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_I, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("Prompt_Q", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_Q, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("PRN_start_sample_count", MAT_C_UINT64, MAT_T_UINT64, 2, dims, PRN_start_sample_count, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("acc_carrier_phase_rad", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, acc_carrier_phase_rad, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carrier_doppler_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_doppler_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_freq_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_freq_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carr_error_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carr_error_filt_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_filt_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_error_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_error_filt_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_filt_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("CN0_SNV_dB_Hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, CN0_SNV_dB_Hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carrier_lock_test", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_lock_test, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("aux1", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux1, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("aux2", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux2, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("PRN", MAT_C_UINT32, MAT_T_UINT32, 2, dims, PRN, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
}
Mat_Close(matfp);
delete[] abs_E;
delete[] abs_P;
delete[] abs_L;
delete[] Prompt_I;
delete[] Prompt_Q;
delete[] PRN_start_sample_count;
delete[] acc_carrier_phase_rad;
delete[] carrier_doppler_hz;
delete[] code_freq_chips;
delete[] carr_error_hz;
delete[] carr_error_filt_hz;
delete[] code_error_chips;
delete[] code_error_filt_chips;
delete[] CN0_SNV_dB_Hz;
delete[] carrier_lock_test;
delete[] aux1;
delete[] aux2;
delete[] PRN;
return 0;
}
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;
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::reset(void)
{
multicorrelator_fpga_8sc->unlock_channel();
}
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)),
@ -703,253 +950,3 @@ int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::general_work(
return 0;
}
}
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();
}
}
}
}
int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::save_matfile()
{
// READ DUMP FILE
std::ifstream::pos_type size;
int number_of_double_vars = 11;
int number_of_float_vars = 5;
int epoch_size_bytes = sizeof(unsigned long int) + sizeof(double) * number_of_double_vars +
sizeof(float) * number_of_float_vars + sizeof(unsigned int);
std::ifstream dump_file;
dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit);
try
{
dump_file.open(d_dump_filename.c_str(), std::ios::binary | std::ios::ate);
}
catch (const std::ifstream::failure &e)
{
std::cerr << "Problem opening dump file:" << e.what() << std::endl;
return 1;
}
// count number of epochs and rewind
long int num_epoch = 0;
if (dump_file.is_open())
{
size = dump_file.tellg();
num_epoch = static_cast<long int>(size) / static_cast<long int>(epoch_size_bytes);
dump_file.seekg(0, std::ios::beg);
}
else
{
return 1;
}
float *abs_E = new float[num_epoch];
float *abs_P = new float[num_epoch];
float *abs_L = new float[num_epoch];
float *Prompt_I = new float[num_epoch];
float *Prompt_Q = new float[num_epoch];
unsigned long int *PRN_start_sample_count = new unsigned long int[num_epoch];
double *acc_carrier_phase_rad = new double[num_epoch];
double *carrier_doppler_hz = new double[num_epoch];
double *code_freq_chips = new double[num_epoch];
double *carr_error_hz = new double[num_epoch];
double *carr_error_filt_hz = new double[num_epoch];
double *code_error_chips = new double[num_epoch];
double *code_error_filt_chips = new double[num_epoch];
double *CN0_SNV_dB_Hz = new double[num_epoch];
double *carrier_lock_test = new double[num_epoch];
double *aux1 = new double[num_epoch];
double *aux2 = new double[num_epoch];
unsigned int *PRN = new unsigned int[num_epoch];
try
{
if (dump_file.is_open())
{
for (long int i = 0; i < num_epoch; i++)
{
dump_file.read(reinterpret_cast<char *>(&abs_E[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&abs_P[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&abs_L[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&Prompt_I[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&Prompt_Q[i]), sizeof(float));
dump_file.read(reinterpret_cast<char *>(&PRN_start_sample_count[i]), sizeof(unsigned long int));
dump_file.read(reinterpret_cast<char *>(&acc_carrier_phase_rad[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carrier_doppler_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_freq_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carr_error_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carr_error_filt_hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_error_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&code_error_filt_chips[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&CN0_SNV_dB_Hz[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&carrier_lock_test[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&aux1[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&aux2[i]), sizeof(double));
dump_file.read(reinterpret_cast<char *>(&PRN[i]), sizeof(unsigned int));
}
}
dump_file.close();
}
catch (const std::ifstream::failure &e)
{
std::cerr << "Problem reading dump file:" << e.what() << std::endl;
delete[] abs_E;
delete[] abs_P;
delete[] abs_L;
delete[] Prompt_I;
delete[] Prompt_Q;
delete[] PRN_start_sample_count;
delete[] acc_carrier_phase_rad;
delete[] carrier_doppler_hz;
delete[] code_freq_chips;
delete[] carr_error_hz;
delete[] carr_error_filt_hz;
delete[] code_error_chips;
delete[] code_error_filt_chips;
delete[] CN0_SNV_dB_Hz;
delete[] carrier_lock_test;
delete[] aux1;
delete[] aux2;
delete[] PRN;
return 1;
}
// WRITE MAT FILE
mat_t *matfp;
matvar_t *matvar;
std::string filename = d_dump_filename;
filename.erase(filename.length() - 4, 4);
filename.append(".mat");
matfp = Mat_CreateVer(filename.c_str(), NULL, MAT_FT_MAT73);
if (reinterpret_cast<long *>(matfp) != NULL)
{
size_t dims[2] = {1, static_cast<size_t>(num_epoch)};
matvar = Mat_VarCreate("abs_E", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_E, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("abs_P", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_P, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("abs_L", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, abs_L, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("Prompt_I", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_I, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("Prompt_Q", MAT_C_SINGLE, MAT_T_SINGLE, 2, dims, Prompt_Q, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("PRN_start_sample_count", MAT_C_UINT64, MAT_T_UINT64, 2, dims, PRN_start_sample_count, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("acc_carrier_phase_rad", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, acc_carrier_phase_rad, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carrier_doppler_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_doppler_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_freq_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_freq_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carr_error_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carr_error_filt_hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carr_error_filt_hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_error_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("code_error_filt_chips", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, code_error_filt_chips, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("CN0_SNV_dB_Hz", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, CN0_SNV_dB_Hz, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("carrier_lock_test", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, carrier_lock_test, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("aux1", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux1, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("aux2", MAT_C_DOUBLE, MAT_T_DOUBLE, 2, dims, aux2, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
matvar = Mat_VarCreate("PRN", MAT_C_UINT32, MAT_T_UINT32, 2, dims, PRN, 0);
Mat_VarWrite(matfp, matvar, MAT_COMPRESSION_ZLIB); // or MAT_COMPRESSION_NONE
Mat_VarFree(matvar);
}
Mat_Close(matfp);
delete[] abs_E;
delete[] abs_P;
delete[] abs_L;
delete[] Prompt_I;
delete[] Prompt_Q;
delete[] PRN_start_sample_count;
delete[] acc_carrier_phase_rad;
delete[] carrier_doppler_hz;
delete[] code_freq_chips;
delete[] carr_error_hz;
delete[] carr_error_filt_hz;
delete[] code_error_chips;
delete[] code_error_filt_chips;
delete[] CN0_SNV_dB_Hz;
delete[] carrier_lock_test;
delete[] aux1;
delete[] aux2;
delete[] PRN;
return 0;
}
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;
}
void gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::reset(void)
{
multicorrelator_fpga_8sc->unlock_channel();
}

View File

@ -277,7 +277,7 @@ void gps_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GPS L1 C/A signal started 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;
LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -541,6 +541,38 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::save_matfile()
}
void gps_l1_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int gps_l1_ca_dll_pll_c_aid_tracking_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)
{
@ -883,35 +915,3 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __attrib
return 0;
}
}
void gps_l1_ca_dll_pll_c_aid_tracking_sc::set_channel(unsigned int channel)
{
d_channel = 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_sc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -245,7 +245,7 @@ void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GPS L1 C/A signal started 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;
LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -287,6 +287,38 @@ Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::~Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc()
}
void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::set_channel(unsigned int channel)
{
d_channel = 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_Tracking_GPU_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::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)
{
@ -539,35 +571,3 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
return 0;
}
}
void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::set_channel(unsigned int channel)
{
d_channel = 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_Tracking_GPU_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -91,8 +91,6 @@ Gps_L1_Ca_Tcp_Connector_Tracking_cc::Gps_L1_Ca_Tcp_Connector_Tracking_cc(
size_t port_ch0) : gr::block("Gps_L1_Ca_Tcp_Connector_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
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->message_port_register_out(pmt::mp("events"));
// initialize internal vars
d_dump = dump;
@ -252,7 +250,7 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking of GPS L1 C/A signal started 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;
LOG(INFO) << "Tracking of GPS L1 C/A signal for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
@ -293,6 +291,45 @@ Gps_L1_Ca_Tcp_Connector_Tracking_cc::~Gps_L1_Ca_Tcp_Connector_Tracking_cc()
}
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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();
}
}
}
//! Listen for connections on a TCP port
if (d_listen_connection == true)
{
d_port = d_port_ch0 + d_channel;
d_listen_connection = d_tcp_com.listen_tcp_connection(d_port, d_port_ch0);
}
}
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}
int Gps_L1_Ca_Tcp_Connector_Tracking_cc::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)
{
@ -553,42 +590,3 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
return 0;
}
}
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = 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();
}
}
}
//! Listen for connections on a TCP port
if (d_listen_connection == true)
{
d_port = d_port_ch0 + d_channel;
d_listen_connection = d_tcp_com.listen_tcp_connection(d_port, d_port_ch0);
}
}
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_gnss_synchro(Gnss_Synchro *p_gnss_synchro)
{
d_acquisition_gnss_synchro = p_gnss_synchro;
}

View File

@ -148,6 +148,7 @@ void ControlThread::run()
std::cout << "Stopping GNSS-SDR, please wait!" << std::endl;
flowgraph_->stop();
stop_ = true;
flowgraph_->disconnect();
//Join keyboard thread
#ifdef OLD_BOOST

View File

@ -1,15 +1,13 @@
/*!
* \file gnss_flowgraph.cc
* \brief Implementation of a GNSS receiver flowgraph
* \brief Implementation of a GNSS receiver flow graph
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Luis Esteve, 2012. luis(at)epsilon-formacion.com
* Carles Fernandez-Prades, 2014. cfernandez(at)cttc.es
*
* Detailed description of the file here if needed.
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
@ -60,7 +58,15 @@ GNSSFlowgraph::GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configurati
}
GNSSFlowgraph::~GNSSFlowgraph() {}
GNSSFlowgraph::~GNSSFlowgraph()
{
if (connected_)
{
GNSSFlowgraph::disconnect();
}
}
void GNSSFlowgraph::start()
{
if (running_)
@ -93,10 +99,9 @@ void GNSSFlowgraph::stop()
void GNSSFlowgraph::connect()
{
/* Connects the blocks in the flowgraph
*
* Signal Source > Signal conditioner >> Channels >> Observables >> PVT
*/
// Connects the blocks in the flow graph
// Signal Source > Signal conditioner >> Channels >> Observables >> PVT
LOG(INFO) << "Connecting flowgraph";
if (connected_)
{
@ -184,8 +189,8 @@ void GNSSFlowgraph::connect()
{
try
{
//TODO: Remove this array implementation and create generic multistream connector
//(if a signal source has more than 1 stream, then connect it to the multistream signal conditioner)
// TODO: Remove this array implementation and create generic multistream connector
// (if a signal source has more than 1 stream, then connect it to the multistream signal conditioner)
if (sig_source_.at(i)->implementation().compare("Raw_Array_Signal_Source") == 0)
{
//Multichannel Array
@ -198,14 +203,14 @@ void GNSSFlowgraph::connect()
}
else
{
//TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
//Include GetRFChannels in the interface to avoid read config parameters here
//read the number of RF channels for each front-end
// TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
// Include GetRFChannels in the interface to avoid read config parameters here
// read the number of RF channels for each front-end
RF_Channels = configuration_->property(sig_source_.at(i)->role() + ".RF_channels", 1);
for (int j = 0; j < RF_Channels; j++)
{
//Connect the multichannel signal source to multiple signal conditioners
// Connect the multichannel signal source to multiple signal conditioners
// GNURADIO max_streams=-1 means infinite ports!
LOG(INFO) << "sig_source_.at(i)->get_right_block()->output_signature()->max_streams()=" << sig_source_.at(i)->get_right_block()->output_signature()->max_streams();
LOG(INFO) << "sig_conditioner_.at(signal_conditioner_ID)->get_left_block()->input_signature()=" << sig_conditioner_.at(signal_conditioner_ID)->get_left_block()->input_signature()->max_streams();
@ -244,8 +249,8 @@ void GNSSFlowgraph::connect()
}
DLOG(INFO) << "Signal source connected to signal conditioner";
//connect the signal source to sample counter
//connect the sample counter to Observables
// connect the signal source to sample counter
// connect the sample counter to Observables
try
{
double fs = static_cast<double>(configuration_->property("GNSS-SDR.internal_fs_sps", 0));
@ -267,7 +272,6 @@ void GNSSFlowgraph::connect()
return;
}
// Signal conditioner (selected_signal_source) >> channels (i) (dependent of their associated SignalSource_ID)
int selected_signal_conditioner_ID;
for (unsigned int i = 0; i < channels_count_; i++)
@ -301,26 +305,46 @@ void GNSSFlowgraph::connect()
top_block_->disconnect_all();
return;
}
}
std::string gnss_signal = channels_.at(i)->get_signal().get_signal_str(); // use channel's implicit signal!
channels_.at(i)->set_signal(search_next_signal(gnss_signal, false));
if (channels_state_[i] == 1)
// Put channels fixed to a given satellite at the beginning of the vector, then the rest
std::vector<unsigned int> vector_of_channels;
for (unsigned int i = 0; i < channels_count_; i++)
{
unsigned int sat = configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".satellite", 0);
if (sat == 0)
{
channels_.at(i)->start_acquisition();
available_GNSS_signals_.pop_front();
LOG(INFO) << "Channel " << i << " assigned to " << channels_.at(i)->get_signal();
LOG(INFO) << "Channel " << i << " connected to observables and ready for acquisition";
vector_of_channels.push_back(i);
}
else
{
LOG(INFO) << "Channel " << i << " connected to observables in standby mode";
auto it = vector_of_channels.begin();
it = vector_of_channels.insert(it, i);
}
}
/*
* Connect the observables output of each channel to the PVT block
*/
// Assign satellites to channels in the initialization
for (unsigned int& i : vector_of_channels)
{
std::string gnss_signal = channels_.at(i)->get_signal().get_signal_str(); // use channel's implicit signal
unsigned int sat = configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".satellite", 0);
if (sat == 0)
{
channels_.at(i)->set_signal(search_next_signal(gnss_signal, true));
}
else
{
std::string gnss_system;
if ((gnss_signal.compare("1C") == 0) or (gnss_signal.compare("2S") == 0) or (gnss_signal.compare("L5") == 0)) gnss_system = "GPS";
if ((gnss_signal.compare("1B") == 0) or (gnss_signal.compare("5X") == 0)) gnss_system = "Galileo";
if ((gnss_signal.compare("1G") == 0) or (gnss_signal.compare("2G") == 0)) gnss_system = "Glonass";
Gnss_Signal signal_value = Gnss_Signal(Gnss_Satellite(gnss_system, sat), gnss_signal);
available_GNSS_signals_.remove(signal_value);
channels_.at(i)->set_signal(signal_value);
}
}
// Connect the observables output of each channel to the PVT block
try
{
for (unsigned int i = 0; i < channels_count_; i++)
@ -337,12 +361,204 @@ void GNSSFlowgraph::connect()
return;
}
// Activate acquisition in enabled channels
for (unsigned int i = 0; i < channels_count_; i++)
{
LOG(INFO) << "Channel " << i << " assigned to " << channels_.at(i)->get_signal();
if (channels_state_[i] == 1)
{
channels_.at(i)->start_acquisition();
LOG(INFO) << "Channel " << i << " connected to observables and ready for acquisition";
}
else
{
LOG(INFO) << "Channel " << i << " connected to observables in standby mode";
}
}
connected_ = true;
LOG(INFO) << "Flowgraph connected";
top_block_->dump();
}
void GNSSFlowgraph::disconnect()
{
LOG(INFO) << "Disconnecting flowgraph";
if (!connected_)
{
LOG(INFO) << "flowgraph was not connected";
return;
}
// Signal Source (i) > Signal conditioner (i) >
int RF_Channels = 0;
int signal_conditioner_ID = 0;
for (int i = 0; i < sources_count_; i++)
{
try
{
// TODO: Remove this array implementation and create generic multistream connector
// (if a signal source has more than 1 stream, then connect it to the multistream signal conditioner)
if (sig_source_.at(i)->implementation().compare("Raw_Array_Signal_Source") == 0)
{
//Multichannel Array
for (int j = 0; j < GNSS_SDR_ARRAY_SIGNAL_CONDITIONER_CHANNELS; j++)
{
top_block_->disconnect(sig_source_.at(i)->get_right_block(), j, sig_conditioner_.at(i)->get_left_block(), j);
}
}
else
{
// TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
// Include GetRFChannels in the interface to avoid read config parameters here
// read the number of RF channels for each front-end
RF_Channels = configuration_->property(sig_source_.at(i)->role() + ".RF_channels", 1);
for (int j = 0; j < RF_Channels; j++)
{
if (sig_source_.at(i)->get_right_block()->output_signature()->max_streams() > 1)
{
top_block_->disconnect(sig_source_.at(i)->get_right_block(), j, sig_conditioner_.at(signal_conditioner_ID)->get_left_block(), 0);
}
else
{
if (j == 0)
{
// RF_channel 0 backward compatibility with single channel sources
top_block_->disconnect(sig_source_.at(i)->get_right_block(), 0, sig_conditioner_.at(signal_conditioner_ID)->get_left_block(), 0);
}
else
{
// Multiple channel sources using multiple output blocks of single channel (requires RF_channel selector in call)
top_block_->disconnect(sig_source_.at(i)->get_right_block(j), 0, sig_conditioner_.at(signal_conditioner_ID)->get_left_block(), 0);
}
}
signal_conditioner_ID++;
}
}
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect signal source " << i << " to signal conditioner " << i << ": " << e.what();
}
}
try
{
top_block_->disconnect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter, 0);
top_block_->disconnect(ch_out_sample_counter, 0, observables_->get_left_block(), channels_count_); //extra port for the sample counter pulse
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect sample counter: " << e.what();
}
// Signal conditioner (selected_signal_source) >> channels (i) (dependent of their associated SignalSource_ID)
int selected_signal_conditioner_ID;
for (unsigned int i = 0; i < channels_count_; i++)
{
selected_signal_conditioner_ID = configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".RF_channel_ID", 0);
try
{
top_block_->disconnect(sig_conditioner_.at(selected_signal_conditioner_ID)->get_right_block(), 0,
channels_.at(i)->get_left_block(), 0);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect signal conditioner " << selected_signal_conditioner_ID << " to channel " << i << ": " << e.what();
}
// Signal Source > Signal conditioner >> Channels >> Observables
try
{
top_block_->disconnect(channels_.at(i)->get_right_block(), 0,
observables_->get_left_block(), i);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect channel " << i << " to observables: " << e.what();
}
}
try
{
for (unsigned int i = 0; i < channels_count_; i++)
{
top_block_->disconnect(observables_->get_right_block(), i, pvt_->get_left_block(), i);
top_block_->msg_disconnect(channels_.at(i)->get_right_block(), pmt::mp("telemetry"), pvt_->get_left_block(), pmt::mp("telemetry"));
}
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect observables to PVT: " << e.what();
}
for (int i = 0; i < sources_count_; i++)
{
try
{
sig_source_.at(i)->disconnect(top_block_);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect signal source block " << i << " internally: " << e.what();
}
}
// Signal Source > Signal conditioner >
for (unsigned int i = 0; i < sig_conditioner_.size(); i++)
{
try
{
sig_conditioner_.at(i)->disconnect(top_block_);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect signal conditioner block " << i << " internally: " << e.what();
}
}
for (unsigned int i = 0; i < channels_count_; i++)
{
try
{
channels_.at(i)->disconnect(top_block_);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect channel " << i << " internally: " << e.what();
}
}
try
{
observables_->disconnect(top_block_);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect observables block internally: " << e.what();
}
// Signal Source > Signal conditioner >> Channels >> Observables > PVT
try
{
pvt_->disconnect(top_block_);
}
catch (const std::exception& e)
{
LOG(INFO) << "Can't disconnect PVT block internally: " << e.what();
}
DLOG(INFO) << "blocks disconnected internally";
connected_ = false;
LOG(INFO) << "Flowgraph disconnected";
}
void GNSSFlowgraph::wait()
{
if (!running_)
@ -366,7 +582,7 @@ bool GNSSFlowgraph::send_telemetry_msg(pmt::pmt_t msg)
/*
* Applies an action to the flowgraph
* Applies an action to the flow graph
*
* \param[in] who Who generated the action
* \param[in] what What is the action 0: acquisition failed
@ -374,50 +590,64 @@ bool GNSSFlowgraph::send_telemetry_msg(pmt::pmt_t msg)
void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
{
DLOG(INFO) << "Received " << what << " from " << who << ". Number of applied actions = " << applied_actions_;
unsigned int sat = configuration_->property("Channel" + boost::lexical_cast<std::string>(who) + ".satellite", 0);
switch (what)
{
case 0:
DLOG(INFO) << "Channel " << who << " ACQ FAILED satellite " << channels_.at(who)->get_signal().get_satellite() << ", Signal " << channels_.at(who)->get_signal().get_signal_str();
available_GNSS_signals_.push_back(channels_.at(who)->get_signal());
channels_.at(who)->set_signal(search_next_signal(channels_.at(who)->get_signal().get_signal_str(), true));
DLOG(INFO) << "Channel " << who << " Starting acquisition " << channels_.at(who)->get_signal().get_satellite() << ", Signal " << channels_.at(who)->get_signal().get_signal_str();
channels_.at(who)->start_acquisition();
DLOG(INFO) << "Channel " << who << " ACQ FAILED satellite " << channels_[who]->get_signal().get_satellite() << ", Signal " << channels_[who]->get_signal().get_signal_str();
if (sat == 0)
{
std::lock_guard<std::mutex> lock(signal_list_mutex);
available_GNSS_signals_.push_back(channels_[who]->get_signal());
channels_[who]->set_signal(search_next_signal(channels_[who]->get_signal().get_signal_str(), true));
}
DLOG(INFO) << "Channel " << who << " Starting acquisition " << channels_[who]->get_signal().get_satellite() << ", Signal " << channels_[who]->get_signal().get_signal_str();
channels_[who]->start_acquisition();
break;
case 1:
LOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite " << channels_.at(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite " << channels_[who]->get_signal().get_satellite();
channels_state_[who] = 2;
acq_channels_count_--;
for (unsigned int i = 0; i < channels_count_; i++)
{
unsigned int sat_ = configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".satellite", 0);
if (!available_GNSS_signals_.empty() && (acq_channels_count_ < max_acq_channels_) && (channels_state_[i] == 0))
{
channels_state_[i] = 1;
channels_.at(i)->set_signal(search_next_signal(channels_.at(i)->get_signal().get_signal_str(), true));
if (sat_ == 0)
{
std::lock_guard<std::mutex> lock(signal_list_mutex);
channels_[i]->set_signal(search_next_signal(channels_[i]->get_signal().get_signal_str(), true));
}
acq_channels_count_++;
DLOG(INFO) << "Channel " << i << " Starting acquisition " << channels_.at(i)->get_signal().get_satellite() << ", Signal " << channels_.at(i)->get_signal().get_signal_str();
channels_.at(i)->start_acquisition();
DLOG(INFO) << "Channel " << i << " Starting acquisition " << channels_[i]->get_signal().get_satellite() << ", Signal " << channels_[i]->get_signal().get_signal_str();
channels_[i]->start_acquisition();
}
DLOG(INFO) << "Channel " << i << " in state " << channels_state_[i];
}
break;
case 2:
LOG(INFO) << "Channel " << who << " TRK FAILED satellite " << channels_.at(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " TRK FAILED satellite " << channels_[who]->get_signal().get_satellite();
DLOG(INFO) << "Number of channels in acquisition = " << acq_channels_count_;
if (acq_channels_count_ < max_acq_channels_)
{
channels_state_[who] = 1;
acq_channels_count_++;
LOG(INFO) << "Channel " << who << " Starting acquisition " << channels_.at(who)->get_signal().get_satellite() << ", Signal " << channels_.at(who)->get_signal().get_signal_str();
channels_.at(who)->start_acquisition();
LOG(INFO) << "Channel " << who << " Starting acquisition " << channels_[who]->get_signal().get_satellite() << ", Signal " << channels_[who]->get_signal().get_signal_str();
channels_[who]->start_acquisition();
}
else
{
channels_state_[who] = 0;
LOG(INFO) << "Channel " << who << " Idle state";
available_GNSS_signals_.push_back(channels_.at(who)->get_signal());
if (sat == 0)
{
std::lock_guard<std::mutex> lock(signal_list_mutex);
available_GNSS_signals_.push_back(channels_[who]->get_signal());
}
}
break;
@ -436,7 +666,6 @@ void GNSSFlowgraph::set_configuration(std::shared_ptr<ConfigurationInterface> co
LOG(WARNING) << "Unable to update configuration while flowgraph running";
return;
}
if (connected_)
{
LOG(WARNING) << "Unable to update configuration while flowgraph connected";
@ -464,9 +693,9 @@ void GNSSFlowgraph::init()
{
std::cout << "Creating source " << i << std::endl;
sig_source_.push_back(block_factory_->GetSignalSource(configuration_, queue_, i));
//TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
//Include GetRFChannels in the interface to avoid read config parameters here
//read the number of RF channels for each front-end
// TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
// Include GetRFChannels in the interface to avoid read config parameters here
// read the number of RF channels for each front-end
RF_Channels = configuration_->property(sig_source_.at(i)->role() + ".RF_channels", 1);
std::cout << "RF Channels " << RF_Channels << std::endl;
for (int j = 0; j < RF_Channels; j++)
@ -478,11 +707,11 @@ void GNSSFlowgraph::init()
}
else
{
//backwards compatibility for old config files
// backwards compatibility for old config files
sig_source_.push_back(block_factory_->GetSignalSource(configuration_, queue_, -1));
//TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
//Include GetRFChannels in the interface to avoid read config parameters here
//read the number of RF channels for each front-end
// TODO: Create a class interface for SignalSources, derived from GNSSBlockInterface.
// Include GetRFChannels in the interface to avoid read config parameters here
// read the number of RF channels for each front-end
RF_Channels = configuration_->property(sig_source_.at(0)->role() + ".RF_channels", 0);
if (RF_Channels != 0)
{
@ -494,7 +723,7 @@ void GNSSFlowgraph::init()
}
else
{
//old config file, single signal source and single channel, not specified
// old config file, single signal source and single channel, not specified
sig_conditioner_.push_back(block_factory_->GetSignalConditioner(configuration_, -1));
}
}
@ -521,7 +750,6 @@ void GNSSFlowgraph::init()
std::shared_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> channels = block_factory_->GetChannels(configuration_, queue_);
//todo:check smart pointer coherence...
channels_count_ = channels->size();
for (unsigned int i = 0; i < channels_count_; i++)
{
@ -541,34 +769,19 @@ void GNSSFlowgraph::init()
void GNSSFlowgraph::set_signals_list()
{
/*
* Sets a sequential list of GNSS satellites
*/
// Set a sequential list of GNSS satellites
std::set<unsigned int>::const_iterator available_gnss_prn_iter;
/*
* \TODO Describe GNSS satellites more nicely, with RINEX notation
* See http://igscb.jpl.nasa.gov/igscb/data/format/rinex301.pdf (page 5)
*/
/*
* Read GNSS-SDR default GNSS system and signal
*/
// Read GNSS systems and signals
unsigned int total_channels = configuration_->property("Channels_1C.count", 0) +
configuration_->property("Channels_2S.count", 0) +
configuration_->property("Channels_1B.count", 0) +
configuration_->property("Channels_5X.count", 0) +
configuration_->property("Channels_1G.count", 0) +
configuration_->property("Channels_2S.count", 0) +
configuration_->property("Channels_2G.count", 0) +
configuration_->property("Channels_5X.count", 0) +
configuration_->property("Channels_L5.count", 0);
/*
* Loop to create the list of GNSS Signals
* To add signals from other systems, add another loop 'for'
*/
// Create the lists of GNSS satellites
std::set<unsigned int> available_gps_prn = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28,
29, 30, 31, 32};
@ -690,6 +903,7 @@ void GNSSFlowgraph::set_signals_list()
std::string("L5")));
}
}
if (configuration_->property("Channels_SBAS.count", 0) > 0)
{
/*
@ -705,7 +919,6 @@ void GNSSFlowgraph::set_signals_list()
}
}
if (configuration_->property("Channels_1B.count", 0) > 0)
{
/*
@ -765,39 +978,12 @@ void GNSSFlowgraph::set_signals_list()
std::string("2G")));
}
}
/*
* Ordering the list of signals from configuration file
*/
std::list<Gnss_Signal>::iterator gnss_it = available_GNSS_signals_.begin();
// Pre-assignation if not defined at ChannelX.signal=1C ...? In what order?
for (unsigned int i = 0; i < total_channels; i++)
{
std::string gnss_signal = (configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".signal", std::string("1C")));
std::string gnss_system;
if ((gnss_signal.compare("1C") == 0) or (gnss_signal.compare("2S") == 0) or (gnss_signal.compare("L5") == 0)) gnss_system = "GPS";
if ((gnss_signal.compare("1B") == 0) or (gnss_signal.compare("5X") == 0)) gnss_system = "Galileo";
if ((gnss_signal.compare("1G") == 0) or (gnss_signal.compare("2G") == 0)) gnss_system = "Glonass";
unsigned int sat = configuration_->property("Channel" + boost::lexical_cast<std::string>(i) + ".satellite", 0);
LOG(INFO) << "Channel " << i << " system " << gnss_system << ", signal " << gnss_signal << ", sat " << sat;
if (sat == 0) // 0 = not PRN in configuration file
{
gnss_it++;
}
else
{
Gnss_Signal signal_value = Gnss_Signal(Gnss_Satellite(gnss_system, sat), gnss_signal);
available_GNSS_signals_.remove(signal_value);
gnss_it = available_GNSS_signals_.insert(gnss_it, signal_value);
}
}
}
void GNSSFlowgraph::set_channels_state()
{
max_acq_channels_ = (configuration_->property("Channels.in_acquisition", channels_count_));
max_acq_channels_ = configuration_->property("Channels.in_acquisition", channels_count_);
if (max_acq_channels_ > channels_count_)
{
max_acq_channels_ = channels_count_;

View File

@ -1,12 +1,12 @@
/*!
* \file gnss_flowgraph.h
* \brief Interface of a GNSS receiver flowgraph.
* \brief Interface of a GNSS receiver flow graph.
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Luis Esteve, 2011. luis(at)epsilon-formacion.com
* Carles Fernandez-Prades, 2014. cfernandez(at)cttc.es
*
* It contains a signal source,
* a signal conditioner, a set of channels, a pvt and an output filter.
* a signal conditioner, a set of channels, an observables block and a pvt.
*
* -------------------------------------------------------------------------
*
@ -43,6 +43,7 @@
#include <gnuradio/msg_queue.h>
#include <list>
#include <memory>
#include <mutex>
#include <queue>
#include <string>
#include <vector>
@ -53,7 +54,7 @@ class ChannelInterface;
class ConfigurationInterface;
class GNSSBlockFactory;
/*! \brief This class represents a GNSS flowgraph.
/*! \brief This class represents a GNSS flow graph.
*
* It contains a signal source,
* a signal conditioner, a set of channels, a PVT and an output filter.
@ -62,35 +63,37 @@ class GNSSFlowgraph
{
public:
/*!
* \brief Constructor that initializes the receiver flowgraph
* \brief Constructor that initializes the receiver flow graph
*/
GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, gr::msg_queue::sptr queue);
/*!
* \brief Virtual destructor
* \brief Destructor
*/
virtual ~GNSSFlowgraph();
~GNSSFlowgraph();
//! \brief Start the flowgraph
//! \brief Start the flow graph
void start();
//! \brief Stop the flowgraph
//! \brief Stop the flow graph
void stop();
/*!
* \brief Connects the defined blocks in the flowgraph
* \brief Connects the defined blocks in the flow graph
*
* Signal Source > Signal conditioner > Channels >> Observables >> PVT > Output filter
*/
void connect();
void disconnect();
void wait();
/*!
* \brief Applies an action to the flowgraph
* \brief Applies an action to the flow graph
*
* \param[in] who Who generated the action
* \param[in] what What is the action 0: acquisition failed
* \param[in] what What is the action. 0: acquisition failed; 1: acquisition success; 2: tracking lost
*/
void apply_action(unsigned int who, unsigned int what);
@ -100,14 +103,17 @@ public:
{
return applied_actions_;
}
bool connected()
{
return connected_;
}
bool running()
{
return running_;
}
/*!
* \brief Sends a GNURadio asynchronous message from telemetry to PVT
*
@ -144,6 +150,7 @@ private:
gr::msg_queue::sptr queue_;
std::list<Gnss_Signal> available_GNSS_signals_;
std::vector<unsigned int> channels_state_;
std::mutex signal_list_mutex;
};
#endif /*GNSS_SDR_GNSS_FLOWGRAPH_H_*/

View File

@ -277,8 +277,8 @@ int StaticPositionSystemTest::configure_receiver()
const float dll_bw_narrow_hz = 2.0;
const int extend_correlation_ms = 1;
const int display_rate_ms = 1000;
const int output_rate_ms = 1000;
const int display_rate_ms = 500;
const int output_rate_ms = 500;
config->set_property("GNSS-SDR.internal_fs_sps", std::to_string(sampling_rate_internal));
@ -361,12 +361,11 @@ int StaticPositionSystemTest::configure_receiver()
config->set_property("Tracking_1C.pll_bw_narrow_hz", std::to_string(pll_bw_narrow_hz));
config->set_property("Tracking_1C.dll_bw_narrow_hz", std::to_string(dll_bw_narrow_hz));
config->set_property("Tracking_1C.extend_correlation_ms", std::to_string(extend_correlation_ms));
config->set_property("Tracking_1C.extend_correlation_symbols", std::to_string(extend_correlation_ms));
// Set Telemetry
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
config->set_property("TelemetryDecoder_1C.dump", "false");
config->set_property("TelemetryDecoder_1C.decimation_factor", std::to_string(decimation_factor));
// Set Observables
config->set_property("Observables.implementation", "Hybrid_Observables");
@ -454,6 +453,7 @@ int StaticPositionSystemTest::run_receiver()
void StaticPositionSystemTest::check_results()
{
std::fstream myfile(StaticPositionSystemTest::generated_kml_file, std::ios_base::in);
ASSERT_TRUE(myfile.is_open()) << "No valid kml file could be opened";
std::string line;
std::vector<double> pos_e;
@ -466,6 +466,7 @@ void StaticPositionSystemTest::check_results()
while (is_header)
{
std::getline(myfile, line);
ASSERT_FALSE(myfile.eof()) << "No valid kml file found.";
std::size_t found = line.find("<coordinates>");
if (found != std::string::npos) is_header = false;
}
@ -474,7 +475,11 @@ void StaticPositionSystemTest::check_results()
//read data
while (is_data)
{
std::getline(myfile, line);
if (!std::getline(myfile, line))
{
is_data = false;
break;
}
std::size_t found = line.find("</coordinates>");
if (found != std::string::npos)
is_data = false;
@ -504,6 +509,7 @@ void StaticPositionSystemTest::check_results()
}
}
myfile.close();
ASSERT_FALSE(pos_e.size() == 0) << "KML file is empty";
double sigma_E_2_precision = std::pow(compute_stdev_precision(pos_e), 2.0);
double sigma_N_2_precision = std::pow(compute_stdev_precision(pos_n), 2.0);

View File

@ -54,7 +54,8 @@
#include "test_flags.h"
DEFINE_bool(plot_gps_l1_tracking_test, false, "Plots results of GpsL1CADllPllTrackingTest with gnuplot");
DEFINE_double(CN0_dBHz, std::numeric_limits<double>::infinity(), "Enable noise generator and set the CN0 [dB-Hz]");
DEFINE_int32(extend_correlation_symbols, 1, "Set the tracking coherent correlation to N symbols (up to 20 for GPS L1 C/A)");
// ######## GNURADIO BLOCK MESSAGE RECEVER #########
class GpsL1CADllPllTrackingTest_msg_rx;
@ -121,7 +122,7 @@ public:
std::string p3;
std::string p4;
std::string p5;
std::string p6;
std::string implementation = "GPS_L1_CA_DLL_PLL_Tracking"; //"GPS_L1_CA_DLL_PLL_C_Aid_Tracking";
const int baseband_sampling_freq = FLAGS_fs_gen_sps;
@ -183,6 +184,7 @@ int GpsL1CADllPllTrackingTest::configure_generator()
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]
p6 = std::string("-CN0_dBHz=") + std::to_string(FLAGS_CN0_dBHz); // Signal generator CN0
return 0;
}
@ -191,7 +193,7 @@ int GpsL1CADllPllTrackingTest::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};
char* const parmList[] = {&generator_binary[0], &generator_binary[0], &p1[0], &p2[0], &p3[0], &p4[0], &p5[0],&p6[0], NULL};
int pid;
if ((pid = fork()) == -1)
@ -223,12 +225,12 @@ void GpsL1CADllPllTrackingTest::configure_receiver()
config->set_property("Tracking_1C.implementation", implementation);
config->set_property("Tracking_1C.item_type", "gr_complex");
config->set_property("Tracking_1C.pll_bw_hz", "20.0");
config->set_property("Tracking_1C.dll_bw_hz", "2.0");
config->set_property("Tracking_1C.dll_bw_hz", "1.5");
config->set_property("Tracking_1C.early_late_space_chips", "0.5");
config->set_property("Tracking_1C.pll_bw_narrow_hz", "20.0");
config->set_property("Tracking_1C.dll_bw_narrow_hz", "2.0");
config->set_property("Tracking_1C.extend_correlation_symbols", std::to_string(FLAGS_extend_correlation_symbols));
config->set_property("Tracking_1C.pll_bw_narrow_hz", "2.0");
config->set_property("Tracking_1C.dll_bw_narrow_hz", "1.0");
config->set_property("Tracking_1C.early_late_space_narrow_chips", "0.5");
config->set_property("Tracking_1C.extend_correlation_ms", "1");
config->set_property("Tracking_1C.dump", "true");
config->set_property("Tracking_1C.dump_filename", "./tracking_ch_");
}
@ -471,6 +473,7 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
std::vector<double> late;
std::vector<double> promptI;
std::vector<double> promptQ;
std::vector<double> CN0_dBHz;
epoch_counter = 0;
while (trk_dump.read_binary_obs())
@ -488,6 +491,7 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
late.push_back(trk_dump.abs_L);
promptI.push_back(trk_dump.prompt_I);
promptQ.push_back(trk_dump.prompt_Q);
CN0_dBHz.push_back(trk_dump.CN0_SNV_dB_Hz);
}
// Align initial measurements and cut the tracking pull-in transitory
@ -555,6 +559,17 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
g2.savetops("Constellation");
g2.savetopdf("Constellation", 18);
g2.showonscreen(); // window output
Gnuplot g3("linespoints");
g3.set_title("GPS L1 C/A tracking CN0 output (satellite PRN #" + std::to_string(FLAGS_test_satellite_PRN) + ")");
g3.set_grid();
g3.set_xlabel("Time [s]");
g3.set_ylabel("Reported CN0 [dB-Hz]");
g3.cmd("set key box opaque");
g3.plot_xy(timevec, CN0_dBHz, "Prompt", decimate);
g3.savetops("CN0_output");
g3.savetopdf("CN0_output", 18);
g3.showonscreen(); // window output
}
catch (const GnuplotException& ge)
{