implemented the acquisition block, not working

This commit is contained in:
Sergi Segura 2018-07-06 14:42:13 +02:00
parent ea55861202
commit bf8ffe63cf
21 changed files with 1508 additions and 28 deletions

View File

@ -38,7 +38,7 @@ Resampler.sample_freq_out=25000000
Resampler.item_type=gr_complex
;######### CHANNELS GLOBAL CONFIG ############
Channels_B1.count=8
Channels_B1.count=1
Channels.in_acquisition=1
Channel.signal=B1
@ -51,12 +51,12 @@ Acquisition_B1.threshold=0.008
;Acquisition_B1.pfa=0.000001
Acquisition_B1.doppler_max=10000
Acquisition_B1.doppler_step=250
Acquisition_B1.dump=false
Acquisition_B1.dump=true
Acquisition_B1.dump_filename=./acq_dump.dat
Acquisition_B1.blocking=false;
;######### TRACKING GLOBAL CONFIG ############
Tracking_B1.implementation=Pass_Through
Tracking_B1.implementation=BEIDOU_B1I_DLL_PLL_Tracking
Tracking_B1.item_type=gr_complex
Tracking_B1.pll_bw_hz=40.0;
Tracking_B1.dll_bw_hz=4.0;
@ -66,18 +66,18 @@ Tracking_B1.dump_filename=./epl_tracking_ch_
;######### TELEMETRY DECODER GPS CONFIG ############
TelemetryDecoder_B1.implementation=Pass_Through
TelemetryDecoder_B1.implementation=BEIDOU_B1I_Telemetry_Decoder
TelemetryDecoder_B1.dump=false
;######### OBSERVABLES CONFIG ############
Observables.implementation=Pass_Through
Observables.implementation=Hybrid_Observables
Observables.dump=true
Observables.dump_filename=./observables.dat
;######### PVT CONFIG ############
PVT.implementation=Pass_Through
PVT.implementation=RTKLIB_PVT
PVT.positioning_mode=PPP_Static ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic
PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX
PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad

View File

@ -16,7 +16,7 @@ ControlThread.wait_for_flowgraph=false
;######### SIGNAL_SOURCE CONFIG ############
SignalSource.implementation=File_Signal_Source
SignalSource.filename=/archive/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE
SignalSource.filename=/home/sergi/gnss/gnss-sdr/data/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE
SignalSource.item_type=ishort
SignalSource.sampling_frequency=4000000
SignalSource.samples=0
@ -51,7 +51,7 @@ Acquisition_1C.threshold=0.008
;Acquisition_1C.pfa=0.000001
Acquisition_1C.doppler_max=10000
Acquisition_1C.doppler_step=250
Acquisition_1C.dump=false
Acquisition_1C.dump=true
Acquisition_1C.dump_filename=./acq_dump.dat
Acquisition_1C.blocking=false;

View File

@ -624,7 +624,6 @@ int pcps_acquisition::general_work(int noutput_items __attribute__((unused)),
* 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)
{

View File

@ -46,23 +46,22 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
unsigned int lcv, lcv2;
unsigned int delay;
signed int prn_idx;
std::cout << "MY SATELLITE " << _prn << "!" << std::endl;
/* G2 Delays as defined in GPS-ISD-200D */
const signed int delays[51] = {5 /*PRN1*/, 6, 7, 8, 17, 18, 139, 140, 141, 251, 252, 254, 255, 256, 257, 258, 469, 470, 471, 472,
473, 474, 509, 512, 513, 514, 515, 516, 859, 860, 861, 862 /*PRN32*/,
145 /*PRN120*/, 175, 52, 21, 237, 235, 886, 657, 634, 762,
355, 1012, 176, 603, 130, 359, 595, 68, 386 /*PRN138*/};
const signed int delays[33] = {712 /*PRN1*/, 1581, 1414, 1550, 581, 771, 1311, 1043, 1549, 359, 710, 1579, 1548, 1103, 579, 769, 358, 709, 1411, 1547,
1102, 578, 357, 1577, 1410, 1546, 1101, 707, 1576, 1409, 1545, 354 /*PRN32*/,
705};
const signed int phase1[37] = {1, 1, 1, 1, 1, 1, 1, 1, 2, 3, 3, 3, 3, 3, 3, 3, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 8, 8, 8, 9, 9, 10};
const signed int phase2[37] = {3, 4, 5, 6, 8, 9, 10, 11, 7, 4, 5, 6, 8, 9, 10, 11, 5, 6, 8, 9, 10, 11, 6, 8, 9, 10, 11, 8, 9, 10, 11, 9, 10, 11, 10, 11, 11};
// compute delay array index for given PRN number
if (120 <= _prn && _prn <= 138)
{
prn_idx = _prn - 88; // SBAS PRNs are at array indices 31 to 50 (offset: -120+33-1 =-88)
}
else
{
// if (120 <= _prn && _prn <= 138)
// {
// prn_idx = _prn - 88; // SBAS PRNs are at array indices 31 to 50 (offset: -120+33-1 =-88)
// }
// else
// {
prn_idx = _prn - 1;
}
// }
/* A simple error check */
if ((prn_idx < 0) || (prn_idx > 51))
@ -78,7 +77,7 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
for (lcv = 0; lcv < _code_length; lcv++)
{
G1[lcv] = G1_register[0];
G2[lcv] = G2_register[phase1[prn_idx]] ^ G2_register[phase2[prn_idx]];
G2[lcv] = G2_register[0];//G2_register[phase1[prn_idx]] ^ G2_register[phase2[prn_idx]];
feedback1 = (G1_register[0] + G1_register[1] + G1_register[2] + G1_register[3] + G1_register[4] + G1_register[10]) & 0x1;
feedback2 = (G2_register[0] + G2_register[2] + G2_register[3] + G2_register[6] + G2_register[7] + G2_register[8] + G2_register[9] + G2_register[10]) & 0x1;
@ -94,7 +93,7 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
}
/* Set the delay */
delay = _code_length /*- delays[prn_idx]*/;
delay = _code_length - delays[prn_idx];
delay += _chip_shift;
delay %= _code_length;

View File

@ -34,6 +34,7 @@
#define BEIDOU_B1I_SDR_SIGNAL_PROCESSING_H_
#include <complex>
#include <iostream>
//!Generates int GPS L1 C/A code for the desired SV ID and code shift
void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shift);

View File

@ -31,7 +31,6 @@
*/
#include "gps_sdr_signal_processing.h"
auto auxCeil = [](float x) { return static_cast<int>(static_cast<long>((x) + 1)); };
void gps_l1_ca_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shift)

View File

@ -112,10 +112,12 @@ Pass_Through::Pass_Through(ConfigurationInterface* configuration, std::string ro
if (in_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one input stream";
LOG(ERROR) << in_streams_;
}
if (out_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
LOG(ERROR) << out_streams_;
}
}

View File

@ -25,7 +25,8 @@ set(TELEMETRY_DECODER_ADAPTER_SOURCES
sbas_l1_telemetry_decoder.cc
galileo_e5a_telemetry_decoder.cc
glonass_l1_ca_telemetry_decoder.cc
glonass_l2_ca_telemetry_decoder.cc
glonass_l2_ca_telemetry_decoder.cc
beidou_b1i_telemetry_decoder.cc
)
include_directories(

View File

@ -0,0 +1,112 @@
/*!
* \file gps_l1_ca_telemetry_decoder.cc
* \brief Implementation of an adapter of a GPS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \author Javier Arribas, 2011. jarribas(at)cttc.es
*
* -------------------------------------------------------------------------
*
* 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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_telemetry_decoder.h"
#include "configuration_interface.h"
#include "gps_ephemeris.h"
#include "gps_almanac.h"
#include "gps_iono.h"
#include "gps_utc_model.h"
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
using google::LogMessage;
GpsL1CaTelemetryDecoder::GpsL1CaTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams) : role_(role),
in_streams_(in_streams),
out_streams_(out_streams)
{
std::string default_dump_filename = "./navigation.dat";
DLOG(INFO) << "role " << role;
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
// make telemetry decoder object
telemetry_decoder_ = gps_l1_ca_make_telemetry_decoder_cc(satellite_, dump_); // TODO fix me
DLOG(INFO) << "telemetry_decoder(" << telemetry_decoder_->unique_id() << ")";
channel_ = 0;
if (in_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one input stream";
}
if (out_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
GpsL1CaTelemetryDecoder::~GpsL1CaTelemetryDecoder()
{
}
void GpsL1CaTelemetryDecoder::set_satellite(const Gnss_Satellite& satellite)
{
satellite_ = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
telemetry_decoder_->set_satellite(satellite_);
DLOG(INFO) << "TELEMETRY DECODER: satellite set to " << satellite_;
}
void GpsL1CaTelemetryDecoder::connect(gr::top_block_sptr top_block)
{
if (top_block)
{ /* top_block is not null */
};
// Nothing to connect internally
DLOG(INFO) << "nothing to connect internally";
}
void GpsL1CaTelemetryDecoder::disconnect(gr::top_block_sptr top_block)
{
if (top_block)
{ /* top_block is not null */
};
// Nothing to disconnect
}
gr::basic_block_sptr GpsL1CaTelemetryDecoder::get_left_block()
{
return telemetry_decoder_;
}
gr::basic_block_sptr GpsL1CaTelemetryDecoder::get_right_block()
{
return telemetry_decoder_;
}

View File

@ -0,0 +1,95 @@
/*!
* \file gps_l1_ca_telemetry_decoder.h
* \brief Interface of an adapter of a GPS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \author Javier Arribas, 2011. jarribas(at)cttc.es
*
* -------------------------------------------------------------------------
*
* 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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L1_CA_TELEMETRY_DECODER_H_
#define GNSS_SDR_GPS_L1_CA_TELEMETRY_DECODER_H_
#include "gps_l1_ca_telemetry_decoder_cc.h"
#include "telemetry_decoder_interface.h"
#include <string>
class ConfigurationInterface;
/*!
* \brief This class implements a NAV data decoder for GPS L1 C/A
*/
class GpsL1CaTelemetryDecoder : public TelemetryDecoderInterface
{
public:
GpsL1CaTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GpsL1CaTelemetryDecoder();
inline std::string role() override
{
return role_;
}
//! Returns "GPS_L1_CA_Telemetry_Decoder"
inline std::string implementation() override
{
return "BEIDOU_B1I_Telemetry_Decoder";
}
void connect(gr::top_block_sptr top_block) override;
void disconnect(gr::top_block_sptr top_block) override;
gr::basic_block_sptr get_left_block() override;
gr::basic_block_sptr get_right_block() override;
void set_satellite(const Gnss_Satellite& satellite) override;
inline void set_channel(int channel) override { telemetry_decoder_->set_channel(channel); }
inline void reset() override
{
return;
}
inline size_t item_size() override
{
return 0;
}
private:
gps_l1_ca_telemetry_decoder_cc_sptr telemetry_decoder_;
Gnss_Satellite satellite_;
int channel_;
bool dump_;
std::string dump_filename_;
std::string role_;
unsigned int in_streams_;
unsigned int out_streams_;
};
#endif

View File

@ -25,6 +25,7 @@ set(TELEMETRY_DECODER_GR_BLOCKS_SOURCES
galileo_e5a_telemetry_decoder_cc.cc
glonass_l1_ca_telemetry_decoder_cc.cc
glonass_l2_ca_telemetry_decoder_cc.cc
beidou_b1i_telemetry_decoder_cc.cc
)
include_directories(

View File

@ -0,0 +1,439 @@
/*!
* \file gps_l1_ca_telemetry_decoder_cc.cc
* \brief Implementation of a NAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \author Javier Arribas, 2011. jarribas(at)cttc.es
*
* -------------------------------------------------------------------------
*
* 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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_telemetry_decoder_cc.h"
#include "control_message_factory.h"
#include <boost/lexical_cast.hpp>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#ifndef _rotl
#define _rotl(X, N) ((X << N) ^ (X >> (32 - N))) // Used in the parity check algorithm
#endif
using google::LogMessage;
gps_l1_ca_telemetry_decoder_cc_sptr
gps_l1_ca_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump)
{
return gps_l1_ca_telemetry_decoder_cc_sptr(new gps_l1_ca_telemetry_decoder_cc(satellite, dump));
}
gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
const Gnss_Satellite &satellite,
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)))
{
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
// set the preamble
unsigned short int preambles_bits[GPS_CA_PREAMBLE_LENGTH_BITS] = GPS_PREAMBLE;
// preamble bits to sampled 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++)
{
for (unsigned int j = 0; j < GPS_CA_TELEMETRY_SYMBOLS_PER_BIT; j++)
{
if (preambles_bits[i] == 1)
{
d_preambles_symbols[n] = 1;
}
else
{
d_preambles_symbols[n] = -1;
}
n++;
}
}
d_stat = 0;
d_symbol_accumulator = 0;
d_symbol_accumulator_counter = 0;
d_frame_bit_index = 0;
d_flag_frame_sync = false;
d_GPS_frame_4bytes = 0;
d_prev_GPS_frame_4bytes = 0;
d_flag_parity = false;
d_TOW_at_Preamble_ms = 0;
flag_TOW_set = false;
d_flag_preamble = false;
d_flag_new_tow_available = false;
d_word_number = 0;
d_channel = 0;
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()
{
volk_gnsssdr_free(d_preambles_symbols);
if (d_dump_file.is_open() == true)
{
try
{
d_dump_file.close();
}
catch (const std::exception &ex)
{
LOG(WARNING) << "Exception in destructor closing the dump file " << ex.what();
}
}
}
bool gps_l1_ca_telemetry_decoder_cc::gps_word_parityCheck(unsigned int gpsword)
{
unsigned int d1, d2, d3, d4, d5, d6, d7, t, parity;
/* XOR as many bits in parallel as possible. The magic constants pick
up bits which are to be XOR'ed together to implement the GPS parity
check algorithm described in IS-GPS-200E. This avoids lengthy shift-
and-xor loops. */
d1 = gpsword & 0xFBFFBF00;
d2 = _rotl(gpsword, 1) & 0x07FFBF01;
d3 = _rotl(gpsword, 2) & 0xFC0F8100;
d4 = _rotl(gpsword, 3) & 0xF81FFE02;
d5 = _rotl(gpsword, 4) & 0xFC00000E;
d6 = _rotl(gpsword, 5) & 0x07F00001;
d7 = _rotl(gpsword, 6) & 0x00003000;
t = d1 ^ d2 ^ d3 ^ d4 ^ d5 ^ d6 ^ d7;
// Now XOR the 5 6-bit fields together to produce the 6-bit final result.
parity = t ^ _rotl(t, 6) ^ _rotl(t, 12) ^ _rotl(t, 18) ^ _rotl(t, 24);
parity = parity & 0x3F;
if (parity == (gpsword & 0x3F))
return (true);
else
return (false);
}
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)
{
int corr_value = 0;
int preamble_diff_ms = 0;
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][0];
d_symbol_history.push_back(current_symbol); //add new symbol to the symbol queue
consume_each(1);
unsigned int required_symbols = GPS_CA_PREAMBLE_LENGTH_SYMBOLS;
d_flag_preamble = false;
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++)
{
if (d_symbol_history.at(i).Flag_valid_symbol_output == true)
{
if (d_symbol_history.at(i).Prompt_I < 0) // symbols clipping
{
corr_value -= d_preambles_symbols[i];
}
else
{
corr_value += d_preambles_symbols[i];
}
}
}
if (std::abs(corr_value) >= GPS_CA_PREAMBLE_LENGTH_SYMBOLS)
{
d_symbol_counter_corr++;
}
}
//******* frame sync ******************
if (std::abs(corr_value) == GPS_CA_PREAMBLE_LENGTH_SYMBOLS)
{
//TODO: Rewrite with state machine
if (d_stat == 0)
{
d_GPS_FSM.Event_gps_word_preamble();
//record the preamble sample stamp
d_preamble_time_samples = d_symbol_history.at(0).Tracking_sample_counter; // record the preamble sample stamp
DLOG(INFO) << "Preamble detection for SAT " << this->d_satellite << "d_symbol_history.at(0).Tracking_sample_counter=" << d_symbol_history.at(0).Tracking_sample_counter;
//sync the symbol to bits integrator
d_symbol_accumulator = 0;
d_symbol_accumulator_counter = 0;
d_frame_bit_index = 0;
d_stat = 1; // enter into frame pre-detection status
}
else if (d_stat == 1) //check 6 seconds of preamble separation
{
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)
{
d_flag_frame_sync = true;
if (corr_value < 0)
{
flag_PLL_180_deg_phase_locked = true; // PLL is locked to opposite phase!
DLOG(INFO) << " PLL in opposite phase for Sat " << this->d_satellite.get_PRN();
}
else
{
flag_PLL_180_deg_phase_locked = false;
}
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at "
<< static_cast<double>(d_preamble_time_samples) / static_cast<double>(d_symbol_history.at(0).fs) << " [s]";
}
}
}
}
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);
if (preamble_diff_ms > GPS_SUBFRAME_MS + 1)
{
DLOG(INFO) << "Lost of frame sync SAT " << this->d_satellite << " preamble_diff= " << preamble_diff_ms;
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;
}
}
}
//******* SYMBOL TO BIT *******
if (d_symbol_history.at(0).Flag_valid_symbol_output == true)
{
// extended correlation to bit period is enabled in tracking!
d_symbol_accumulator += d_symbol_history.at(0).Prompt_I; // accumulate the input value in d_symbol_accumulator
d_symbol_accumulator_counter += d_symbol_history.at(0).correlation_length_ms;
}
if (d_symbol_accumulator_counter >= 20)
{
if (d_symbol_accumulator > 0)
{ //symbol to bit
d_GPS_frame_4bytes += 1; //insert the telemetry bit in LSB
}
d_symbol_accumulator = 0;
d_symbol_accumulator_counter = 0;
//******* bits to words ******
d_frame_bit_index++;
if (d_frame_bit_index == 30)
{
d_frame_bit_index = 0;
// parity check
// Each word in wordbuff is composed of:
// Bits 0 to 29 = the GPS data word
// Bits 30 to 31 = 2 LSBs of the GPS word ahead.
// prepare the extended frame [-2 -1 0 ... 30]
if (d_prev_GPS_frame_4bytes & 0x00000001)
{
d_GPS_frame_4bytes = d_GPS_frame_4bytes | 0x40000000;
}
if (d_prev_GPS_frame_4bytes & 0x00000002)
{
d_GPS_frame_4bytes = d_GPS_frame_4bytes | 0x80000000;
}
/* Check that the 2 most recently logged words pass parity. Have to first
invert the data bits according to bit 30 of the previous word. */
if (d_GPS_frame_4bytes & 0x40000000)
{
d_GPS_frame_4bytes ^= 0x3FFFFFC0; // invert the data bits (using XOR)
}
if (gps_l1_ca_telemetry_decoder_cc::gps_word_parityCheck(d_GPS_frame_4bytes))
{
memcpy(&d_GPS_FSM.d_GPS_frame_4bytes, &d_GPS_frame_4bytes, sizeof(char) * 4);
//d_GPS_FSM.d_preamble_time_ms = d_preamble_time_seconds * 1000.0;
d_GPS_FSM.Event_gps_word_valid();
// send TLM data to PVT using asynchronous message queues
if (d_GPS_FSM.d_flag_new_subframe == true)
{
switch (d_GPS_FSM.d_subframe_ID)
{
case 3: //we have a new set of ephemeris data for the current SV
if (d_GPS_FSM.d_nav.satellite_validation() == true)
{
// get ephemeris object for this SV (mandatory)
std::shared_ptr<Gps_Ephemeris> tmp_obj = std::make_shared<Gps_Ephemeris>(d_GPS_FSM.d_nav.get_ephemeris());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
break;
case 4: // Possible IONOSPHERE and UTC model update (page 18)
if (d_GPS_FSM.d_nav.flag_iono_valid == true)
{
std::shared_ptr<Gps_Iono> tmp_obj = std::make_shared<Gps_Iono>(d_GPS_FSM.d_nav.get_iono());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_GPS_FSM.d_nav.flag_utc_model_valid == true)
{
std::shared_ptr<Gps_Utc_Model> tmp_obj = std::make_shared<Gps_Utc_Model>(d_GPS_FSM.d_nav.get_utc_model());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
break;
case 5:
// get almanac (if available)
//TODO: implement almanac reader in navigation_message
break;
default:
break;
}
d_GPS_FSM.clear_flag_new_subframe();
d_flag_new_tow_available = true;
}
d_flag_parity = true;
}
else
{
d_GPS_FSM.Event_gps_word_invalid();
d_flag_parity = false;
}
d_prev_GPS_frame_4bytes = d_GPS_frame_4bytes; // save the actual frame
d_GPS_frame_4bytes = d_GPS_frame_4bytes & 0;
}
else
{
d_GPS_frame_4bytes <<= 1; //shift 1 bit left the telemetry word
}
}
//2. Add the telemetry decoder information
if (this->d_flag_preamble == true and d_flag_new_tow_available == true)
{
d_TOW_at_current_symbol_ms = static_cast<unsigned int>(d_GPS_FSM.d_nav.d_TOW) * 1000 + GPS_L1_CA_CODE_PERIOD_MS + GPS_CA_PREAMBLE_DURATION_MS;
d_TOW_at_Preamble_ms = d_TOW_at_current_symbol_ms;
flag_TOW_set = true;
d_flag_new_tow_available = false;
}
else
{
d_TOW_at_current_symbol_ms += GPS_L1_CA_CODE_PERIOD_MS;
}
current_symbol.TOW_at_current_symbol_ms = d_TOW_at_current_symbol_ms;
current_symbol.Flag_valid_word = flag_TOW_set;
if (flag_PLL_180_deg_phase_locked == true)
{
//correct the accumulated phase for the Costas loop phase shift, if required
current_symbol.Carrier_phase_rads += GPS_PI;
}
if (d_dump == true)
{
// MULTIPLEXED FILE RECORDING - Record results to file
try
{
double tmp_double;
unsigned long int tmp_ulong_int;
tmp_double = static_cast<double>(d_TOW_at_current_symbol_ms) / 1000.0;
d_dump_file.write(reinterpret_cast<char *>(&tmp_double), sizeof(double));
tmp_ulong_int = current_symbol.Tracking_sample_counter;
d_dump_file.write(reinterpret_cast<char *>(&tmp_ulong_int), sizeof(unsigned long int));
tmp_double = static_cast<double>(d_TOW_at_Preamble_ms) * 1000.0;
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();
}
}
//3. Make the output (copy the object contents to the GNURadio reserved memory)
*out[0] = current_symbol;
return 1;
}

View File

@ -0,0 +1,120 @@
/*!
* \file gps_l1_ca_telemetry_decoder_cc.h
* \brief Interface of a NAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \author Javier Arribas, 2011. jarribas(at)cttc.es
* -------------------------------------------------------------------------
*
* 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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L1_CA_TELEMETRY_DECODER_CC_H
#define GNSS_SDR_GPS_L1_CA_TELEMETRY_DECODER_CC_H
#include "GPS_L1_CA.h"
#include "gps_l1_ca_subframe_fsm.h"
#include "gnss_satellite.h"
#include "gnss_synchro.h"
#include <gnuradio/block.h>
#include <fstream>
#include <string>
#include <boost/circular_buffer.hpp>
class gps_l1_ca_telemetry_decoder_cc;
typedef boost::shared_ptr<gps_l1_ca_telemetry_decoder_cc> gps_l1_ca_telemetry_decoder_cc_sptr;
gps_l1_ca_telemetry_decoder_cc_sptr
gps_l1_ca_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
/*!
* \brief This class implements a block that decodes the NAV data defined in IS-GPS-200E
*
*/
class gps_l1_ca_telemetry_decoder_cc : public gr::block
{
public:
~gps_l1_ca_telemetry_decoder_cc();
void set_satellite(const Gnss_Satellite &satellite); //!< Set satellite PRN
void set_channel(int channel); //!< Set receiver's channel
/*!
* \brief This is where all signal processing takes place
*/
int general_work(int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private:
friend gps_l1_ca_telemetry_decoder_cc_sptr
gps_l1_ca_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
gps_l1_ca_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
bool gps_word_parityCheck(unsigned int gpsword);
// class private vars
int *d_preambles_symbols;
unsigned int d_stat;
bool d_flag_frame_sync;
// symbols
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;
unsigned int d_prev_GPS_frame_4bytes;
bool d_flag_parity;
bool d_flag_preamble;
bool d_flag_new_tow_available;
int d_word_number;
// navigation message vars
Gps_Navigation_Message d_nav;
GpsL1CaSubframeFsm d_GPS_FSM;
bool d_dump;
Gnss_Satellite d_satellite;
int d_channel;
unsigned long int d_preamble_time_samples;
unsigned int d_TOW_at_Preamble_ms;
unsigned int d_TOW_at_current_symbol_ms;
bool flag_TOW_set;
bool flag_PLL_180_deg_phase_locked;
std::string d_dump_filename;
std::ofstream d_dump_file;
};
#endif

View File

@ -38,6 +38,7 @@ set(TRACKING_ADAPTER_SOURCES
gps_l5_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_c_aid_tracking.cc
beidou_b1i_dll_pll_tracking.cc
${OPT_TRACKING_ADAPTERS}
)

View File

@ -0,0 +1,199 @@
/*!
* \file gps_l1_ca_dll_pll_tracking.cc
* \brief Implementation of an adapter of a DLL+PLL tracking loop block
* for GPS L1 C/A to a TrackingInterface
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Javier Arribas, 2011. jarribas(at)cttc.es
*
* Code DLL + carrier PLL according to the algorithms described in:
* K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency
* Approach, Birkhauser, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_dll_pll_tracking.h"
#include "configuration_interface.h"
#include "GPS_L1_CA.h"
#include "gnss_sdr_flags.h"
#include "display.h"
#include <glog/logging.h>
using google::LogMessage;
GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{
dllpllconf_t trk_param;
DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ########################
std::string default_item_type = "gr_complex";
std::string item_type = configuration->property(role + ".item_type", default_item_type);
int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
int fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
trk_param.fs_in = fs_in;
bool dump = configuration->property(role + ".dump", false);
trk_param.dump = dump;
float pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0);
if (FLAGS_pll_bw_hz != 0.0) pll_bw_hz = static_cast<float>(FLAGS_pll_bw_hz);
trk_param.pll_bw_hz = pll_bw_hz;
float pll_bw_narrow_hz = configuration->property(role + ".pll_bw_narrow_hz", 20.0);
trk_param.pll_bw_narrow_hz = pll_bw_narrow_hz;
float dll_bw_narrow_hz = configuration->property(role + ".dll_bw_narrow_hz", 2.0);
trk_param.dll_bw_narrow_hz = dll_bw_narrow_hz;
float dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
if (FLAGS_dll_bw_hz != 0.0) dll_bw_hz = static_cast<float>(FLAGS_dll_bw_hz);
trk_param.dll_bw_hz = dll_bw_hz;
float early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
trk_param.early_late_space_chips = early_late_space_chips;
float early_late_space_narrow_chips = configuration->property(role + ".early_late_space_narrow_chips", 0.5);
trk_param.early_late_space_narrow_chips = early_late_space_narrow_chips;
std::string default_dump_filename = "./track_ch";
std::string dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
trk_param.dump_filename = dump_filename;
int vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
trk_param.vector_length = vector_length;
int symbols_extended_correlator = configuration->property(role + ".extend_correlation_symbols", 1);
if (symbols_extended_correlator < 1)
{
symbols_extended_correlator = 1;
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. extend_correlation_symbols must be bigger than 1. Coherent integration has been set to 1 symbol (1 ms)" << TEXT_RESET << std::endl;
}
else if (symbols_extended_correlator > 20)
{
symbols_extended_correlator = 20;
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. extend_correlation_symbols must be lower than 21. Coherent integration has been set to 20 symbols (20 ms)" << TEXT_RESET << std::endl;
}
trk_param.extend_correlation_symbols = symbols_extended_correlator;
bool track_pilot = configuration->property(role + ".track_pilot", false);
if (track_pilot)
{
std::cout << TEXT_RED << "WARNING: GPS L1 C/A does not have pilot signal. Data tracking has been enabled" << TEXT_RESET << std::endl;
}
if ((symbols_extended_correlator > 1) and (pll_bw_narrow_hz > pll_bw_hz or dll_bw_narrow_hz > dll_bw_hz))
{
std::cout << TEXT_RED << "WARNING: GPS L1 C/A. PLL or DLL narrow tracking bandwidth is higher than wide tracking one" << TEXT_RESET << std::endl;
}
trk_param.very_early_late_space_chips = 0.0;
trk_param.very_early_late_space_narrow_chips = 0.0;
trk_param.track_pilot = false;
trk_param.system = 'G';
char sig_[3] = "1C";
std::memcpy(trk_param.signal, sig_, 3);
int cn0_samples = configuration->property(role + ".cn0_samples", 20);
if (FLAGS_cn0_samples != 20) cn0_samples = FLAGS_cn0_samples;
trk_param.cn0_samples = cn0_samples;
int cn0_min = configuration->property(role + ".cn0_min", 25);
if (FLAGS_cn0_min != 25) cn0_min = FLAGS_cn0_min;
trk_param.cn0_min = cn0_min;
int max_lock_fail = configuration->property(role + ".max_lock_fail", 50);
if (FLAGS_max_lock_fail != 50) max_lock_fail = FLAGS_max_lock_fail;
trk_param.max_lock_fail = max_lock_fail;
double carrier_lock_th = configuration->property(role + ".carrier_lock_th", 0.85);
if (FLAGS_carrier_lock_th != 0.85) carrier_lock_th = FLAGS_carrier_lock_th;
trk_param.carrier_lock_th = carrier_lock_th;
//################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0)
{
item_size_ = sizeof(gr_complex);
tracking_ = dll_pll_veml_make_tracking(trk_param);
}
else
{
item_size_ = sizeof(gr_complex);
LOG(WARNING) << item_type << " unknown tracking item type.";
}
channel_ = 0;
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
if (in_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one input stream";
}
if (out_streams_ > 1)
{
LOG(ERROR) << "This implementation only supports one output stream";
}
}
GpsL1CaDllPllTracking::~GpsL1CaDllPllTracking()
{
}
void GpsL1CaDllPllTracking::start_tracking()
{
tracking_->start_tracking();
}
/*
* Set tracking channel unique ID
*/
void GpsL1CaDllPllTracking::set_channel(unsigned int channel)
{
channel_ = channel;
tracking_->set_channel(channel);
}
void GpsL1CaDllPllTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
{
tracking_->set_gnss_synchro(p_gnss_synchro);
}
void GpsL1CaDllPllTracking::connect(gr::top_block_sptr top_block)
{
if (top_block)
{ /* top_block is not null */
};
//nothing to connect, now the tracking uses gr_sync_decimator
}
void GpsL1CaDllPllTracking::disconnect(gr::top_block_sptr top_block)
{
if (top_block)
{ /* top_block is not null */
};
//nothing to disconnect, now the tracking uses gr_sync_decimator
}
gr::basic_block_sptr GpsL1CaDllPllTracking::get_left_block()
{
return tracking_;
}
gr::basic_block_sptr GpsL1CaDllPllTracking::get_right_block()
{
return tracking_;
}

View File

@ -0,0 +1,103 @@
/*!
* \file gps_l1_ca_dll_pll_tracking.h
* \brief Interface of an adapter of a DLL+PLL tracking loop block
* for GPS L1 C/A to a TrackingInterface
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Javier Arribas, 2011. jarribas(at)cttc.es
*
* Code DLL + carrier PLL according to the algorithms described in:
* K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency
* Approach, Birkhauser, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_H_
#define GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_H_
#include "tracking_interface.h"
#include "dll_pll_veml_tracking.h"
#include <string>
class ConfigurationInterface;
/*!
* \brief This class implements a code DLL + carrier PLL tracking loop
*/
class GpsL1CaDllPllTracking : public TrackingInterface
{
public:
GpsL1CaDllPllTracking(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GpsL1CaDllPllTracking();
inline std::string role() override
{
return role_;
}
//! Returns "GPS_L1_CA_DLL_PLL_Tracking"
inline std::string implementation() override
{
return "BEIDOU_B1I_DLL_PLL_Tracking";
}
inline size_t item_size() override
{
return item_size_;
}
void connect(gr::top_block_sptr top_block) override;
void disconnect(gr::top_block_sptr top_block) override;
gr::basic_block_sptr get_left_block() override;
gr::basic_block_sptr get_right_block() override;
/*!
* \brief Set tracking channel unique ID
*/
void set_channel(unsigned int channel) override;
/*!
* \brief Set acquisition/tracking common Gnss_Synchro object pointer
* to efficiently exchange synchronization data between acquisition and tracking blocks
*/
void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro) override;
void start_tracking() override;
private:
dll_pll_veml_tracking_sptr tracking_;
size_t item_size_;
unsigned int channel_;
std::string role_;
unsigned int in_streams_;
unsigned int out_streams_;
};
#endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_H_

View File

@ -94,6 +94,7 @@
#include "glonass_l2_ca_dll_pll_tracking.h"
#include "glonass_l2_ca_dll_pll_c_aid_tracking.h"
#include "gps_l5_dll_pll_tracking.h"
#include "beidou_b1i_dll_pll_tracking.h"
#include "gps_l1_ca_telemetry_decoder.h"
#include "gps_l2c_telemetry_decoder.h"
#include "gps_l5_telemetry_decoder.h"
@ -101,6 +102,7 @@
#include "galileo_e5a_telemetry_decoder.h"
#include "glonass_l1_ca_telemetry_decoder.h"
#include "glonass_l2_ca_telemetry_decoder.h"
#include "beidou_b1i_telemetry_decoder.h"
#include "sbas_l1_telemetry_decoder.h"
#include "hybrid_observables.h"
#include "rtklib_pvt.h"
@ -826,10 +828,13 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_B1(
LOG(ERROR) << "Acquisition and Tracking blocks must have the same input data type!";
}
config->set_property("Channel.item_type", acq_item_type);
std::cout << "Now Channel pass Through" << std::endl;
std::unique_ptr<GNSSBlockInterface> pass_through_ = GetBlock(configuration, "Channel", "Pass_Through", 1, 1, queue);
std::cout << "Now Acquisition" << std::endl;
std::unique_ptr<AcquisitionInterface> acq_ = GetAcqBlock(configuration, "Acquisition_B1" + appendix1, acq, 1, 0);
std::cout << "Now Tracking" << std::endl;
std::unique_ptr<TrackingInterface> trk_ = GetTrkBlock(configuration, "Tracking_B1" + appendix2, trk, 1, 1);
std::cout << "Now Telemetry Decoder" << std::endl;
std::unique_ptr<TelemetryDecoderInterface> tlm_ = GetTlmBlock(configuration, "TelemetryDecoder_B1" + appendix3, tlm, 1, 1);
std::unique_ptr<GNSSBlockInterface> channel_(new Channel(configuration.get(), channel, std::move(pass_through_),
@ -1138,6 +1143,8 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
if (implementation.compare("Pass_Through") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new Pass_Through(configuration.get(), role, in_streams, out_streams));
std::cout << "Input streams: " <<in_streams<< "Output streams: " <<out_streams <<"GNSS-SDR program ended." << std::endl;
block = std::move(block_);
}
@ -1649,6 +1656,12 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("BEIDOU_B1I_DLL_PLL_Tracking") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaDllPllTracking(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
// TELEMETRY DECODERS ----------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_Telemetry_Decoder") == 0)
{
@ -1698,6 +1711,13 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("BEIDOU_B1I_Telemetry_Decoder") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
// OBSERVABLES -----------------------------------------------------------------
else if ((implementation.compare("Hybrid_Observables") == 0) || (implementation.compare("GPS_L1_CA_Observables") == 0) || (implementation.compare("GPS_L2C_Observables") == 0) ||
(implementation.compare("Galileo_E5A_Observables") == 0))
@ -1854,6 +1874,13 @@ std::unique_ptr<AcquisitionInterface> GNSSBlockFactory::GetAcqBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("BEIDOU_B1I_PCPS_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new BeidouB1iPcpsAcquisition(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
@ -1960,6 +1987,13 @@ std::unique_ptr<TrackingInterface> GNSSBlockFactory::GetTrkBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("BEIDOU_B1I_DLL_PLL_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaDllPllTracking(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
@ -2026,6 +2060,14 @@ std::unique_ptr<TelemetryDecoderInterface> GNSSBlockFactory::GetTlmBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("BEIDOU_B1I_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new GpsL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.

View File

@ -972,7 +972,8 @@ void GNSSFlowgraph::set_signals_list()
std::set<unsigned int> available_glonass_prn = {1, 2, 3, 4, 9, 10, 11, 12, 18, 19, 20, 21, 24};
std::set<unsigned int> available_beidou_prn = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 17, 31, 32, 33, 34, 35};
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29,
30, 31, 32, 33, 34, 35};
std::string sv_list = configuration_->property("Galileo.prns", std::string(""));
@ -992,7 +993,7 @@ void GNSSFlowgraph::set_signals_list()
sv_list = configuration_->property("GPS.prns", std::string(""));
if (sv_list.length() > 0)
if (sv_list.length() > 0)
{
// Reset the available prns:
std::set<unsigned int> tmp_set;
@ -1038,6 +1039,7 @@ void GNSSFlowgraph::set_signals_list()
}
}
sv_list = configuration_->property("Beidou.prns", std::string(""));
if (sv_list.length() > 0)
{
@ -1186,6 +1188,7 @@ void GNSSFlowgraph::set_signals_list()
available_GNSS_signals_.push_back(Gnss_Signal(
Gnss_Satellite(std::string("Beidou"), *available_gnss_prn_iter),
std::string("B1")));
}
}

View File

@ -222,6 +222,19 @@ void Gnss_Satellite::set_PRN(unsigned int PRN_)
PRN = PRN_;
}
}
else if (system.compare("Beidou") == 0)
{
if (PRN_ < 1 or PRN_ > 36)
{
DLOG(INFO) << "This PRN is not defined";
PRN = 0;
}
else
{
PRN = PRN_;
}
}
else
{
DLOG(INFO) << "System " << system << " is not defined";

View File

@ -115,6 +115,7 @@ DECLARE_string(log_dir);
#include "unit-tests/signal-processing-blocks/acquisition/galileo_e5a_pcps_acquisition_gsoc2014_gensource_test.cc"
#include "unit-tests/signal-processing-blocks/acquisition/glonass_l1_ca_pcps_acquisition_gsoc2017_test.cc"
// #include "unit-tests/signal-processing-blocks/acquisition/glonass_l2_ca_pcps_acquisition_test.cc"
#include "unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc"
#if OPENCL_BLOCKS_TEST
#include "unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc"

View File

@ -0,0 +1,350 @@
/*!
* \file beidou_b1i_pcps_acquisition_test.cc
* \brief This class implements an acquisition test for
* BeidouB1iPcpsAcquisition class based on some input parameters.
* \author Sergi Segura, 2018. sergi.segura.munoz(at)gmail.com
*
*
* -------------------------------------------------------------------------
*
* 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 <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <chrono>
#include <boost/filesystem.hpp>
#include <boost/make_shared.hpp>
#include <glog/logging.h>
#include <gnuradio/top_block.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/analog/sig_source_waveform.h>
#include <gnuradio/analog/sig_source_c.h>
#include <gnuradio/msg_queue.h>
#include <gnuradio/blocks/null_sink.h>
#include <gtest/gtest.h>
#include "gnss_block_factory.h"
#include "gnss_block_interface.h"
#include "in_memory_configuration.h"
#include "gnss_sdr_valve.h"
#include "gnss_synchro.h"
#include "gnuplot_i.h"
#include "beidou_b1I.h"
#include "test_flags.h"
#include "acquisition_dump_reader.h"
#include "beidou_b1i_pcps_acquisition.h"
// ######## GNURADIO BLOCK MESSAGE RECEVER #########
class BeidouB1iPcpsAcquisitionTest_msg_rx;
typedef boost::shared_ptr<BeidouB1iPcpsAcquisitionTest_msg_rx> BeidouB1iPcpsAcquisitionTest_msg_rx_sptr;
BeidouB1iPcpsAcquisitionTest_msg_rx_sptr BeidouB1iPcpsAcquisitionTest_msg_rx_make();
class BeidouB1iPcpsAcquisitionTest_msg_rx : public gr::block
{
private:
friend BeidouB1iPcpsAcquisitionTest_msg_rx_sptr BeidouB1iPcpsAcquisitionTest_msg_rx_make();
void msg_handler_events(pmt::pmt_t msg);
BeidouB1iPcpsAcquisitionTest_msg_rx();
public:
int rx_message;
~BeidouB1iPcpsAcquisitionTest_msg_rx(); //!< Default destructor
};
BeidouB1iPcpsAcquisitionTest_msg_rx_sptr BeidouB1iPcpsAcquisitionTest_msg_rx_make()
{
return BeidouB1iPcpsAcquisitionTest_msg_rx_sptr(new BeidouB1iPcpsAcquisitionTest_msg_rx());
}
void BeidouB1iPcpsAcquisitionTest_msg_rx::msg_handler_events(pmt::pmt_t msg)
{
try
{
long int message = pmt::to_long(msg);
rx_message = message;
}
catch (boost::bad_any_cast &e)
{
LOG(WARNING) << "msg_handler_telemetry Bad any cast!";
rx_message = 0;
}
}
BeidouB1iPcpsAcquisitionTest_msg_rx::BeidouB1iPcpsAcquisitionTest_msg_rx() : gr::block("BeidouB1iPcpsAcquisitionTest_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0))
{
this->message_port_register_in(pmt::mp("events"));
this->set_msg_handler(pmt::mp("events"), boost::bind(&BeidouB1iPcpsAcquisitionTest_msg_rx::msg_handler_events, this, _1));
rx_message = 0;
}
BeidouB1iPcpsAcquisitionTest_msg_rx::~BeidouB1iPcpsAcquisitionTest_msg_rx()
{
}
// ###########################################################
class BeidouB1iPcpsAcquisitionTest : public ::testing::Test
{
protected:
BeidouB1iPcpsAcquisitionTest()
{
factory = std::make_shared<GNSSBlockFactory>();
config = std::make_shared<InMemoryConfiguration>();
item_size = sizeof(gr_complex);
gnss_synchro = Gnss_Synchro();
doppler_max = 5000;
doppler_step = 100;
}
~BeidouB1iPcpsAcquisitionTest()
{
}
void init();
void plot_grid();
gr::top_block_sptr top_block;
std::shared_ptr<GNSSBlockFactory> factory;
std::shared_ptr<InMemoryConfiguration> config;
Gnss_Synchro gnss_synchro;
size_t item_size;
unsigned int doppler_max;
unsigned int doppler_step;
};
void BeidouB1iPcpsAcquisitionTest::init()
{
gnss_synchro.Channel_ID = 0;
gnss_synchro.System = 'C';
std::string signal = "B1";
signal.copy(gnss_synchro.Signal, 2, 0);
gnss_synchro.PRN = 1;
config->set_property("GNSS-SDR.internal_fs_sps", "25000000");
config->set_property("Acquisition_B1.implementation", "BEIDOU_B1I_PCPS_Acquisition");
config->set_property("Acquisition_B1.item_type", "gr_complex");
config->set_property("Acquisition_B1.coherent_integration_time_ms", "1");
if (FLAGS_plot_acq_grid == true)
{
config->set_property("Acquisition_B1.dump", "true");
}
else
{
config->set_property("Acquisition_B1.dump", "false");
}
config->set_property("Acquisition_B1.dump_filename", "./tmp-acq-beidou1/acquisition");
config->set_property("Acquisition_B1.threshold", "0.00001");
config->set_property("Acquisition_B1.doppler_max", std::to_string(doppler_max));
config->set_property("Acquisition_B1.doppler_step", std::to_string(doppler_step));
config->set_property("Acquisition_B1.repeat_satellite", "false");
//config->set_property("Acquisition_B1.pfa", "0.0");
}
void BeidouB1iPcpsAcquisitionTest::plot_grid()
{
//load the measured values
std::string basename = "./tmp-acq-beidou1/acquisition_C_B1";
unsigned int sat = static_cast<unsigned int>(gnss_synchro.PRN);
unsigned int samples_per_code = static_cast<unsigned int>(round(4000000 / (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS))); // !!
acquisition_dump_reader acq_dump(basename, sat, doppler_max, doppler_step, samples_per_code);
if (!acq_dump.read_binary_acq()) std::cout << "Error reading files" << std::endl;
std::vector<int> *doppler = &acq_dump.doppler;
std::vector<unsigned int> *samples = &acq_dump.samples;
std::vector<std::vector<float> > *mag = &acq_dump.mag;
const std::string gnuplot_executable(FLAGS_gnuplot_executable);
if (gnuplot_executable.empty())
{
std::cout << "WARNING: Although the flag plot_acq_grid has been set to TRUE," << std::endl;
std::cout << "gnuplot has not been found in your system." << std::endl;
std::cout << "Test results will not be plotted." << std::endl;
}
else
{
std::cout << "Plotting the acquisition grid. This can take a while..." << std::endl;
try
{
boost::filesystem::path p(gnuplot_executable);
boost::filesystem::path dir = p.parent_path();
std::string gnuplot_path = dir.native();
Gnuplot::set_GNUPlotPath(gnuplot_path);
Gnuplot g1("lines");
g1.set_title("BeiDou signal acquisition for satellite PRN #" + std::to_string(gnss_synchro.PRN));
g1.set_xlabel("Doppler [Hz]");
g1.set_ylabel("Sample");
//g1.cmd("set view 60, 105, 1, 1");
g1.plot_grid3d(*doppler, *samples, *mag);
g1.savetops("BEIDOU_B1I_acq_grid");
g1.savetopdf("BEIDOU_BI1_acq_grid");
g1.showonscreen();
}
catch (const GnuplotException &ge)
{
std::cout << ge.what() << std::endl;
}
}
std::string data_str = "./tmp-acq-beidou1";
if (boost::filesystem::exists(data_str))
{
boost::filesystem::remove_all(data_str);
}
}
TEST_F(BeidouB1iPcpsAcquisitionTest, Instantiate)
{
init();
boost::shared_ptr<BeidouB1iPcpsAcquisition> acquisition = boost::make_shared<BeidouB1iPcpsAcquisition>(config.get(), "Acquisition_B1", 1, 0);
}
TEST_F(BeidouB1iPcpsAcquisitionTest, ConnectAndRun)
{
int fs_in = 25000000;
int nsamples = 4000;
std::chrono::time_point<std::chrono::system_clock> start, end;
std::chrono::duration<double> elapsed_seconds(0);
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
top_block = gr::make_top_block("Acquisition test");
init();
boost::shared_ptr<BeidouB1iPcpsAcquisition> acquisition = boost::make_shared<BeidouB1iPcpsAcquisition>(config.get(), "Acquisition_B1", 1, 0);
boost::shared_ptr<BeidouB1iPcpsAcquisitionTest_msg_rx> msg_rx = BeidouB1iPcpsAcquisitionTest_msg_rx_make();
ASSERT_NO_THROW({
acquisition->connect(top_block);
boost::shared_ptr<gr::analog::sig_source_c> source = gr::analog::sig_source_c::make(fs_in, gr::analog::GR_SIN_WAVE, 1000, 1, gr_complex(0));
boost::shared_ptr<gr::block> valve = gnss_sdr_make_valve(sizeof(gr_complex), nsamples, queue);
top_block->connect(source, 0, valve, 0);
top_block->connect(valve, 0, acquisition->get_left_block(), 0);
top_block->msg_connect(acquisition->get_right_block(), pmt::mp("events"), msg_rx, pmt::mp("events"));
}) << "Failure connecting the blocks of acquisition test.";
EXPECT_NO_THROW({
start = std::chrono::system_clock::now();
top_block->run(); // Start threads and wait
end = std::chrono::system_clock::now();
elapsed_seconds = end - start;
}) << "Failure running the top_block.";
std::cout << "Processed " << nsamples << " samples in " << elapsed_seconds.count() * 1e6 << " microseconds" << std::endl;
}
TEST_F(BeidouB1iPcpsAcquisitionTest, ValidationOfResults)
{
std::chrono::time_point<std::chrono::system_clock> start, end;
std::chrono::duration<double> elapsed_seconds(0.0);
top_block = gr::make_top_block("Acquisition test");
double expected_delay_samples = 524;
double expected_doppler_hz = 1680;
init();
if (FLAGS_plot_acq_grid == true)
{
std::string data_str = "./tmp-acq-beidou1";
if (boost::filesystem::exists(data_str))
{
boost::filesystem::remove_all(data_str);
}
boost::filesystem::create_directory(data_str);
}
std::shared_ptr<BeidouB1iPcpsAcquisition> acquisition = std::make_shared<BeidouB1iPcpsAcquisition>(config.get(), "Acquisition_B1", 1, 0);
boost::shared_ptr<BeidouB1iPcpsAcquisitionTest_msg_rx> msg_rx = BeidouB1iPcpsAcquisitionTest_msg_rx_make();
ASSERT_NO_THROW({
acquisition->set_channel(1);
}) << "Failure setting channel.";
ASSERT_NO_THROW({
acquisition->set_gnss_synchro(&gnss_synchro);
}) << "Failure setting gnss_synchro.";
ASSERT_NO_THROW({
acquisition->set_threshold(0.001);
}) << "Failure setting threshold.";
ASSERT_NO_THROW({
acquisition->set_doppler_max(doppler_max);
}) << "Failure setting doppler_max.";
ASSERT_NO_THROW({
acquisition->set_doppler_step(doppler_step);
}) << "Failure setting doppler_step.";
ASSERT_NO_THROW({
acquisition->connect(top_block);
}) << "Failure connecting acquisition to the top_block.";
ASSERT_NO_THROW({
std::string path = std::string(TEST_PATH);
std::string file = path + "signal_samples/BEIDOU_B1I_ID_1_Fs_4Msps_2ms.dat";
const char *file_name = file.c_str();
gr::blocks::file_source::sptr file_source = gr::blocks::file_source::make(sizeof(gr_complex), file_name, false);
top_block->connect(file_source, 0, acquisition->get_left_block(), 0);
top_block->msg_connect(acquisition->get_right_block(), pmt::mp("events"), msg_rx, pmt::mp("events"));
}) << "Failure connecting the blocks of acquisition test.";
acquisition->set_local_code();
acquisition->set_state(1); // Ensure that acquisition starts at the first sample
acquisition->init();
EXPECT_NO_THROW({
start = std::chrono::system_clock::now();
top_block->run(); // Start threads and wait
end = std::chrono::system_clock::now();
elapsed_seconds = end - start;
}) << "Failure running the top_block.";
unsigned long int nsamples = gnss_synchro.Acq_samplestamp_samples;
std::cout << "Acquired " << nsamples << " samples in " << elapsed_seconds.count() * 1e6 << " microseconds" << std::endl;
ASSERT_EQ(1, msg_rx->rx_message) << "Acquisition failure. Expected message: 1=ACQ SUCCESS.";
double delay_error_samples = std::abs(expected_delay_samples - gnss_synchro.Acq_delay_samples);
float delay_error_chips = static_cast<float>(delay_error_samples * 1023 / 4000);
double doppler_error_hz = std::abs(expected_doppler_hz - gnss_synchro.Acq_doppler_hz);
EXPECT_LE(doppler_error_hz, 666) << "Doppler error exceeds the expected value: 666 Hz = 2/(3*integration period)";
EXPECT_LT(delay_error_chips, 0.5) << "Delay error exceeds the expected value: 0.5 chips";
if (FLAGS_plot_acq_grid == true)
{
plot_grid();
}
}