Sort header files

This commit is contained in:
Carles Fernandez 2020-06-19 12:39:28 +02:00
parent f6058c6b61
commit 0d5b5894b4
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
17 changed files with 314 additions and 298 deletions

View File

@ -132,20 +132,33 @@ private:
const Pvt_Conf& conf_,
const rtk_t& rtk);
enum StringValue_
void msg_handler_telemetry(const pmt::pmt_t& msg);
void initialize_and_apply_carrier_phase_offset();
void apply_rx_clock_offset(std::map<int, Gnss_Synchro>& observables_map,
double rx_clock_offset_s);
std::map<int, Gnss_Synchro> interpolate_observables(const std::map<int, Gnss_Synchro>& observables_map_t0,
const std::map<int, Gnss_Synchro>& observables_map_t1,
double rx_time_s);
inline std::time_t convert_to_time_t(const boost::posix_time::ptime pt) const
{
evGPS_1C,
evGPS_2S,
evGPS_L5,
evSBAS_1C,
evGAL_1B,
evGAL_5X,
evGLO_1G,
evGLO_2G,
evBDS_B1,
evBDS_B2,
evBDS_B3
};
return (pt - boost::posix_time::ptime(boost::gregorian::date(1970, 1, 1))).total_seconds();
}
std::vector<std::string> split_string(const std::string& s, char delim) const;
typedef struct
{
long mtype; // NOLINT(google-runtime-int) required by SysV queue messaging
double ttff;
} d_ttff_msgbuf;
bool send_sys_v_ttff_msg(d_ttff_msgbuf ttff);
bool save_gnss_synchro_map_xml(const std::string& file_name); // debug helper function
bool load_gnss_synchro_map_xml(const std::string& file_name); // debug helper function
bool d_dump;
bool d_dump_mat;
@ -189,6 +202,9 @@ private:
double d_rinex_version;
double d_rx_time;
key_t d_sysv_msg_key;
int d_sysv_msqid;
std::unique_ptr<Rinex_Printer> d_rp;
std::unique_ptr<Kml_Printer> d_kml_dump;
std::unique_ptr<Gpx_Printer> d_gpx_dump;
@ -210,42 +226,26 @@ private:
std::vector<bool> d_channel_initialized;
std::vector<double> d_initial_carrier_phase_offset_estimation_rads;
enum StringValue_
{
evGPS_1C,
evGPS_2S,
evGPS_L5,
evSBAS_1C,
evGAL_1B,
evGAL_5X,
evGLO_1G,
evGLO_2G,
evBDS_B1,
evBDS_B2,
evBDS_B3
};
std::map<std::string, StringValue_> d_mapStringValues;
std::map<int, Gnss_Synchro> d_gnss_observables_map;
std::map<int, Gnss_Synchro> d_gnss_observables_map_t0;
std::map<int, Gnss_Synchro> d_gnss_observables_map_t1;
std::map<std::string, StringValue_> d_mapStringValues;
boost::posix_time::time_duration d_utc_diff_time;
void msg_handler_telemetry(const pmt::pmt_t& msg);
void initialize_and_apply_carrier_phase_offset();
void apply_rx_clock_offset(std::map<int, Gnss_Synchro>& observables_map,
double rx_clock_offset_s);
std::map<int, Gnss_Synchro> interpolate_observables(const std::map<int, Gnss_Synchro>& observables_map_t0,
const std::map<int, Gnss_Synchro>& observables_map_t1,
double rx_time_s);
inline std::time_t convert_to_time_t(const boost::posix_time::ptime pt) const
{
return (pt - boost::posix_time::ptime(boost::gregorian::date(1970, 1, 1))).total_seconds();
}
std::vector<std::string> split_string(const std::string& s, char delim) const;
key_t d_sysv_msg_key;
int d_sysv_msqid;
typedef struct
{
long mtype; // NOLINT(google-runtime-int) required by SysV queue messaging
double ttff;
} d_ttff_msgbuf;
bool send_sys_v_ttff_msg(d_ttff_msgbuf ttff);
bool save_gnss_synchro_map_xml(const std::string& file_name); // debug helper function
bool load_gnss_synchro_map_xml(const std::string& file_name); // debug helper function
};
#endif // GNSS_SDR_RTKLIB_PVT_GS_H

View File

@ -220,6 +220,20 @@ public:
private:
friend pcps_acquisition_sptr pcps_make_acquisition(const Acq_Conf& conf_);
explicit pcps_acquisition(const Acq_Conf& conf_);
void update_local_carrier(own::span<gr_complex> carrier_vector, float freq);
void update_grid_doppler_wipeoffs();
void update_grid_doppler_wipeoffs_step2();
void acquisition_core(uint64_t samp_count);
void send_negative_acquisition();
void send_positive_acquisition();
void dump_results(int32_t effective_fft_size);
bool is_fdma();
bool start();
void calculate_threshold(void);
float first_vs_second_peak_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
float max_to_input_power_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
bool d_active;
bool d_worker_active;
bool d_cshort;
@ -248,6 +262,9 @@ private:
float d_test_statistics;
float d_doppler_center_step_two;
std::string d_dump_filename;
std::unique_ptr<gr::fft::fft_complex> d_fft_if;
std::unique_ptr<gr::fft::fft_complex> d_ifft;
std::weak_ptr<ChannelFsm> d_channel_fsm;
volk_gnsssdr::vector<volk_gnsssdr::vector<float>> d_magnitude_grid;
volk_gnsssdr::vector<float> d_tmp_buffer;
volk_gnsssdr::vector<std::complex<float>> d_input_signal;
@ -256,25 +273,10 @@ private:
volk_gnsssdr::vector<std::complex<float>> d_fft_codes;
volk_gnsssdr::vector<std::complex<float>> d_data_buffer;
volk_gnsssdr::vector<lv_16sc_t> d_data_buffer_sc;
std::unique_ptr<gr::fft::fft_complex> d_fft_if;
std::unique_ptr<gr::fft::fft_complex> d_ifft;
std::weak_ptr<ChannelFsm> d_channel_fsm;
Acq_Conf d_acq_parameters;
Gnss_Synchro* d_gnss_synchro;
arma::fmat d_grid;
arma::fmat d_narrow_grid;
void update_local_carrier(own::span<gr_complex> carrier_vector, float freq);
void update_grid_doppler_wipeoffs();
void update_grid_doppler_wipeoffs_step2();
void acquisition_core(uint64_t samp_count);
void send_negative_acquisition();
void send_positive_acquisition();
void dump_results(int32_t effective_fft_size);
bool is_fdma();
bool start();
void calculate_threshold(void);
float first_vs_second_peak_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
float max_to_input_power_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
};
#endif // GNSS_SDR_PCPS_ACQUISITION_H

View File

@ -189,6 +189,12 @@ public:
private:
friend pcps_acquisition_fpga_sptr pcps_make_acquisition_fpga(pcpsconf_fpga_t conf_);
explicit pcps_acquisition_fpga(pcpsconf_fpga_t conf_);
void send_negative_acquisition();
void send_positive_acquisition();
void acquisition_core(uint32_t num_doppler_bins, uint32_t doppler_step, int32_t doppler_min);
float first_vs_second_peak_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
bool d_active;
bool d_make_2_steps;
uint32_t d_doppler_index;
@ -211,14 +217,10 @@ private:
float d_test_statistics;
float d_doppler_step2;
float d_doppler_center_step_two;
pcpsconf_fpga_t d_acq_parameters;
Gnss_Synchro* d_gnss_synchro;
std::shared_ptr<Fpga_Acquisition> d_acquisition_fpga;
std::weak_ptr<ChannelFsm> d_channel_fsm;
void send_negative_acquisition();
void send_positive_acquisition();
void acquisition_core(uint32_t num_doppler_bins, uint32_t doppler_step, int32_t doppler_min);
float first_vs_second_peak_statistic(uint32_t& indext, int32_t& doppler, uint32_t num_doppler_bins, int32_t doppler_max, int32_t doppler_step);
pcpsconf_fpga_t d_acq_parameters;
Gnss_Synchro* d_gnss_synchro;
};
#endif // GNSS_SDR_PCPS_ACQUISITION_FPGA_H

View File

@ -103,7 +103,7 @@ Channel::Channel(ConfigurationInterface* configuration, uint32_t channel, std::s
gnss_signal_ = Gnss_Signal(implementation_);
channel_msg_rx = channel_msg_receiver_make_cc(channel_fsm_, repeat_);
channel_msg_rx_ = channel_msg_receiver_make_cc(channel_fsm_, repeat_);
}
@ -126,9 +126,9 @@ void Channel::connect(gr::top_block_sptr top_block)
// Message ports
if (!flag_enable_fpga)
{
top_block->msg_connect(acq_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));
top_block->msg_connect(acq_->get_right_block(), pmt::mp("events"), channel_msg_rx_, pmt::mp("events"));
}
top_block->msg_connect(trk_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));
top_block->msg_connect(trk_->get_right_block(), pmt::mp("events"), channel_msg_rx_, pmt::mp("events"));
connected_ = true;
}
@ -153,9 +153,9 @@ void Channel::disconnect(gr::top_block_sptr top_block)
top_block->msg_disconnect(nav_->get_left_block(), pmt::mp("telemetry_to_trk"), trk_->get_right_block(), pmt::mp("telemetry_to_trk"));
if (!flag_enable_fpga)
{
top_block->msg_disconnect(acq_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));
top_block->msg_disconnect(acq_->get_right_block(), pmt::mp("events"), channel_msg_rx_, pmt::mp("events"));
}
top_block->msg_disconnect(trk_->get_right_block(), pmt::mp("events"), channel_msg_rx, pmt::mp("events"));
top_block->msg_disconnect(trk_->get_right_block(), pmt::mp("events"), channel_msg_rx_, pmt::mp("events"));
connected_ = false;
}
@ -191,7 +191,7 @@ gr::basic_block_sptr Channel::get_right_block()
void Channel::set_signal(const Gnss_Signal& gnss_signal)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
gnss_signal_ = gnss_signal;
std::string str_aux = gnss_signal_.get_signal_str();
gnss_synchro_.Signal[0] = str_aux[0];
@ -210,7 +210,7 @@ void Channel::set_signal(const Gnss_Signal& gnss_signal)
void Channel::stop_channel()
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
bool result = channel_fsm_->Event_stop_channel();
if (!result)
{
@ -229,7 +229,7 @@ void Channel::assist_acquisition_doppler(double Carrier_Doppler_hz)
void Channel::start_acquisition()
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
bool result = false;
if (!flag_enable_fpga)
{

View File

@ -84,21 +84,22 @@ public:
void msg_handler_events(pmt::pmt_t msg);
private:
channel_msg_receiver_cc_sptr channel_msg_rx;
std::shared_ptr<AcquisitionInterface> acq_;
std::shared_ptr<TrackingInterface> trk_;
std::shared_ptr<TelemetryDecoderInterface> nav_;
std::shared_ptr<ChannelFsm> channel_fsm_;
channel_msg_receiver_cc_sptr channel_msg_rx_;
std::string role_;
std::string implementation_;
std::mutex mx_;
bool connected_;
bool repeat_;
bool flag_enable_fpga;
uint32_t channel_;
Gnss_Synchro gnss_synchro_{};
Gnss_Signal gnss_signal_;
bool connected_;
bool repeat_;
std::shared_ptr<ChannelFsm> channel_fsm_;
Concurrent_Queue<pmt::pmt_t>* queue_;
std::mutex mx;
};
#endif // GNSS_SDR_CHANNEL_H

View File

@ -29,7 +29,7 @@ ChannelFsm::ChannelFsm()
acq_ = nullptr;
trk_ = nullptr;
channel_ = 0U;
d_state = 0U;
state_ = 0U;
queue_ = nullptr;
}
@ -38,25 +38,25 @@ ChannelFsm::ChannelFsm(std::shared_ptr<AcquisitionInterface> acquisition) : acq_
{
trk_ = nullptr;
channel_ = 0U;
d_state = 0U;
state_ = 0U;
queue_ = nullptr;
}
bool ChannelFsm::Event_stop_channel()
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
DLOG(INFO) << "CH = " << channel_ << ". Ev stop channel";
switch (d_state)
switch (state_)
{
case 0: // already in stanby
break;
case 1: // acquisition
d_state = 0;
state_ = 0;
stop_acquisition();
break;
case 2: // tracking
d_state = 0;
state_ = 0;
stop_tracking();
break;
default:
@ -68,12 +68,12 @@ bool ChannelFsm::Event_stop_channel()
bool ChannelFsm::Event_start_acquisition_fpga()
{
std::lock_guard<std::mutex> lk(mx);
if ((d_state == 1) || (d_state == 2))
std::lock_guard<std::mutex> lk(mx_);
if ((state_ == 1) || (state_ == 2))
{
return false;
}
d_state = 1;
state_ = 1;
DLOG(INFO) << "CH = " << channel_ << ". Ev start acquisition FPGA";
return true;
}
@ -81,12 +81,12 @@ bool ChannelFsm::Event_start_acquisition_fpga()
bool ChannelFsm::Event_start_acquisition()
{
std::lock_guard<std::mutex> lk(mx);
if ((d_state == 1) || (d_state == 2))
std::lock_guard<std::mutex> lk(mx_);
if ((state_ == 1) || (state_ == 2))
{
return false;
}
d_state = 1;
state_ = 1;
start_acquisition();
DLOG(INFO) << "CH = " << channel_ << ". Ev start acquisition";
return true;
@ -95,12 +95,12 @@ bool ChannelFsm::Event_start_acquisition()
bool ChannelFsm::Event_valid_acquisition()
{
std::lock_guard<std::mutex> lk(mx);
if (d_state != 1)
std::lock_guard<std::mutex> lk(mx_);
if (state_ != 1)
{
return false;
}
d_state = 2;
state_ = 2;
start_tracking();
DLOG(INFO) << "CH = " << channel_ << ". Ev valid acquisition";
return true;
@ -109,12 +109,12 @@ bool ChannelFsm::Event_valid_acquisition()
bool ChannelFsm::Event_failed_acquisition_repeat()
{
std::lock_guard<std::mutex> lk(mx);
if (d_state != 1)
std::lock_guard<std::mutex> lk(mx_);
if (state_ != 1)
{
return false;
}
d_state = 1;
state_ = 1;
start_acquisition();
DLOG(INFO) << "CH = " << channel_ << ". Ev failed acquisition repeat";
return true;
@ -123,12 +123,12 @@ bool ChannelFsm::Event_failed_acquisition_repeat()
bool ChannelFsm::Event_failed_acquisition_no_repeat()
{
std::lock_guard<std::mutex> lk(mx);
if (d_state != 1)
std::lock_guard<std::mutex> lk(mx_);
if (state_ != 1)
{
return false;
}
d_state = 3;
state_ = 3;
request_satellite();
DLOG(INFO) << "CH = " << channel_ << ". Ev failed acquisition no repeat";
return true;
@ -137,12 +137,12 @@ bool ChannelFsm::Event_failed_acquisition_no_repeat()
bool ChannelFsm::Event_failed_tracking_standby()
{
std::lock_guard<std::mutex> lk(mx);
if (d_state != 2)
std::lock_guard<std::mutex> lk(mx_);
if (state_ != 2)
{
return false;
}
d_state = 0U;
state_ = 0U;
notify_stop_tracking();
DLOG(INFO) << "CH = " << channel_ << ". Ev failed tracking standby";
return true;
@ -151,35 +151,35 @@ bool ChannelFsm::Event_failed_tracking_standby()
void ChannelFsm::set_acquisition(std::shared_ptr<AcquisitionInterface> acquisition)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
acq_ = std::move(acquisition);
}
void ChannelFsm::set_tracking(std::shared_ptr<TrackingInterface> tracking)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
trk_ = std::move(tracking);
}
void ChannelFsm::set_telemetry(std::shared_ptr<TelemetryDecoderInterface> telemetry)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
nav_ = std::move(telemetry);
}
void ChannelFsm::set_queue(Concurrent_Queue<pmt::pmt_t>* queue)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
queue_ = queue;
}
void ChannelFsm::set_channel(uint32_t channel)
{
std::lock_guard<std::mutex> lk(mx);
std::lock_guard<std::mutex> lk(mx_);
channel_ = channel;
}

View File

@ -48,6 +48,7 @@ public:
void set_queue(Concurrent_Queue<pmt::pmt_t>* queue);
void set_channel(uint32_t channel);
void start_acquisition();
// FSM EVENTS
bool Event_start_acquisition();
bool Event_start_acquisition_fpga();
@ -64,13 +65,16 @@ private:
void request_satellite();
void notify_stop_tracking();
uint32_t channel_;
uint32_t state_;
std::shared_ptr<AcquisitionInterface> acq_;
std::shared_ptr<TrackingInterface> trk_;
std::shared_ptr<TelemetryDecoderInterface> nav_;
std::mutex mx_;
Concurrent_Queue<pmt::pmt_t>* queue_;
uint32_t channel_;
uint32_t d_state;
std::mutex mx;
};
#endif // GNSS_SDR_CHANNEL_FSM_H

View File

@ -50,9 +50,9 @@ public:
private:
friend channel_msg_receiver_cc_sptr channel_msg_receiver_make_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
channel_msg_receiver_cc(std::shared_ptr<ChannelFsm> channel_fsm, bool repeat);
void msg_handler_events(pmt::pmt_t msg);
std::shared_ptr<ChannelFsm> d_channel_fsm;
bool d_repeat; // todo: change FSM to include repeat value
void msg_handler_events(pmt::pmt_t msg);
};
#endif // GNSS_SDR_CHANNEL_MSG_RECEIVER_CC_H

View File

@ -68,7 +68,23 @@ private:
explicit hybrid_observables_gs(const Obs_Conf& conf_);
Obs_Conf d_conf;
void msg_handler_pvt_to_observables(const pmt::pmt_t& msg);
double compute_T_rx_s(const Gnss_Synchro& a) const;
bool interp_trk_obs(Gnss_Synchro& interpolated_obs, uint32_t ch, uint64_t rx_clock) const;
void update_TOW(const std::vector<Gnss_Synchro>& data);
void compute_pranges(std::vector<Gnss_Synchro>& data) const;
void smooth_pseudoranges(std::vector<Gnss_Synchro>& data);
int32_t save_matfile() const;
bool d_T_rx_TOW_set; // rx time follow GPST
bool d_dump;
bool d_dump_mat;
uint32_t d_T_rx_TOW_ms;
uint32_t d_T_rx_step_ms;
uint32_t d_T_status_report_timer_ms;
uint32_t d_nchannels_in;
uint32_t d_nchannels_out;
double d_smooth_filter_M;
enum StringValue_
{
@ -84,33 +100,21 @@ private:
evBDS_B2,
evBDS_B3
};
bool d_T_rx_TOW_set; // rx time follow GPST
bool d_dump;
bool d_dump_mat;
uint32_t d_T_rx_TOW_ms;
uint32_t d_T_rx_step_ms;
uint32_t d_T_status_report_timer_ms;
uint32_t d_nchannels_in;
uint32_t d_nchannels_out;
double d_smooth_filter_M;
std::map<std::string, StringValue_> d_mapStringValues;
std::vector<bool> d_channel_last_pll_lock;
std::vector<double> d_channel_last_pseudorange_smooth;
std::vector<double> d_channel_last_carrier_phase_rads;
std::string d_dump_filename;
std::ofstream d_dump_file;
std::unique_ptr<Gnss_circular_deque<Gnss_Synchro>> d_gnss_synchro_history; // Tracking observable history
boost::circular_buffer<uint64_t> d_Rx_clock_buffer; // time history
void msg_handler_pvt_to_observables(const pmt::pmt_t& msg);
double compute_T_rx_s(const Gnss_Synchro& a) const;
bool interp_trk_obs(Gnss_Synchro& interpolated_obs, uint32_t ch, uint64_t rx_clock) const;
void update_TOW(const std::vector<Gnss_Synchro>& data);
void compute_pranges(std::vector<Gnss_Synchro>& data) const;
void smooth_pseudoranges(std::vector<Gnss_Synchro>& data);
int32_t save_matfile() const;
std::string d_dump_filename;
std::ofstream d_dump_file;
std::unique_ptr<Gnss_circular_deque<Gnss_Synchro>> d_gnss_synchro_history; // Tracking observable history
boost::circular_buffer<uint64_t> d_Rx_clock_buffer; // time history
Obs_Conf d_conf;
};
#endif // GNSS_SDR_HYBRID_OBSERVABLES_GS_H

View File

@ -78,6 +78,11 @@ private:
galileo_telemetry_decoder_gs(const Gnss_Satellite &satellite, int frame_type, bool dump);
void viterbi_decoder(float *page_part_symbols, int32_t *page_part_bits);
void deinterleaver(int32_t rows, int32_t cols, const float *in, float *out);
void decode_INAV_word(float *page_part_symbols, int32_t frame_length);
void decode_FNAV_word(float *page_symbols, int32_t frame_length);
bool d_sent_tlm_failed_msg;
bool d_flag_frame_sync;
bool d_flag_PLL_180_deg_phase_locked;
@ -130,11 +135,6 @@ private:
// navigation message vars
Galileo_Navigation_Message d_inav_nav;
Galileo_Fnav_Message d_fnav_nav;
void viterbi_decoder(float *page_part_symbols, int32_t *page_part_bits);
void deinterleaver(int32_t rows, int32_t cols, const float *in, float *out);
void decode_INAV_word(float *page_part_symbols, int32_t frame_length);
void decode_FNAV_word(float *page_symbols, int32_t frame_length);
};
#endif // GNSS_SDR_GALILEO_TELEMETRY_DECODER_GS_H

View File

@ -73,6 +73,9 @@ private:
gps_l1_ca_telemetry_decoder_gs(const Gnss_Satellite &satellite, bool dump);
bool gps_word_parityCheck(uint32_t gpsword);
bool decode_subframe();
bool d_flag_frame_sync;
bool d_flag_parity;
bool d_flag_preamble;
@ -108,9 +111,6 @@ private:
Gps_Navigation_Message d_nav;
Gnss_Satellite d_satellite;
bool gps_word_parityCheck(uint32_t gpsword);
bool decode_subframe();
};
#endif // GNSS_SDR_GPS_L1_CA_TELEMETRY_DECODER_GS_H

View File

@ -76,6 +76,18 @@ private:
friend dll_pll_veml_tracking_sptr dll_pll_veml_make_tracking(const Dll_Pll_Conf &conf_);
explicit dll_pll_veml_tracking(const Dll_Pll_Conf &conf_);
void msg_handler_telemetry_to_trk(const pmt::pmt_t &msg);
void do_correlation_step(const gr_complex *input_samples);
void run_dll_pll();
void check_carrier_phase_coherent_initialization();
void update_tracking_vars();
void clear_tracking_vars();
void save_correlation_results();
void log_data();
bool cn0_and_tracking_lock_status(double coh_integration_time_s);
bool acquire_secondary();
int32_t save_matfile();
bool d_pull_in_transitory;
bool d_corrected_doppler;
bool d_interchange_iq;
@ -187,18 +199,6 @@ private:
Tracking_loop_filter d_code_loop_filter;
Tracking_FLL_PLL_filter d_carrier_loop_filter;
void msg_handler_telemetry_to_trk(const pmt::pmt_t &msg);
void do_correlation_step(const gr_complex *input_samples);
void run_dll_pll();
void check_carrier_phase_coherent_initialization();
void update_tracking_vars();
void clear_tracking_vars();
void save_correlation_results();
void log_data();
bool cn0_and_tracking_lock_status(double coh_integration_time_s);
bool acquire_secondary();
int32_t save_matfile();
};
#endif // GNSS_SDR_DLL_PLL_VEML_TRACKING_H

View File

@ -105,6 +105,18 @@ private:
friend dll_pll_veml_tracking_fpga_sptr dll_pll_veml_make_tracking_fpga(const Dll_Pll_Conf_Fpga &conf_);
explicit dll_pll_veml_tracking_fpga(const Dll_Pll_Conf_Fpga &conf_);
void msg_handler_telemetry_to_trk(const pmt::pmt_t &msg);
bool cn0_and_tracking_lock_status(double coh_integration_time_s);
bool acquire_secondary();
void do_correlation_step();
void run_dll_pll();
void check_carrier_phase_coherent_initialization();
void update_tracking_vars();
void clear_tracking_vars();
void save_correlation_results();
void log_data();
int32_t save_matfile();
bool d_veml;
bool d_cloop;
bool d_secondary;
@ -228,18 +240,6 @@ private:
Tracking_loop_filter d_code_loop_filter;
Tracking_FLL_PLL_filter d_carrier_loop_filter;
void msg_handler_telemetry_to_trk(const pmt::pmt_t &msg);
bool cn0_and_tracking_lock_status(double coh_integration_time_s);
bool acquire_secondary();
void do_correlation_step();
void run_dll_pll();
void check_carrier_phase_coherent_initialization();
void update_tracking_vars();
void clear_tracking_vars();
void save_correlation_results();
void log_data();
int32_t save_matfile();
};
#endif // GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H

View File

@ -58,7 +58,6 @@
#include <glog/logging.h> // for LOG
#include <pmt/pmt.h> // for make_any
#include <algorithm> // for find, min
#include <array> // for array
#include <chrono> // for milliseconds
#include <cmath> // for floor, fmod, log
#include <exception> // for exception
@ -94,9 +93,9 @@ ControlThread::ControlThread()
}
ControlThread::ControlThread(const std::shared_ptr<ConfigurationInterface> &configuration)
ControlThread::ControlThread(std::shared_ptr<ConfigurationInterface> configuration)
{
configuration_ = configuration;
configuration_ = std::move(configuration);
delete_configuration_ = false;
restart_ = false;
init();
@ -121,11 +120,11 @@ void ControlThread::init()
stop_ = false;
processed_control_messages_ = 0;
applied_actions_ = 0;
supl_mcc = 0;
supl_mns = 0;
supl_lac = 0;
supl_ci = 0;
msqid = -1;
supl_mcc_ = 0;
supl_mns_ = 0;
supl_lac_ = 0;
supl_ci_ = 0;
msqid_ = -1;
agnss_ref_location_ = Agnss_Ref_Location();
agnss_ref_time_ = Agnss_Ref_Time();
@ -198,9 +197,9 @@ void ControlThread::init()
ControlThread::~ControlThread() // NOLINT(modernize-use-equals-default)
{
if (msqid != -1)
if (msqid_ != -1)
{
msgctl(msqid, IPC_RMID, nullptr);
msgctl(msqid_, IPC_RMID, nullptr);
}
if (sysv_queue_thread_.joinable())
@ -375,14 +374,14 @@ int ControlThread::run()
}
void ControlThread::set_control_queue(const std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue) // NOLINT(performance-unnecessary-value-param)
void ControlThread::set_control_queue(std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue)
{
if (flowgraph_->running())
{
LOG(WARNING) << "Unable to set control queue while flowgraph is running";
return;
}
control_queue_ = control_queue;
control_queue_ = std::move(control_queue);
cmd_interface_.set_msg_queue(control_queue_);
}
@ -395,37 +394,37 @@ bool ControlThread::read_assistance_from_XML()
// return variable (true == succeeded)
bool ret = false;
// getting names from the config file, if available
std::string eph_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_xml", eph_default_xml_filename);
std::string utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_utc_model_xml", utc_default_xml_filename);
std::string iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_iono_xml", iono_default_xml_filename);
std::string gal_iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_iono_xml", gal_iono_default_xml_filename);
std::string ref_time_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_time_xml", ref_time_default_xml_filename);
std::string ref_location_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_location_xml", ref_location_default_xml_filename);
std::string eph_gal_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_ephemeris_xml", eph_gal_default_xml_filename);
std::string eph_cnav_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_cnav_ephemeris_xml", eph_cnav_default_xml_filename);
std::string gal_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_utc_model_xml", gal_utc_default_xml_filename);
std::string cnav_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_cnav_utc_model_xml", cnav_utc_default_xml_filename);
std::string eph_glo_xml_filename = configuration_->property("GNSS-SDR.SUPL_glo_ephemeris_xml", eph_glo_gnav_default_xml_filename);
std::string glo_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_glo_utc_model_xml", glo_utc_default_xml_filename);
std::string gal_almanac_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_almanac_xml", gal_almanac_default_xml_filename);
std::string gps_almanac_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_almanac_xml", gps_almanac_default_xml_filename);
std::string eph_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_xml", eph_default_xml_filename_);
std::string utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_utc_model_xml", utc_default_xml_filename_);
std::string iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_iono_xml", iono_default_xml_filename_);
std::string gal_iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_iono_xml", gal_iono_default_xml_filename_);
std::string ref_time_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_time_xml", ref_time_default_xml_filename_);
std::string ref_location_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_location_xml", ref_location_default_xml_filename_);
std::string eph_gal_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_ephemeris_xml", eph_gal_default_xml_filename_);
std::string eph_cnav_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_cnav_ephemeris_xml", eph_cnav_default_xml_filename_);
std::string gal_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_utc_model_xml", gal_utc_default_xml_filename_);
std::string cnav_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_cnav_utc_model_xml", cnav_utc_default_xml_filename_);
std::string eph_glo_xml_filename = configuration_->property("GNSS-SDR.SUPL_glo_ephemeris_xml", eph_glo_gnav_default_xml_filename_);
std::string glo_utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_glo_utc_model_xml", glo_utc_default_xml_filename_);
std::string gal_almanac_xml_filename = configuration_->property("GNSS-SDR.SUPL_gal_almanac_xml", gal_almanac_default_xml_filename_);
std::string gps_almanac_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_almanac_xml", gps_almanac_default_xml_filename_);
if (configuration_->property("GNSS-SDR.AGNSS_XML_enabled", false) == true)
{
eph_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ephemeris_xml", eph_default_xml_filename);
utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_utc_model_xml", utc_default_xml_filename);
iono_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_iono_xml", iono_default_xml_filename);
gal_iono_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_iono_xml", gal_iono_default_xml_filename);
ref_time_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ref_time_xml", ref_time_default_xml_filename);
ref_location_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ref_location_xml", ref_location_default_xml_filename);
eph_gal_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_ephemeris_xml", eph_gal_default_xml_filename);
eph_cnav_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_cnav_ephemeris_xml", eph_cnav_default_xml_filename);
gal_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_utc_model_xml", gal_utc_default_xml_filename);
cnav_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_cnav_utc_model_xml", cnav_utc_default_xml_filename);
eph_glo_xml_filename = configuration_->property("GNSS-SDR.AGNSS_glo_ephemeris_xml", eph_glo_gnav_default_xml_filename);
glo_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_glo_utc_model_xml", glo_utc_default_xml_filename);
gal_almanac_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_almanac_xml", gal_almanac_default_xml_filename);
gps_almanac_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_almanac_xml", gps_almanac_default_xml_filename);
eph_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ephemeris_xml", eph_default_xml_filename_);
utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_utc_model_xml", utc_default_xml_filename_);
iono_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_iono_xml", iono_default_xml_filename_);
gal_iono_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_iono_xml", gal_iono_default_xml_filename_);
ref_time_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ref_time_xml", ref_time_default_xml_filename_);
ref_location_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_ref_location_xml", ref_location_default_xml_filename_);
eph_gal_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_ephemeris_xml", eph_gal_default_xml_filename_);
eph_cnav_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_cnav_ephemeris_xml", eph_cnav_default_xml_filename_);
gal_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_utc_model_xml", gal_utc_default_xml_filename_);
cnav_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_cnav_utc_model_xml", cnav_utc_default_xml_filename_);
eph_glo_xml_filename = configuration_->property("GNSS-SDR.AGNSS_glo_ephemeris_xml", eph_glo_gnav_default_xml_filename_);
glo_utc_xml_filename = configuration_->property("GNSS-SDR.AGNSS_glo_utc_model_xml", glo_utc_default_xml_filename_);
gal_almanac_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gal_almanac_xml", gal_almanac_default_xml_filename_);
gps_almanac_xml_filename = configuration_->property("GNSS-SDR.AGNSS_gps_almanac_xml", gps_almanac_default_xml_filename_);
}
std::cout << "Trying to read GNSS ephemeris from XML file(s)..." << std::endl;
@ -628,8 +627,8 @@ void ControlThread::assist_GNSS()
supl_client_acquisition_.server_name = configuration_->property("GNSS-SDR.SUPL_gps_acquisition_server", default_eph_server);
supl_client_ephemeris_.server_port = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_port", 7275);
supl_client_acquisition_.server_port = configuration_->property("GNSS-SDR.SUPL_gps_acquisition_port", 7275);
supl_mcc = configuration_->property("GNSS-SDR.SUPL_MCC", 244);
supl_mns = configuration_->property("GNSS-SDR.SUPL_MNC ", 5);
supl_mcc_ = configuration_->property("GNSS-SDR.SUPL_MCC", 244);
supl_mns_ = configuration_->property("GNSS-SDR.SUPL_MNC ", 5);
std::string default_lac = "0x59e2";
std::string default_ci = "0x31b0";
@ -637,31 +636,31 @@ void ControlThread::assist_GNSS()
std::string supl_ci_s = configuration_->property("GNSS-SDR.SUPL_CI", default_ci);
try
{
supl_lac = std::stoi(supl_lac_s, nullptr, 0);
supl_lac_ = std::stoi(supl_lac_s, nullptr, 0);
}
catch (const std::invalid_argument &ia)
{
std::cerr << "Invalid argument for SUPL LAC: " << ia.what() << '\n';
supl_lac = -1;
supl_lac_ = -1;
}
try
{
supl_ci = std::stoi(supl_ci_s, nullptr, 0);
supl_ci_ = std::stoi(supl_ci_s, nullptr, 0);
}
catch (const std::invalid_argument &ia)
{
std::cerr << "Invalid argument for SUPL CI: " << ia.what() << '\n';
supl_ci = -1;
supl_ci_ = -1;
}
if (supl_lac < 0 or supl_lac > 65535)
if (supl_lac_ < 0 or supl_lac_ > 65535)
{
supl_lac = 0x59e2;
supl_lac_ = 0x59e2;
}
if (supl_ci < 0 or supl_ci > 268435455) // 2^16 for GSM and CDMA, 2^28 for UMTS and LTE networks
if (supl_ci_ < 0 or supl_ci_ > 268435455) // 2^16 for GSM and CDMA, 2^28 for UMTS and LTE networks
{
supl_ci = 0x31b0;
supl_ci_ = 0x31b0;
}
bool SUPL_read_gps_assistance_xml = configuration_->property("GNSS-SDR.SUPL_read_gps_assistance_xml", false);
@ -680,7 +679,7 @@ void ControlThread::assist_GNSS()
int error;
supl_client_ephemeris_.request = 1;
std::cout << "SUPL: Try to read GPS ephemeris data from SUPL server..." << std::endl;
error = supl_client_ephemeris_.get_assistance(supl_mcc, supl_mns, supl_lac, supl_ci);
error = supl_client_ephemeris_.get_assistance(supl_mcc_, supl_mns_, supl_lac_, supl_ci_);
if (error == 0)
{
std::map<int, Gps_Ephemeris>::const_iterator gps_eph_iter;
@ -693,7 +692,7 @@ void ControlThread::assist_GNSS()
flowgraph_->send_telemetry_msg(pmt::make_any(tmp_obj));
}
// Save ephemeris to XML file
std::string eph_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_xml", eph_default_xml_filename);
std::string eph_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_xml", eph_default_xml_filename_);
if (supl_client_ephemeris_.save_ephemeris_map_xml(eph_xml_filename, supl_client_ephemeris_.gps_ephemeris_map) == true)
{
std::cout << "SUPL: XML ephemeris data file created" << std::endl;
@ -717,7 +716,7 @@ void ControlThread::assist_GNSS()
// Request almanac, IONO and UTC Model data
supl_client_ephemeris_.request = 0;
std::cout << "SUPL: Try to read Almanac, Iono, Utc Model, Ref Time and Ref Location data from SUPL server..." << std::endl;
error = supl_client_ephemeris_.get_assistance(supl_mcc, supl_mns, supl_lac, supl_ci);
error = supl_client_ephemeris_.get_assistance(supl_mcc_, supl_mns_, supl_lac_, supl_ci_);
if (error == 0)
{
std::map<int, Gps_Almanac>::const_iterator gps_alm_iter;
@ -743,7 +742,7 @@ void ControlThread::assist_GNSS()
flowgraph_->send_telemetry_msg(pmt::make_any(tmp_obj));
}
// Save iono and UTC model data to xml file
std::string iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_iono_xml", iono_default_xml_filename);
std::string iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_iono_xml", iono_default_xml_filename_);
if (supl_client_ephemeris_.save_iono_xml(iono_xml_filename, supl_client_ephemeris_.gps_iono) == true)
{
std::cout << "SUPL: Iono data file created" << std::endl;
@ -752,7 +751,7 @@ void ControlThread::assist_GNSS()
{
std::cout << "SUPL: Failed to create Iono data file" << std::endl;
}
std::string utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_utc_model_xml", utc_default_xml_filename);
std::string utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_utc_model_xml", utc_default_xml_filename_);
if (supl_client_ephemeris_.save_utc_xml(utc_xml_filename, supl_client_ephemeris_.gps_utc) == true)
{
std::cout << "SUPL: UTC model data file created" << std::endl;
@ -771,7 +770,7 @@ void ControlThread::assist_GNSS()
// Request acquisition assistance
supl_client_acquisition_.request = 2;
std::cout << "SUPL: Try to read acquisition assistance data from SUPL server..." << std::endl;
error = supl_client_acquisition_.get_assistance(supl_mcc, supl_mns, supl_lac, supl_ci);
error = supl_client_acquisition_.get_assistance(supl_mcc_, supl_mns_, supl_lac_, supl_ci_);
if (error == 0)
{
std::map<int, Gps_Acq_Assist>::const_iterator gps_acq_iter;
@ -1100,7 +1099,7 @@ void ControlThread::sysv_queue_listener()
key_t key = 1102;
if ((msqid = msgget(key, 0644 | IPC_CREAT)) == -1)
if ((msqid_ = msgget(key, 0644 | IPC_CREAT)) == -1)
{
perror("GNSS-SDR cannot create SysV message queues");
exit(1);
@ -1108,7 +1107,7 @@ void ControlThread::sysv_queue_listener()
while (read_queue && !stop_)
{
if (msgrcv(msqid, &msg, msgrcv_size, 1, 0) != -1)
if (msgrcv(msqid_, &msg, msgrcv_size, 1, 0) != -1)
{
received_message = msg.stop_message;
if ((std::abs(received_message - (-200.0)) < 10 * std::numeric_limits<double>::epsilon()))

View File

@ -66,7 +66,7 @@ public:
*
* \param[in] configuration Pointer to a ConfigurationInterface
*/
explicit ControlThread(const std::shared_ptr<ConfigurationInterface> &configuration);
explicit ControlThread(std::shared_ptr<ConfigurationInterface> configuration);
/*!
* \brief Destructor
@ -92,7 +92,7 @@ public:
*
* \param[in] std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue
*/
void set_control_queue(const std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue); // NOLINT(performance-unnecessary-value-param)
void set_control_queue(std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue);
unsigned int processed_control_messages() const
{
@ -115,28 +115,15 @@ public:
}
private:
// Telecommand TCP interface
TcpCmdInterface cmd_interface_;
void telecommand_listener();
void init();
void apply_action(unsigned int what);
/*
* New receiver event dispatcher
*/
bool receiver_on_standby_;
void event_dispatcher(bool &valid_event, pmt::pmt_t &msg);
std::thread cmd_interface_thread_;
// SUPL assistance classes
Gnss_Sdr_Supl_Client supl_client_acquisition_;
Gnss_Sdr_Supl_Client supl_client_ephemeris_;
int supl_mcc; // Current network MCC (Mobile country code), 3 digits.
int supl_mns; // Current network MNC (Mobile Network code), 2 or 3 digits.
int supl_lac; // Current network LAC (Location area code),16 bits, 1-65520 are valid values.
int supl_ci; // Cell Identity (16 bits, 0-65535 are valid values).
void init();
// Read {ephemeris, iono, utc, ref loc, ref time} assistance from a local XML file previously recorded
bool read_assistance_from_XML();
@ -156,40 +143,53 @@ private:
*/
void assist_GNSS();
void apply_action(unsigned int what);
void telecommand_listener();
void keyboard_listener();
void sysv_queue_listener();
std::thread cmd_interface_thread_;
std::thread keyboard_thread_;
std::thread sysv_queue_thread_;
std::thread gps_acq_assist_data_collector_thread_;
std::shared_ptr<GNSSFlowgraph> flowgraph_;
std::shared_ptr<ConfigurationInterface> configuration_;
std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> control_queue_;
bool receiver_on_standby_;
bool pre_2009_file_; // to override the system time to postprocess old gnss records and avoid wrong week rollover
bool stop_;
bool restart_;
bool delete_configuration_;
unsigned int processed_control_messages_;
unsigned int applied_actions_;
std::thread keyboard_thread_;
std::thread sysv_queue_thread_;
std::thread gps_acq_assist_data_collector_thread_;
void keyboard_listener();
void sysv_queue_listener();
int msqid;
int msqid_;
// default filename for assistance data
const std::string eph_default_xml_filename = "./gps_ephemeris.xml";
const std::string utc_default_xml_filename = "./gps_utc_model.xml";
const std::string iono_default_xml_filename = "./gps_iono.xml";
const std::string ref_time_default_xml_filename = "./gps_ref_time.xml";
const std::string ref_location_default_xml_filename = "./gps_ref_location.xml";
const std::string eph_gal_default_xml_filename = "./gal_ephemeris.xml";
const std::string eph_cnav_default_xml_filename = "./gps_cnav_ephemeris.xml";
const std::string gal_iono_default_xml_filename = "./gal_iono.xml";
const std::string gal_utc_default_xml_filename = "./gal_utc_model.xml";
const std::string cnav_utc_default_xml_filename = "./gps_cnav_utc_model.xml";
const std::string eph_glo_gnav_default_xml_filename = "./glo_gnav_ephemeris.xml";
const std::string glo_utc_default_xml_filename = "./glo_utc_model.xml";
const std::string gal_almanac_default_xml_filename = "./gal_almanac.xml";
const std::string gps_almanac_default_xml_filename = "./gps_almanac.xml";
const std::string eph_default_xml_filename_ = "./gps_ephemeris.xml";
const std::string utc_default_xml_filename_ = "./gps_utc_model.xml";
const std::string iono_default_xml_filename_ = "./gps_iono.xml";
const std::string ref_time_default_xml_filename_ = "./gps_ref_time.xml";
const std::string ref_location_default_xml_filename_ = "./gps_ref_location.xml";
const std::string eph_gal_default_xml_filename_ = "./gal_ephemeris.xml";
const std::string eph_cnav_default_xml_filename_ = "./gps_cnav_ephemeris.xml";
const std::string gal_iono_default_xml_filename_ = "./gal_iono.xml";
const std::string gal_utc_default_xml_filename_ = "./gal_utc_model.xml";
const std::string cnav_utc_default_xml_filename_ = "./gps_cnav_utc_model.xml";
const std::string eph_glo_gnav_default_xml_filename_ = "./glo_gnav_ephemeris.xml";
const std::string glo_utc_default_xml_filename_ = "./glo_utc_model.xml";
const std::string gal_almanac_default_xml_filename_ = "./gal_almanac.xml";
const std::string gps_almanac_default_xml_filename_ = "./gps_almanac.xml";
TcpCmdInterface cmd_interface_;
// SUPL assistance classes
Gnss_Sdr_Supl_Client supl_client_acquisition_;
Gnss_Sdr_Supl_Client supl_client_ephemeris_;
int supl_mcc_; // Current network MCC (Mobile country code), 3 digits.
int supl_mns_; // Current network MNC (Mobile Network code), 2 or 3 digits.
int supl_lac_; // Current network LAC (Location area code),16 bits, 1-65520 are valid values.
int supl_ci_; // Cell Identity (16 bits, 0-65535 are valid values).
Agnss_Ref_Location agnss_ref_location_;
Agnss_Ref_Time agnss_ref_time_;

View File

@ -296,9 +296,9 @@ void GNSSFlowgraph::connect()
throw(std::invalid_argument("Set GNSS-SDR.internal_fs_sps in configuration"));
}
int observable_interval_ms = static_cast<double>(configuration_->property("GNSS-SDR.observable_interval_ms", 20));
ch_out_sample_counter = gnss_sdr_make_sample_counter(fs, observable_interval_ms, sig_conditioner_.at(0)->get_right_block()->output_signature()->sizeof_stream_item(0));
top_block_->connect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter, 0);
top_block_->connect(ch_out_sample_counter, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
ch_out_sample_counter_ = gnss_sdr_make_sample_counter(fs, observable_interval_ms, sig_conditioner_.at(0)->get_right_block()->output_signature()->sizeof_stream_item(0));
top_block_->connect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter_, 0);
top_block_->connect(ch_out_sample_counter_, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
}
catch (const std::exception& e)
{
@ -321,8 +321,8 @@ void GNSSFlowgraph::connect()
throw(std::invalid_argument("Set GNSS-SDR.internal_fs_sps in configuration"));
}
int observable_interval_ms = static_cast<double>(configuration_->property("GNSS-SDR.observable_interval_ms", 20));
ch_out_fpga_sample_counter = gnss_sdr_make_fpga_sample_counter(fs, observable_interval_ms);
top_block_->connect(ch_out_fpga_sample_counter, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
ch_out_fpga_sample_counter_ = gnss_sdr_make_fpga_sample_counter(fs, observable_interval_ms);
top_block_->connect(ch_out_fpga_sample_counter_, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
}
catch (const std::exception& e)
{
@ -346,9 +346,9 @@ void GNSSFlowgraph::connect()
}
int observable_interval_ms = static_cast<double>(configuration_->property("GNSS-SDR.observable_interval_ms", 20));
ch_out_sample_counter = gnss_sdr_make_sample_counter(fs, observable_interval_ms, sig_conditioner_.at(0)->get_right_block()->output_signature()->sizeof_stream_item(0));
top_block_->connect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter, 0);
top_block_->connect(ch_out_sample_counter, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
ch_out_sample_counter_ = gnss_sdr_make_sample_counter(fs, observable_interval_ms, sig_conditioner_.at(0)->get_right_block()->output_signature()->sizeof_stream_item(0));
top_block_->connect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter_, 0);
top_block_->connect(ch_out_sample_counter_, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
}
catch (const std::exception& e)
{
@ -862,8 +862,8 @@ void GNSSFlowgraph::disconnect()
// disconnect the sample counter to Observables
try
{
top_block_->disconnect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter, 0);
top_block_->disconnect(ch_out_sample_counter, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
top_block_->disconnect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter_, 0);
top_block_->disconnect(ch_out_sample_counter_, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
}
catch (const std::exception& e)
{
@ -877,7 +877,7 @@ void GNSSFlowgraph::disconnect()
{
try
{
top_block_->disconnect(ch_out_fpga_sample_counter, 0, observables_->get_left_block(), channels_count_);
top_block_->disconnect(ch_out_fpga_sample_counter_, 0, observables_->get_left_block(), channels_count_);
}
catch (const std::exception& e)
{
@ -892,8 +892,8 @@ void GNSSFlowgraph::disconnect()
// disconnect the sample counter to Observables
try
{
top_block_->disconnect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter, 0);
top_block_->disconnect(ch_out_sample_counter, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
top_block_->disconnect(sig_conditioner_.at(0)->get_right_block(), 0, ch_out_sample_counter_, 0);
top_block_->disconnect(ch_out_sample_counter_, 0, observables_->get_left_block(), channels_count_); // extra port for the sample counter pulse
}
catch (const std::exception& e)
{
@ -1284,7 +1284,7 @@ void GNSSFlowgraph::acquisition_manager(unsigned int who)
void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
{
// todo: the acquisition events are initiated from the acquisition success or failure queued msg. If the acquisition is disabled for non-assisted secondary freq channels, the engine stops..
std::lock_guard<std::mutex> lock(signal_list_mutex);
std::lock_guard<std::mutex> lock(signal_list_mutex_);
DLOG(INFO) << "Received " << what << " from " << who;
unsigned int sat = 0;
Gnss_Signal gs;
@ -1861,7 +1861,7 @@ void GNSSFlowgraph::set_signals_list()
void GNSSFlowgraph::set_channels_state()
{
std::lock_guard<std::mutex> lock(signal_list_mutex);
std::lock_guard<std::mutex> lock(signal_list_mutex_);
max_acq_channels_ = configuration_->property("Channels.in_acquisition", channels_count_);
if (max_acq_channels_ > channels_count_)
{

View File

@ -62,7 +62,7 @@ public:
/*!
* \brief Constructor that initializes the receiver flow graph
*/
GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue); // NOLINT(performance-unnecessary-value-param)
GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue);
/*!
* \brief Destructor
@ -173,32 +173,29 @@ private:
double project_doppler(const std::string& searched_signal, double primary_freq_doppler_hz);
bool is_multiband() const;
std::vector<std::string> split_string(const std::string& s, char delim);
bool connected_;
bool running_;
bool multiband_;
bool enable_monitor_;
int sources_count_;
unsigned int channels_count_;
unsigned int acq_channels_count_;
unsigned int max_acq_channels_;
std::string config_file_;
std::shared_ptr<ConfigurationInterface> configuration_;
std::mutex signal_list_mutex_;
std::vector<std::shared_ptr<GNSSBlockInterface>> sig_source_;
std::vector<std::shared_ptr<GNSSBlockInterface>> sig_conditioner_;
std::vector<gr::blocks::null_sink::sptr> null_sinks_;
std::shared_ptr<GNSSBlockInterface> observables_;
std::shared_ptr<GNSSBlockInterface> pvt_;
std::map<std::string, gr::basic_block_sptr> acq_resamplers_;
std::vector<std::shared_ptr<ChannelInterface>> channels_;
gnss_sdr_sample_counter_sptr ch_out_sample_counter;
#if ENABLE_FPGA
gnss_sdr_fpga_sample_counter_sptr ch_out_fpga_sample_counter;
#endif
gr::top_block_sptr top_block_;
std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue_;
std::vector<unsigned int> channels_state_;
std::list<Gnss_Signal> available_GPS_1C_signals_;
std::list<Gnss_Signal> available_GPS_2S_signals_;
@ -210,6 +207,7 @@ private:
std::list<Gnss_Signal> available_GLO_2G_signals_;
std::list<Gnss_Signal> available_BDS_B1_signals_;
std::list<Gnss_Signal> available_BDS_B3_signals_;
enum StringValue
{
evGPS_1C,
@ -224,14 +222,20 @@ private:
evBDS_B3
};
std::map<std::string, StringValue> mapStringValues_;
std::map<std::string, gr::basic_block_sptr> acq_resamplers_;
std::vector<unsigned int> channels_state_;
channel_status_msg_receiver_sptr channels_status_; // class that receives and stores the current status of the receiver channels
std::mutex signal_list_mutex;
std::shared_ptr<ConfigurationInterface> configuration_;
std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue_;
std::shared_ptr<GNSSBlockInterface> observables_;
std::shared_ptr<GNSSBlockInterface> pvt_;
bool enable_monitor_;
gr::top_block_sptr top_block_;
gr::basic_block_sptr GnssSynchroMonitor_;
std::vector<std::string> split_string(const std::string& s, char delim);
channel_status_msg_receiver_sptr channels_status_; // class that receives and stores the current status of the receiver channels
gnss_sdr_sample_counter_sptr ch_out_sample_counter_;
#if ENABLE_FPGA
gnss_sdr_fpga_sample_counter_sptr ch_out_fpga_sample_counter_;
#endif
};
#endif // GNSS_SDR_GNSS_FLOWGRAPH_H