Code cleaning, initializations

This commit is contained in:
Carles Fernandez 2019-07-20 11:13:28 +02:00
parent 03a77b06ea
commit 49e64f94f6
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
21 changed files with 70 additions and 57 deletions

View File

@ -384,7 +384,7 @@ int Rtcm_Printer::init_serial(const std::string& serial_device)
* Opens the serial device and sets the default baud rate for a RTCM transmission (9600,8,N,1) * Opens the serial device and sets the default baud rate for a RTCM transmission (9600,8,N,1)
*/ */
int32_t fd = 0; int32_t fd = 0;
struct termios options; struct termios options{};
int64_t BAUD; int64_t BAUD;
int64_t DATABITS; int64_t DATABITS;
int64_t STOPBITS; int64_t STOPBITS;

View File

@ -101,7 +101,7 @@ private:
std::string implementation_; std::string implementation_;
bool flag_enable_fpga; bool flag_enable_fpga;
uint32_t channel_; uint32_t channel_;
Gnss_Synchro gnss_synchro_; Gnss_Synchro gnss_synchro_{};
Gnss_Signal gnss_signal_; Gnss_Signal gnss_signal_;
bool connected_; bool connected_;
bool repeat_; bool repeat_;

View File

@ -85,7 +85,7 @@ private:
int fifo_items; int fifo_items;
int d_sock_raw; int d_sock_raw;
int d_udp_port; int d_udp_port;
struct sockaddr_in si_me; struct sockaddr_in si_me{};
std::string d_src_device; std::string d_src_device;
std::string d_origin_address; std::string d_origin_address;
int d_udp_payload_size; int d_udp_payload_size;

View File

@ -110,7 +110,7 @@ private:
size_t unread_; size_t unread_;
// lookup for scaling data // lookup for scaling data
boost::array<float, 0xff> lookup_; boost::array<float, 0xff> lookup_{};
// async read callback // async read callback
void handle_read(const boost::system::error_code &ec, void handle_read(const boost::system::error_code &ec,

View File

@ -385,7 +385,7 @@ int beidou_b1i_telemetry_decoder_gs::general_work(int noutput_items __attribute_
auto **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer auto **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer
const auto **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer const auto **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 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 // 1. Copy the current tracking output
current_symbol = in[0][0]; current_symbol = in[0][0];
d_symbol_history.push_back(current_symbol.Prompt_I); // add new symbol to the symbol queue d_symbol_history.push_back(current_symbol.Prompt_I); // add new symbol to the symbol queue

View File

@ -40,17 +40,19 @@
#include <boost/shared_ptr.hpp> // for boost::shared_ptr #include <boost/shared_ptr.hpp> // for boost::shared_ptr
#include <gnuradio/block.h> // for block #include <gnuradio/block.h> // for block
#include <gnuradio/types.h> // for gr_vector_const_void_star #include <gnuradio/types.h> // for gr_vector_const_void_star
#include <array>
#include <cstdint> #include <cstdint>
#include <fstream> #include <fstream>
#include <string> #include <string>
#include <array>
class beidou_b1i_telemetry_decoder_gs; class beidou_b1i_telemetry_decoder_gs;
using beidou_b1i_telemetry_decoder_gs_sptr = boost::shared_ptr<beidou_b1i_telemetry_decoder_gs>; using beidou_b1i_telemetry_decoder_gs_sptr = boost::shared_ptr<beidou_b1i_telemetry_decoder_gs>;
beidou_b1i_telemetry_decoder_gs_sptr beidou_b1i_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); beidou_b1i_telemetry_decoder_gs_sptr beidou_b1i_make_telemetry_decoder_gs(
const Gnss_Satellite &satellite,
bool dump);
/*! /*!
@ -72,8 +74,10 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items); gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
friend beidou_b1i_telemetry_decoder_gs_sptr friend beidou_b1i_telemetry_decoder_gs_sptr beidou_b1i_make_telemetry_decoder_gs(
beidou_b1i_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
beidou_b1i_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); beidou_b1i_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
void decode_subframe(float *symbols); void decode_subframe(float *symbols);

View File

@ -408,7 +408,7 @@ int beidou_b3i_telemetry_decoder_gs::general_work(
auto **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer auto **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer
const auto **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer const auto **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer
Gnss_Synchro current_symbol; // structure to save the synchronization Gnss_Synchro current_symbol{}; // structure to save the synchronization
// information and send the output object to the // information and send the output object to the
// next block // next block
// 1. Copy the current tracking output // 1. Copy the current tracking output

View File

@ -53,7 +53,6 @@ beidou_b3i_telemetry_decoder_gs_sptr beidou_b3i_make_telemetry_decoder_gs(
/*! /*!
* \brief This class implements a block that decodes the BeiDou DNAV data. * \brief This class implements a block that decodes the BeiDou DNAV data.
*
*/ */
class beidou_b3i_telemetry_decoder_gs : public gr::block class beidou_b3i_telemetry_decoder_gs : public gr::block
{ {
@ -71,9 +70,10 @@ public:
gr_vector_void_star &output_items); gr_vector_void_star &output_items);
private: private:
friend beidou_b3i_telemetry_decoder_gs_sptr friend beidou_b3i_telemetry_decoder_gs_sptr beidou_b3i_make_telemetry_decoder_gs(
beidou_b3i_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, const Gnss_Satellite &satellite,
bool dump); bool dump);
beidou_b3i_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); beidou_b3i_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
void decode_subframe(float *symbols); void decode_subframe(float *symbols);

View File

@ -50,7 +50,9 @@ class glonass_l2_ca_telemetry_decoder_gs;
using glonass_l2_ca_telemetry_decoder_gs_sptr = boost::shared_ptr<glonass_l2_ca_telemetry_decoder_gs>; using glonass_l2_ca_telemetry_decoder_gs_sptr = boost::shared_ptr<glonass_l2_ca_telemetry_decoder_gs>;
glonass_l2_ca_telemetry_decoder_gs_sptr glonass_l2_ca_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); glonass_l2_ca_telemetry_decoder_gs_sptr glonass_l2_ca_make_telemetry_decoder_gs(
const Gnss_Satellite &satellite,
bool dump);
/*! /*!
* \brief This class implements a block that decodes the GNAV data defined in GLONASS ICD v5.1 * \brief This class implements a block that decodes the GNAV data defined in GLONASS ICD v5.1
@ -74,8 +76,10 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items); gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
friend glonass_l2_ca_telemetry_decoder_gs_sptr friend glonass_l2_ca_telemetry_decoder_gs_sptr glonass_l2_ca_make_telemetry_decoder_gs(
glonass_l2_ca_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
glonass_l2_ca_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); glonass_l2_ca_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
void decode_string(const double *symbols, int32_t frame_length); void decode_string(const double *symbols, int32_t frame_length);

View File

@ -49,12 +49,12 @@ class gps_l1_ca_telemetry_decoder_gs;
using gps_l1_ca_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l1_ca_telemetry_decoder_gs>; using gps_l1_ca_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l1_ca_telemetry_decoder_gs>;
gps_l1_ca_telemetry_decoder_gs_sptr gps_l1_ca_telemetry_decoder_gs_sptr gps_l1_ca_make_telemetry_decoder_gs(
gps_l1_ca_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
/*! /*!
* \brief This class implements a block that decodes the NAV data defined in IS-GPS-200E * \brief This class implements a block that decodes the NAV data defined in IS-GPS-200E
*
*/ */
class gps_l1_ca_telemetry_decoder_gs : public gr::block class gps_l1_ca_telemetry_decoder_gs : public gr::block
{ {
@ -71,8 +71,9 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items); gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
friend gps_l1_ca_telemetry_decoder_gs_sptr friend gps_l1_ca_telemetry_decoder_gs_sptr gps_l1_ca_make_telemetry_decoder_gs(
gps_l1_ca_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
gps_l1_ca_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); gps_l1_ca_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
bool gps_word_parityCheck(uint32_t gpsword); bool gps_word_parityCheck(uint32_t gpsword);
@ -81,7 +82,7 @@ private:
int32_t d_bits_per_preamble; int32_t d_bits_per_preamble;
int32_t d_samples_per_preamble; int32_t d_samples_per_preamble;
int32_t d_preamble_period_symbols; int32_t d_preamble_period_symbols;
std::array<int32_t, GPS_CA_PREAMBLE_LENGTH_BITS> d_preamble_samples; std::array<int32_t, GPS_CA_PREAMBLE_LENGTH_BITS> d_preamble_samples{};
uint32_t d_required_symbols; uint32_t d_required_symbols;
uint32_t d_frame_length_symbols; uint32_t d_frame_length_symbols;
bool flag_PLL_180_deg_phase_locked; bool flag_PLL_180_deg_phase_locked;

View File

@ -1,7 +1,6 @@
/*! /*!
* \file gps_l2c_telemetry_decoder_gs.cc * \file gps_l2c_telemetry_decoder_gs.cc
* \brief Implementation of a NAV message demodulator block based on * \brief Implementation of a NAV message demodulator block
* Kay Borre book MATLAB-based GPS receiver
* \author Javier Arribas, 2015. jarribas(at)cttc.es * \author Javier Arribas, 2015. jarribas(at)cttc.es
* *
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
@ -60,7 +59,7 @@ gps_l2c_telemetry_decoder_gs::gps_l2c_telemetry_decoder_gs(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)), gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro))) gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{ {
//prevent telemetry symbols accumulation in output buffers // prevent telemetry symbols accumulation in output buffers
this->set_max_noutput_items(1); this->set_max_noutput_items(1);
// Ephemeris data port out // Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry")); this->message_port_register_out(pmt::mp("telemetry"));
@ -68,8 +67,7 @@ gps_l2c_telemetry_decoder_gs::gps_l2c_telemetry_decoder_gs(
this->message_port_register_out(pmt::mp("telemetry_to_trk")); this->message_port_register_out(pmt::mp("telemetry_to_trk"));
d_last_valid_preamble = 0; d_last_valid_preamble = 0;
d_sent_tlm_failed_msg = false; d_sent_tlm_failed_msg = false;
d_max_symbols_without_valid_frame = GPS_L2_CNAV_DATA_PAGE_BITS * GPS_L2_SYMBOLS_PER_BIT * 5; //rise alarm if 5 consecutive subframes have no valid CRC d_max_symbols_without_valid_frame = GPS_L2_CNAV_DATA_PAGE_BITS * GPS_L2_SYMBOLS_PER_BIT * 5; // rise alarm if 5 consecutive subframes have no valid CRC
// initialize internal vars // initialize internal vars
d_dump = dump; d_dump = dump;

View File

@ -1,7 +1,6 @@
/*! /*!
* \file gps_l2c_telemetry_decoder_gs.h * \file gps_l2c_telemetry_decoder_gs.h
* \brief Interface of a CNAV message demodulator block based on * \brief Interface of a CNAV message demodulator block
* Kay Borre book MATLAB-based GPS receiver
* \author Javier Arribas, 2015. jarribas(at)cttc.es * \author Javier Arribas, 2015. jarribas(at)cttc.es
* ------------------------------------------------------------------------- * -------------------------------------------------------------------------
* *
@ -41,7 +40,8 @@
#include <fstream> #include <fstream>
#include <string> #include <string>
extern "C" { extern "C"
{
#include "cnav_msg.h" #include "cnav_msg.h"
} }
@ -50,12 +50,12 @@ class gps_l2c_telemetry_decoder_gs;
using gps_l2c_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l2c_telemetry_decoder_gs>; using gps_l2c_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l2c_telemetry_decoder_gs>;
gps_l2c_telemetry_decoder_gs_sptr gps_l2c_telemetry_decoder_gs_sptr gps_l2c_make_telemetry_decoder_gs(
gps_l2c_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); 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 * \brief This class implements a block that decodes CNAV data defined in IS-GPS-200K
*
*/ */
class gps_l2c_telemetry_decoder_gs : public gr::block class gps_l2c_telemetry_decoder_gs : public gr::block
{ {
@ -64,6 +64,7 @@ public:
void set_satellite(const Gnss_Satellite &satellite); //!< Set satellite PRN void set_satellite(const Gnss_Satellite &satellite); //!< Set satellite PRN
void set_channel(int32_t channel); //!< Set receiver's channel void set_channel(int32_t channel); //!< Set receiver's channel
void reset(); void reset();
/*! /*!
* \brief This is where all signal processing takes place * \brief This is where all signal processing takes place
*/ */
@ -71,8 +72,10 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items); gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
friend gps_l2c_telemetry_decoder_gs_sptr friend gps_l2c_telemetry_decoder_gs_sptr gps_l2c_make_telemetry_decoder_gs(
gps_l2c_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
gps_l2c_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); gps_l2c_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
bool d_dump; bool d_dump;

View File

@ -58,7 +58,7 @@ gps_l5_telemetry_decoder_gs::gps_l5_telemetry_decoder_gs(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)), gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro))) gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{ {
//prevent telemetry symbols accumulation in output buffers // prevent telemetry symbols accumulation in output buffers
this->set_max_noutput_items(1); this->set_max_noutput_items(1);
// Ephemeris data port out // Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry")); this->message_port_register_out(pmt::mp("telemetry"));
@ -66,7 +66,7 @@ gps_l5_telemetry_decoder_gs::gps_l5_telemetry_decoder_gs(
this->message_port_register_out(pmt::mp("telemetry_to_trk")); this->message_port_register_out(pmt::mp("telemetry_to_trk"));
d_last_valid_preamble = 0; d_last_valid_preamble = 0;
d_sent_tlm_failed_msg = false; d_sent_tlm_failed_msg = false;
d_max_symbols_without_valid_frame = GPS_L5_CNAV_DATA_PAGE_BITS * GPS_L5_SYMBOLS_PER_BIT * 10; //rise alarm if 20 consecutive subframes have no valid CRC d_max_symbols_without_valid_frame = GPS_L5_CNAV_DATA_PAGE_BITS * GPS_L5_SYMBOLS_PER_BIT * 10; // rise alarm if 20 consecutive subframes have no valid CRC
// initialize internal vars // initialize internal vars
d_dump = dump; d_dump = dump;
@ -217,7 +217,7 @@ int gps_l5_telemetry_decoder_gs::general_work(int noutput_items __attribute__((u
// \code // \code
// symbolTime_ms = msg->tow * 6000 + *pdelay * 10 + (12 * 10); 12 symbols of the encoder's transitory // symbolTime_ms = msg->tow * 6000 + *pdelay * 10 + (12 * 10); 12 symbols of the encoder's transitory
//check TOW update consistency // check TOW update consistency
uint32_t last_d_TOW_at_current_symbol_ms = d_TOW_at_current_symbol_ms; uint32_t last_d_TOW_at_current_symbol_ms = d_TOW_at_current_symbol_ms;
d_TOW_at_current_symbol_ms = msg.tow * 6000 + (delay + 12) * GPS_L5I_SYMBOL_PERIOD_MS; d_TOW_at_current_symbol_ms = msg.tow * 6000 + (delay + 12) * GPS_L5I_SYMBOL_PERIOD_MS;
if (last_d_TOW_at_current_symbol_ms != 0 and abs(static_cast<int64_t>(d_TOW_at_current_symbol_ms) - int64_t(last_d_TOW_at_current_symbol_ms)) > GPS_L5I_SYMBOL_PERIOD_MS) if (last_d_TOW_at_current_symbol_ms != 0 and abs(static_cast<int64_t>(d_TOW_at_current_symbol_ms) - int64_t(last_d_TOW_at_current_symbol_ms)) > GPS_L5I_SYMBOL_PERIOD_MS)

View File

@ -42,7 +42,8 @@
#include <fstream> #include <fstream>
#include <string> #include <string>
extern "C" { extern "C"
{
#include "cnav_msg.h" #include "cnav_msg.h"
} }
@ -51,8 +52,9 @@ class gps_l5_telemetry_decoder_gs;
using gps_l5_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l5_telemetry_decoder_gs>; using gps_l5_telemetry_decoder_gs_sptr = boost::shared_ptr<gps_l5_telemetry_decoder_gs>;
gps_l5_telemetry_decoder_gs_sptr gps_l5_telemetry_decoder_gs_sptr gps_l5_make_telemetry_decoder_gs(
gps_l5_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
/*! /*!
* \brief This class implements a GPS L5 Telemetry decoder * \brief This class implements a GPS L5 Telemetry decoder
@ -69,8 +71,10 @@ public:
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items); gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private: private:
friend gps_l5_telemetry_decoder_gs_sptr friend gps_l5_telemetry_decoder_gs_sptr gps_l5_make_telemetry_decoder_gs(
gps_l5_make_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); const Gnss_Satellite &satellite,
bool dump);
gps_l5_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump); gps_l5_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
bool d_dump; bool d_dump;

View File

@ -114,10 +114,10 @@ private:
private: private:
int32_t d_n_smpls_in_history; int32_t d_n_smpls_in_history;
double d_iir_par; double d_iir_par;
double d_corr_paired; double d_corr_paired{};
double d_corr_shifted; double d_corr_shifted{};
bool d_aligned; bool d_aligned{};
double d_past_sample; double d_past_sample{};
} d_sample_aligner; } d_sample_aligner;
// helper class for symbol alignment and Viterbi decoding // helper class for symbol alignment and Viterbi decoding

View File

@ -163,7 +163,7 @@ private:
double d_carrier_phase_step_rad; double d_carrier_phase_step_rad;
double d_carrier_phase_rate_step_rad; double d_carrier_phase_rate_step_rad;
boost::circular_buffer<std::pair<double, double>> d_carr_ph_history; boost::circular_buffer<std::pair<double, double>> d_carr_ph_history;
// remaining code phase and carrier phase between tracking loops // remaining code phase and carrier phase between tracking loops
double d_rem_code_phase_samples; double d_rem_code_phase_samples;
float d_rem_carr_phase_rad; float d_rem_carr_phase_rad;

View File

@ -460,8 +460,7 @@ void dll_pll_veml_tracking_fpga::msg_handler_telemetry_to_trk(const pmt::pmt_t &
{ {
DLOG(INFO) << "Telemetry fault received in ch " << this->d_channel; DLOG(INFO) << "Telemetry fault received in ch " << this->d_channel;
gr::thread::scoped_lock lock(d_setlock); gr::thread::scoped_lock lock(d_setlock);
d_carrier_lock_fail_counter = 10000; //force loss-of-lock condition d_carrier_lock_fail_counter = 10000; // force loss-of-lock condition
break;
} }
} }
} }

View File

@ -188,7 +188,7 @@ void Galileo_E1_Tcp_Connector_Tracking_cc::start_tracking()
d_acq_code_phase_samples = d_acquisition_gnss_synchro->Acq_delay_samples; d_acq_code_phase_samples = d_acquisition_gnss_synchro->Acq_delay_samples;
d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz; d_acq_carrier_doppler_hz = d_acquisition_gnss_synchro->Acq_doppler_hz;
d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples; d_acq_sample_stamp = d_acquisition_gnss_synchro->Acq_samplestamp_samples;
std::array<char, 3> Signal_; std::array<char, 3> Signal_{};
std::memcpy(Signal_.data(), d_acquisition_gnss_synchro->Signal, 3); std::memcpy(Signal_.data(), d_acquisition_gnss_synchro->Signal, 3);
// generate local reference ALWAYS starting at chip 1 (2 samples per chip) // generate local reference ALWAYS starting at chip 1 (2 samples per chip)

View File

@ -166,7 +166,7 @@ private:
// Tracking_2nd_PLL_filter d_carrier_loop_filter; // Tracking_2nd_PLL_filter d_carrier_loop_filter;
// acquisition // acquisition
double d_acq_carrier_doppler_step_hz; double d_acq_carrier_doppler_step_hz{};
double d_acq_code_phase_samples; double d_acq_code_phase_samples;
double d_acq_carrier_doppler_hz; double d_acq_carrier_doppler_hz;
// correlator // correlator
@ -184,7 +184,7 @@ private:
double d_carrier_dopplerrate_hz2; double d_carrier_dopplerrate_hz2;
double d_carrier_phase_step_rad; double d_carrier_phase_step_rad;
double d_acc_carrier_phase_rad; double d_acc_carrier_phase_rad;
double d_carr_phase_error_rad; double d_carr_phase_error_rad{};
double d_carr_phase_sigma2; double d_carr_phase_sigma2;
double d_code_phase_samples; double d_code_phase_samples;
double code_error_chips; double code_error_chips;

View File

@ -76,7 +76,7 @@ int Tcp_Communication::listen_tcp_connection(size_t d_port_, size_t d_port_ch0_)
void Tcp_Communication::send_receive_tcp_packet_galileo_e1(boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> buf, Tcp_Packet_Data* tcp_data_) void Tcp_Communication::send_receive_tcp_packet_galileo_e1(boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> buf, Tcp_Packet_Data* tcp_data_)
{ {
int controlc = 0; int controlc = 0;
boost::array<float, NUM_RX_VARIABLES> readbuf; boost::array<float, NUM_RX_VARIABLES> readbuf{};
float d_control_id_ = buf.data()[0]; float d_control_id_ = buf.data()[0];
try try
@ -111,7 +111,7 @@ void Tcp_Communication::send_receive_tcp_packet_galileo_e1(boost::array<float, N
void Tcp_Communication::send_receive_tcp_packet_gps_l1_ca(boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> buf, Tcp_Packet_Data* tcp_data_) void Tcp_Communication::send_receive_tcp_packet_gps_l1_ca(boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> buf, Tcp_Packet_Data* tcp_data_)
{ {
int controlc = 0; int controlc = 0;
boost::array<float, NUM_RX_VARIABLES> readbuf; boost::array<float, NUM_RX_VARIABLES> readbuf{};
float d_control_id_ = buf.data()[0]; float d_control_id_ = buf.data()[0];
try try

View File

@ -64,7 +64,7 @@ private:
channel_status_msg_receiver(); channel_status_msg_receiver();
std::map<int, std::shared_ptr<Gnss_Synchro>> d_channel_status_map; std::map<int, std::shared_ptr<Gnss_Synchro>> d_channel_status_map;
Monitor_Pvt d_pvt_status; Monitor_Pvt d_pvt_status{};
void msg_handler_events(pmt::pmt_t msg); void msg_handler_events(pmt::pmt_t msg);
}; };