1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-06-18 11:09:56 +00:00

Add GPS L5 files

This commit is contained in:
Antonio Ramos 2017-11-29 15:51:30 +01:00
parent e57c66bd83
commit 7c8855b9ac
10 changed files with 595 additions and 11 deletions

View File

@ -18,7 +18,8 @@
set(TELEMETRY_DECODER_ADAPTER_SOURCES
gps_l1_ca_telemetry_decoder.cc
gps_l2c_telemetry_decoder.cc
gps_l2c_telemetry_decoder.cc
gps_l5_telemetry_decoder.cc
galileo_e1b_telemetry_decoder.cc
sbas_l1_telemetry_decoder.cc
galileo_e5a_telemetry_decoder.cc

View File

@ -0,0 +1,103 @@
/*!
* \file gps_l5_telemetry_decoder.cc
* \brief Implementation of an adapter of a GPS L5 NAV data decoder block
* to a TelemetryDecoderInterface
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "gps_l5_telemetry_decoder.h"
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "concurrent_queue.h"
#include "gps_cnav_ephemeris.h"
#include "gps_almanac.h"
#include "gps_cnav_iono.h"
#include "gps_cnav_utc_model.h"
#include "configuration_interface.h"
using google::LogMessage;
GpsL5TelemetryDecoder::GpsL5TelemetryDecoder(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_l5_make_telemetry_decoder_cc(satellite_, dump_);
DLOG(INFO) << "telemetry_decoder(" << telemetry_decoder_->unique_id() << ")";
LOG(INFO) << "global navigation message queue assigned to telemetry_decoder (" << telemetry_decoder_->unique_id() << ")" << "role " << role;
channel_ = 0;
}
GpsL5TelemetryDecoder::~GpsL5TelemetryDecoder()
{}
void GpsL5TelemetryDecoder::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 GpsL5TelemetryDecoder::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 GpsL5TelemetryDecoder::disconnect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
// Nothing to disconnect
}
gr::basic_block_sptr GpsL5TelemetryDecoder::get_left_block()
{
return telemetry_decoder_;
}
gr::basic_block_sptr GpsL5TelemetryDecoder::get_right_block()
{
return telemetry_decoder_;
}

View File

@ -0,0 +1,95 @@
/*!
* \file gps_l5_telemetry_decoder.h
* \brief Interface of an adapter of a GPS L5 (CNAV) data decoder block
* to a TelemetryDecoderInterface
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L5_TELEMETRY_DECODER_H_
#define GNSS_SDR_GPS_L5_TELEMETRY_DECODER_H_
#include <string>
#include "telemetry_decoder_interface.h"
#include "gps_l5_telemetry_decoder_cc.h"
class ConfigurationInterface;
/*!
* \brief This class implements a NAV data decoder for GPS L5
*/
class GpsL5TelemetryDecoder : public TelemetryDecoderInterface
{
public:
GpsL5TelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GpsL5TelemetryDecoder();
inline std::string role() override
{
return role_;
}
//! Returns "GPS_L5_Telemetry_Decoder"
inline std::string implementation() override
{
return "GPS_L5_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_l5_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

@ -19,6 +19,7 @@
set(TELEMETRY_DECODER_GR_BLOCKS_SOURCES
gps_l1_ca_telemetry_decoder_cc.cc
gps_l2c_telemetry_decoder_cc.cc
gps_l5_telemetry_decoder_cc.cc
galileo_e1b_telemetry_decoder_cc.cc
sbas_l1_telemetry_decoder_cc.cc
galileo_e5a_telemetry_decoder_cc.cc

View File

@ -297,14 +297,8 @@ int galileo_e5a_telemetry_decoder_cc::general_work (int noutput_items __attribut
d_symbol_counter = 0;
flag_bit_start = true;
corr_value = 0;
while(d_preamble_init.size() > 0)
{ //Clear preamble correlating queue
d_preamble_init.pop_front();
}
while(d_symbol_history.size() > 0)
{ //Clear symbol queue in order to prevent possible symbol discontinuities
d_symbol_history.pop_front();
}
d_preamble_init.clear();
d_symbol_history.clear();
LOG(INFO) << "Bit start sync for Galileo E5a satellite " << d_satellite;
}
else

View File

@ -0,0 +1,236 @@
/*!
* \file gps_l5_telemetry_decoder_cc.cc
* \brief Implementation of a NAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <bitset>
#include <iostream>
#include <sstream>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <boost/lexical_cast.hpp>
#include "gnss_synchro.h"
#include "gps_l5_telemetry_decoder_cc.h"
using google::LogMessage;
gps_l5_telemetry_decoder_cc_sptr
gps_l5_make_telemetry_decoder_cc(const Gnss_Satellite & satellite, bool dump)
{
return gps_l5_telemetry_decoder_cc_sptr(new gps_l5_telemetry_decoder_cc(satellite, dump));
}
gps_l5_telemetry_decoder_cc::gps_l5_telemetry_decoder_cc(
const Gnss_Satellite & satellite, bool dump) : gr::block("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
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "GPS L5 TELEMETRY PROCESSING: satellite " << d_satellite;
//set_output_multiple (1);
d_channel = 0;
d_flag_valid_word = false;
d_TOW_at_current_symbol = 0;
d_TOW_at_Preamble = 0;
d_state = 0; //initial state
d_crc_error_count = 0;
//initialize the CNAV frame decoder (libswiftcnav)
cnav_msg_decoder_init(&d_cnav_decoder);
}
gps_l5_telemetry_decoder_cc::~gps_l5_telemetry_decoder_cc()
{
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();
}
}
}
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)
{
// 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
bool flag_new_cnav_frame = false;
cnav_msg_t msg;
u32 delay = 0;
//add the symbol to the decoder
u8 symbol_clip = static_cast<u8>(in[0].Prompt_I > 0) * 255;
flag_new_cnav_frame = cnav_msg_decoder_add_symbol(&d_cnav_decoder, symbol_clip, &msg, &delay);
consume_each(1); //one by one
// UPDATE GNSS SYNCHRO DATA
Gnss_Synchro current_synchro_data; //structure to save the synchronization information and send the output object to the next block
//1. Copy the current tracking output
current_synchro_data = in[0];
//2. Add the telemetry decoder information
//check if new CNAV frame is available
if (flag_new_cnav_frame == true)
{
std::bitset<GPS_L5_CNAV_DATA_PAGE_BITS> raw_bits;
//Expand packet bits to bitsets. Notice the reverse order of the bits sequence, required by the CNAV message decoder
for (u32 i = 0; i < GPS_L5_CNAV_DATA_PAGE_BITS ; i++)
{
raw_bits[GPS_L5_CNAV_DATA_PAGE_BITS - 1 - i] = ((msg.raw_msg[i/8] >> (7 - i%8)) & 1u);
}
d_CNAV_Message.decode_page(raw_bits);
//Push the new navigation data to the queues
if (d_CNAV_Message.have_new_ephemeris() == true)
{
// 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 CNAV message received: ephemeris from satellite " << d_satellite << 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 CNAV message received: iono model parameters from satellite " << d_satellite << 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 CNAV message received: UTC model parameters from satellite " << d_satellite << std::endl;
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
//update TOW at the preamble instant
d_TOW_at_Preamble = static_cast<int>(msg.tow);
//* The time of the last input symbol can be computed from the message ToW and
//* delay by the formulae:
//* \code
//* symbolTime_ms = msg->tow * 6000 + *pdelay * 20
d_TOW_at_current_symbol = static_cast<double>(msg.tow) * 6.0 + static_cast<double>(delay) * GPS_L5_PERIOD + 6 * GPS_L5_PERIOD;
d_TOW_at_current_symbol = floor(d_TOW_at_current_symbol * 1000.0) / 1000.0;
d_flag_valid_word = true;
}
else
{
d_TOW_at_current_symbol += GPS_L5_PERIOD;
if (current_synchro_data.Flag_valid_symbol_output == false)
{
d_flag_valid_word = false;
}
}
current_synchro_data.TOW_at_current_symbol_s = d_TOW_at_current_symbol;
current_synchro_data.Flag_valid_word = d_flag_valid_word;
// if (flag_PLL_180_deg_phase_locked == true)
// {
// //correct the accumulated phase for the Costas loop phase shift, if required
// current_synchro_data.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 = d_TOW_at_current_symbol;
d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
tmp_ulong_int = current_synchro_data.Tracking_sample_counter;
d_dump_file.write(reinterpret_cast<char*>(&tmp_ulong_int), sizeof(unsigned long int));
tmp_double = d_TOW_at_Preamble;
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_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;
}
void gps_l5_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
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 trk dump file " << e.what();
}
}
}
}

View File

@ -0,0 +1,105 @@
/*!
* \file gps_l5_telemetry_decoder_cc.h
* \brief Interface of a CNAV message demodulator block based on
* Kay Borre book MATLAB-based GPS receiver
* \author Antonio Ramos, 2017. antonio.ramos(at)cttc.es
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GPS_L5_TELEMETRY_DECODER_CC_H
#define GNSS_SDR_GPS_L5_TELEMETRY_DECODER_CC_H
#include <algorithm> // for copy
#include <deque>
#include <fstream>
#include <string>
#include <utility> // for pair
#include <vector>
#include <gnuradio/block.h>
#include "gnss_satellite.h"
#include "gps_cnav_navigation_message.h"
#include "gps_cnav_ephemeris.h"
#include "gps_cnav_iono.h"
#include "concurrent_queue.h"
extern "C" {
#include "cnav_msg.h"
#include "edc.h"
#include "bits.h"
}
#include "GPS_L5.h"
class gps_l5_telemetry_decoder_cc;
typedef boost::shared_ptr<gps_l5_telemetry_decoder_cc> gps_l5_telemetry_decoder_cc_sptr;
gps_l5_telemetry_decoder_cc_sptr
gps_l5_make_telemetry_decoder_cc(const Gnss_Satellite & satellite, bool dump);
/*!
* \brief This class implements a block that decodes the SBAS integrity and corrections data defined in RTCA MOPS DO-229
*
*/
class gps_l5_telemetry_decoder_cc : public gr::block
{
public:
~gps_l5_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_l5_telemetry_decoder_cc_sptr
gps_l5_make_telemetry_decoder_cc(const Gnss_Satellite & satellite, bool dump);
gps_l5_telemetry_decoder_cc(const Gnss_Satellite & satellite, bool dump);
bool d_dump;
Gnss_Satellite d_satellite;
int d_channel;
std::string d_dump_filename;
std::ofstream d_dump_file;
cnav_msg_decoder_t d_cnav_decoder;
int d_state;
int d_crc_error_count;
double d_TOW_at_current_symbol;
double d_TOW_at_Preamble;
bool d_flag_valid_word;
Gps_CNAV_Navigation_Message d_CNAV_Message;
};
#endif

View File

@ -49,9 +49,11 @@
*/
/** Viterbi decoder reversed polynomial A */
#define GPS_L2C_V27_POLY_A (0x4F) /* 0b01001111 - reversed 0171*/
#define GPS_L5_V27_POLY_A (0x4F) /* 0b01001111 - reversed 0171*/
/** Viterbi decoder reversed polynomial B */
#define GPS_L2C_V27_POLY_B (0x6D) /* 0b01101101 - reversed 0133 */
#define GPS_L5_V27_POLY_B (0x6D) /* 0b01101101 - reversed 0133 */
/*
* GPS L2C message constants.
*/
@ -67,7 +69,7 @@
/** GPS LC2 CNAV CRC length in bits */
#define GPS_CNAV_MSG_CRC_LENGTH (24)
/** GPS L2C CNAV message payload length in bits */
#define GPS_CNAV_MSG_DATA_LENGTH (GPS_CNAV_MSG_LENGTH-GPS_CNAV_MSG_CRC_LENGTH)
#define GPS_CNAV_MSG_DATA_LENGTH (GPS_CNAV_MSG_LENGTH - GPS_CNAV_MSG_CRC_LENGTH)
/** GPS L2C CNAV message lock detector threshold */
#define GPS_CNAV_LOCK_MAX_CRC_FAILS (10)

View File

@ -49,12 +49,16 @@
/** Size of the Viterbi decoder history. */
#define GPS_L2_V27_HISTORY_LENGTH_BITS 64
#define GPS_L5_V27_HISTORY_LENGTH_BITS 64
/** Bits to accumulate before decoding starts. */
#define GPS_L2C_V27_INIT_BITS (32)
#define GPS_L5_V27_INIT_BITS (32)
/** Bits to decode at a time. */
#define GPS_L2C_V27_DECODE_BITS (32)
#define GPS_L5_V27_DECODE_BITS (32)
/** Bits in decoder tail. We ignore them. */
#define GPS_L2C_V27_DELAY_BITS (32)
#define GPS_L5_V27_DELAY_BITS (32)
/**
* GPS CNAV message container.
*
@ -69,6 +73,15 @@ typedef struct
u8 raw_msg[GPS_L2C_V27_DECODE_BITS + GPS_L2C_V27_DELAY_BITS]; /**< RAW MSG for GNSS-SDR */
} cnav_msg_t;
typedef struct
{
u8 prn; /**< SV PRN. 0..31 */
u8 msg_id; /**< Message id. 0..31 */
u32 tow; /**< GPS ToW in 6-second units. Multiply to 6 to get seconds. */
bool alert; /**< CNAV message alert flag */
u8 raw_msg[GPS_L5_V27_DECODE_BITS + GPS_L5_V27_DELAY_BITS]; /**< RAW MSG for GNSS-SDR */
} cnav_L5_msg_t;
/**
* GPS CNAV decoder component.
* This component controls symbol decoding string.
@ -96,6 +109,27 @@ typedef struct {
* do not produce output. */
} cnav_v27_part_t;
typedef struct {
v27_t dec; /**< Viterbi block decoder object */
v27_decision_t decisions[GPS_L5_V27_HISTORY_LENGTH_BITS];
/**< Decision graph */
unsigned char symbols[(GPS_L5_V27_INIT_BITS + GPS_L5_V27_DECODE_BITS) * 2];
/**< Symbol buffer */
size_t n_symbols; /**< Count of symbols in the symbol buffer */
unsigned char decoded[GPS_L5_V27_DECODE_BITS + GPS_L5_V27_DELAY_BITS];
/**< Decode buffer */
size_t n_decoded; /**< Number of bits in the decode buffer */
bool preamble_seen; /**< When true, the decode buffer is aligned on
* preamble. */
bool invert; /**< When true, indicates the bits are inverted */
bool message_lock; /**< When true, indicates the message boundary
* is found. */
bool crc_ok; /**< Flag that the last message had good CRC */
size_t n_crc_fail; /**< Counter for CRC failures */
bool init; /**< Initial state flag. When true, initial bits
* do not produce output. */
} cnav_L5_v27_part_t;
/**
* GPS CNAV message lock and decoder object.
*

View File

@ -88,6 +88,7 @@
#include "gps_l2_m_dll_pll_tracking.h"
#include "gps_l1_ca_telemetry_decoder.h"
#include "gps_l2c_telemetry_decoder.h"
#include "gps_l5_telemetry_decoder.h"
#include "galileo_e1b_telemetry_decoder.h"
#include "galileo_e5a_telemetry_decoder.h"
#include "sbas_l1_telemetry_decoder.h"
@ -1094,6 +1095,12 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("GPS_L5_Telemetry_Decoder") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new GpsL5TelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1B_Telemetry_Decoder") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1BTelemetryDecoder(configuration.get(), role, in_streams,
@ -1368,6 +1375,12 @@ std::unique_ptr<TelemetryDecoderInterface> GNSSBlockFactory::GetTlmBlock(
out_streams));
block = std::move(block_);
}
else if (implementation.compare("GPS_L5_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new GpsL5TelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.