1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-08-29 17:07:58 +00:00

Improve constructors

Prefer initialization to assignment in constructors

Improves the readability of the code and performance

Easier detection of unused members

(see https://github.com/isocpp/CppCoreGuidelines/blob/master/CppCoreGuidelines.md\#Rc-initialize\)
This commit is contained in:
Carles Fernandez
2021-10-10 18:54:42 +02:00
parent 8cd13e7ccb
commit 446b7cfbea
25 changed files with 397 additions and 400 deletions

View File

@@ -109,38 +109,96 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
const Pvt_Conf& conf_, const Pvt_Conf& conf_,
const rtk_t& rtk) : gr::sync_block("rtklib_pvt_gs", const rtk_t& rtk) : gr::sync_block("rtklib_pvt_gs",
gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)), gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)),
gr::io_signature::make(0, 0, 0)) gr::io_signature::make(0, 0, 0)),
d_dump_filename(conf_.dump_filename),
d_gps_ephemeris_sptr_type_hash_code(typeid(std::shared_ptr<Gps_Ephemeris>).hash_code()),
d_gps_iono_sptr_type_hash_code(typeid(std::shared_ptr<Gps_Iono>).hash_code()),
d_gps_utc_model_sptr_type_hash_code(typeid(std::shared_ptr<Gps_Utc_Model>).hash_code()),
d_gps_cnav_ephemeris_sptr_type_hash_code(typeid(std::shared_ptr<Gps_CNAV_Ephemeris>).hash_code()),
d_gps_cnav_iono_sptr_type_hash_code(typeid(std::shared_ptr<Gps_CNAV_Iono>).hash_code()),
d_gps_cnav_utc_model_sptr_type_hash_code(typeid(std::shared_ptr<Gps_CNAV_Utc_Model>).hash_code()),
d_gps_almanac_sptr_type_hash_code(typeid(std::shared_ptr<Gps_Almanac>).hash_code()),
d_galileo_ephemeris_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_Ephemeris>).hash_code()),
d_galileo_iono_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_Iono>).hash_code()),
d_galileo_utc_model_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_Utc_Model>).hash_code()),
d_galileo_almanac_helper_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_Almanac_Helper>).hash_code()),
d_galileo_almanac_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_Almanac>).hash_code()),
d_glonass_gnav_ephemeris_sptr_type_hash_code(typeid(std::shared_ptr<Glonass_Gnav_Ephemeris>).hash_code()),
d_glonass_gnav_utc_model_sptr_type_hash_code(typeid(std::shared_ptr<Glonass_Gnav_Utc_Model>).hash_code()),
d_glonass_gnav_almanac_sptr_type_hash_code(typeid(std::shared_ptr<Glonass_Gnav_Almanac>).hash_code()),
d_beidou_dnav_ephemeris_sptr_type_hash_code(typeid(std::shared_ptr<Beidou_Dnav_Ephemeris>).hash_code()),
d_beidou_dnav_iono_sptr_type_hash_code(typeid(std::shared_ptr<Beidou_Dnav_Iono>).hash_code()),
d_beidou_dnav_utc_model_sptr_type_hash_code(typeid(std::shared_ptr<Beidou_Dnav_Utc_Model>).hash_code()),
d_beidou_dnav_almanac_sptr_type_hash_code(typeid(std::shared_ptr<Beidou_Dnav_Almanac>).hash_code()),
d_galileo_has_data_sptr_type_hash_code(typeid(std::shared_ptr<Galileo_HAS_data>).hash_code()),
d_rinex_version(conf_.rinex_version),
d_rx_time(0.0),
d_rinexobs_rate_ms(conf_.rinexobs_rate_ms),
d_kml_rate_ms(conf_.kml_rate_ms),
d_gpx_rate_ms(conf_.gpx_rate_ms),
d_geojson_rate_ms(conf_.geojson_rate_ms),
d_nmea_rate_ms(conf_.nmea_rate_ms),
d_an_rate_ms(conf_.an_rate_ms),
d_output_rate_ms(conf_.output_rate_ms),
d_display_rate_ms(conf_.display_rate_ms),
d_report_rate_ms(1000),
d_max_obs_block_rx_clock_offset_ms(conf_.max_obs_block_rx_clock_offset_ms),
d_nchannels(nchannels),
d_type_of_rx(conf_.type_of_receiver),
d_observable_interval_ms(conf_.observable_interval_ms),
d_dump(conf_.dump),
d_dump_mat(conf_.dump_mat && conf_.dump),
d_rinex_output_enabled(conf_.rinex_output_enabled),
d_geojson_output_enabled(conf_.geojson_output_enabled),
d_gpx_output_enabled(conf_.gpx_output_enabled),
d_kml_output_enabled(conf_.kml_output_enabled),
d_nmea_output_file_enabled(conf_.nmea_output_file_enabled || conf_.flag_nmea_tty_port),
d_xml_storage(conf_.xml_output_enabled),
d_flag_monitor_pvt_enabled(conf_.monitor_enabled),
d_flag_monitor_ephemeris_enabled(conf_.monitor_ephemeris_enabled),
d_show_local_time_zone(conf_.show_local_time_zone),
d_waiting_obs_block_rx_clock_offset_correction_msg(false),
d_enable_rx_clock_correction(conf_.enable_rx_clock_correction),
d_an_printer_enabled(conf_.an_output_enabled)
{ {
// Send feedback message to observables block with the receiver clock offset // Send feedback message to observables block with the receiver clock offset
this->message_port_register_out(pmt::mp("pvt_to_observables")); this->message_port_register_out(pmt::mp("pvt_to_observables"));
// Send PVT status to gnss_flowgraph // Send PVT status to gnss_flowgraph
this->message_port_register_out(pmt::mp("status")); this->message_port_register_out(pmt::mp("status"));
d_mapStringValues["1C"] = evGPS_1C; // GPS Ephemeris data message port in
d_mapStringValues["2S"] = evGPS_2S; this->message_port_register_in(pmt::mp("telemetry"));
d_mapStringValues["L5"] = evGPS_L5; this->set_msg_handler(pmt::mp("telemetry"),
d_mapStringValues["1B"] = evGAL_1B; #if HAS_GENERIC_LAMBDA
d_mapStringValues["5X"] = evGAL_5X; [this](auto&& PH1) { msg_handler_telemetry(PH1); });
d_mapStringValues["E6"] = evGAL_E6; #else
d_mapStringValues["7X"] = evGAL_7X; #if USE_BOOST_BIND_PLACEHOLDERS
d_mapStringValues["1G"] = evGLO_1G; boost::bind(&rtklib_pvt_gs::msg_handler_telemetry, this, boost::placeholders::_1));
d_mapStringValues["2G"] = evGLO_2G; #else
d_mapStringValues["B1"] = evBDS_B1; boost::bind(&rtklib_pvt_gs::msg_handler_telemetry, this, _1));
d_mapStringValues["B2"] = evBDS_B2; #endif
d_mapStringValues["B3"] = evBDS_B3; #endif
// Galileo E6 HAS messages port in
this->message_port_register_in(pmt::mp("E6_HAS_to_PVT"));
this->set_msg_handler(pmt::mp("E6_HAS_to_PVT"),
#if HAS_GENERIC_LAMBDA
[this](auto&& PH1) { msg_handler_has_data(PH1); });
#else
#if USE_BOOST_BIND_PLACEHOLDERS
boost::bind(&rtklib_pvt_gs::msg_handler_has_data, this, boost::placeholders::_1));
#else
boost::bind(&rtklib_pvt_gs::msg_handler_has_data, this, _1));
#endif
#endif
d_initial_carrier_phase_offset_estimation_rads = std::vector<double>(nchannels, 0.0); d_initial_carrier_phase_offset_estimation_rads = std::vector<double>(nchannels, 0.0);
d_channel_initialized = std::vector<bool>(nchannels, false); d_channel_initialized = std::vector<bool>(nchannels, false);
d_max_obs_block_rx_clock_offset_ms = conf_.max_obs_block_rx_clock_offset_ms;
d_output_rate_ms = conf_.output_rate_ms;
d_display_rate_ms = conf_.display_rate_ms;
d_report_rate_ms = 1000; // report every second PVT to gnss_synchro
d_dump = conf_.dump;
d_dump_mat = conf_.dump_mat && d_dump;
d_dump_filename = conf_.dump_filename;
std::string dump_ls_pvt_filename = conf_.dump_filename; std::string dump_ls_pvt_filename = conf_.dump_filename;
if (d_dump) if (d_dump)
{ {
std::string dump_path; std::string dump_path;
@@ -174,41 +232,8 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
} }
d_nchannels = nchannels;
d_type_of_rx = conf_.type_of_receiver;
d_observable_interval_ms = conf_.observable_interval_ms;
// GPS Ephemeris data message port in
this->message_port_register_in(pmt::mp("telemetry"));
this->set_msg_handler(pmt::mp("telemetry"),
#if HAS_GENERIC_LAMBDA
[this](auto&& PH1) { msg_handler_telemetry(PH1); });
#else
#if USE_BOOST_BIND_PLACEHOLDERS
boost::bind(&rtklib_pvt_gs::msg_handler_telemetry, this, boost::placeholders::_1));
#else
boost::bind(&rtklib_pvt_gs::msg_handler_telemetry, this, _1));
#endif
#endif
// Galileo E6 HAS messages port in
this->message_port_register_in(pmt::mp("E6_HAS_to_PVT"));
this->set_msg_handler(pmt::mp("E6_HAS_to_PVT"),
#if HAS_GENERIC_LAMBDA
[this](auto&& PH1) { msg_handler_has_data(PH1); });
#else
#if USE_BOOST_BIND_PLACEHOLDERS
boost::bind(&rtklib_pvt_gs::msg_handler_has_data, this, boost::placeholders::_1));
#else
boost::bind(&rtklib_pvt_gs::msg_handler_has_data, this, _1));
#endif
#endif
// initialize kml_printer // initialize kml_printer
const std::string kml_dump_filename = d_dump_filename; const std::string kml_dump_filename = d_dump_filename;
d_kml_output_enabled = conf_.kml_output_enabled;
d_kml_rate_ms = conf_.kml_rate_ms;
if (d_kml_rate_ms == 0) if (d_kml_rate_ms == 0)
{ {
d_kml_output_enabled = false; d_kml_output_enabled = false;
@@ -225,8 +250,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
// initialize gpx_printer // initialize gpx_printer
const std::string gpx_dump_filename = d_dump_filename; const std::string gpx_dump_filename = d_dump_filename;
d_gpx_output_enabled = conf_.gpx_output_enabled;
d_gpx_rate_ms = conf_.gpx_rate_ms;
if (d_gpx_rate_ms == 0) if (d_gpx_rate_ms == 0)
{ {
d_gpx_output_enabled = false; d_gpx_output_enabled = false;
@@ -243,8 +266,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
// initialize geojson_printer // initialize geojson_printer
const std::string geojson_dump_filename = d_dump_filename; const std::string geojson_dump_filename = d_dump_filename;
d_geojson_output_enabled = conf_.geojson_output_enabled;
d_geojson_rate_ms = conf_.geojson_rate_ms;
if (d_geojson_rate_ms == 0) if (d_geojson_rate_ms == 0)
{ {
d_geojson_output_enabled = false; d_geojson_output_enabled = false;
@@ -260,8 +281,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
// initialize nmea_printer // initialize nmea_printer
d_nmea_output_file_enabled = (conf_.nmea_output_file_enabled || conf_.flag_nmea_tty_port);
d_nmea_rate_ms = conf_.nmea_rate_ms;
if (d_nmea_rate_ms == 0) if (d_nmea_rate_ms == 0)
{ {
d_nmea_output_file_enabled = false; d_nmea_output_file_enabled = false;
@@ -348,8 +367,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
// initialize RINEX printer // initialize RINEX printer
d_rinex_output_enabled = conf_.rinex_output_enabled;
d_rinex_version = conf_.rinex_version;
if (d_rinex_output_enabled) if (d_rinex_output_enabled)
{ {
d_rp = std::make_unique<Rinex_Printer>(d_rinex_version, conf_.rinex_output_path, conf_.rinex_name); d_rp = std::make_unique<Rinex_Printer>(d_rinex_version, conf_.rinex_output_path, conf_.rinex_name);
@@ -359,10 +376,8 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
{ {
d_rp = nullptr; d_rp = nullptr;
} }
d_rinexobs_rate_ms = conf_.rinexobs_rate_ms;
// XML printer // XML printer
d_xml_storage = conf_.xml_output_enabled;
if (d_xml_storage) if (d_xml_storage)
{ {
d_xml_base_path = conf_.xml_output_path; d_xml_base_path = conf_.xml_output_path;
@@ -409,12 +424,7 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
d_has_simple_printer = nullptr; d_has_simple_printer = nullptr;
} }
d_rx_time = 0.0;
d_last_status_print_seg = 0;
// Initialize AN printer // Initialize AN printer
d_an_printer_enabled = conf_.an_output_enabled;
d_an_rate_ms = conf_.an_rate_ms;
if (d_an_printer_enabled) if (d_an_printer_enabled)
{ {
d_an_printer = std::make_unique<An_Packet_Printer>(conf_.an_dump_devname); d_an_printer = std::make_unique<An_Packet_Printer>(conf_.an_dump_devname);
@@ -425,7 +435,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
// PVT MONITOR // PVT MONITOR
d_flag_monitor_pvt_enabled = conf_.monitor_enabled;
if (d_flag_monitor_pvt_enabled) if (d_flag_monitor_pvt_enabled)
{ {
std::string address_string = conf_.udp_addresses; std::string address_string = conf_.udp_addresses;
@@ -441,7 +450,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
// EPHEMERIS MONITOR // EPHEMERIS MONITOR
d_flag_monitor_ephemeris_enabled = conf_.monitor_ephemeris_enabled;
if (d_flag_monitor_ephemeris_enabled) if (d_flag_monitor_ephemeris_enabled)
{ {
std::string address_string = conf_.udp_eph_addresses; std::string address_string = conf_.udp_eph_addresses;
@@ -467,7 +475,6 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
} }
// Display time in local time zone // Display time in local time zone
d_show_local_time_zone = conf_.show_local_time_zone;
std::ostringstream os; std::ostringstream os;
#ifdef HAS_PUT_TIME #ifdef HAS_PUT_TIME
time_t when = std::time(nullptr); time_t when = std::time(nullptr);
@@ -503,54 +510,42 @@ rtklib_pvt_gs::rtklib_pvt_gs(uint32_t nchannels,
d_local_time_str = std::string(" ") + time_zone_abrv + " (UTC " + utc_diff_str.substr(0, 3) + ":" + utc_diff_str.substr(3, 2) + ")"; d_local_time_str = std::string(" ") + time_zone_abrv + " (UTC " + utc_diff_str.substr(0, 3) + ":" + utc_diff_str.substr(3, 2) + ")";
} }
d_waiting_obs_block_rx_clock_offset_correction_msg = false;
d_enable_rx_clock_correction = conf_.enable_rx_clock_correction;
if (d_enable_rx_clock_correction == true) if (d_enable_rx_clock_correction == true)
{ {
// setup two PVT solvers: internal solver for rx clock and user solver // setup two PVT solvers: internal solver for rx clock and user solver
// user PVT solver // user PVT solver
d_user_pvt_solver = std::make_shared<Rtklib_Solver>(rtk, static_cast<int32_t>(nchannels), dump_ls_pvt_filename, d_dump, d_dump_mat); d_user_pvt_solver = std::make_shared<Rtklib_Solver>(rtk, dump_ls_pvt_filename, d_dump, d_dump_mat);
d_user_pvt_solver->set_averaging_depth(1); d_user_pvt_solver->set_averaging_depth(1);
d_user_pvt_solver->set_pre_2009_file(conf_.pre_2009_file); d_user_pvt_solver->set_pre_2009_file(conf_.pre_2009_file);
// internal PVT solver, mainly used to estimate the receiver clock // internal PVT solver, mainly used to estimate the receiver clock
rtk_t internal_rtk = rtk; rtk_t internal_rtk = rtk;
internal_rtk.opt.mode = PMODE_SINGLE; // use single positioning mode in internal PVT solver internal_rtk.opt.mode = PMODE_SINGLE; // use single positioning mode in internal PVT solver
d_internal_pvt_solver = std::make_shared<Rtklib_Solver>(internal_rtk, static_cast<int32_t>(nchannels), dump_ls_pvt_filename, false, false); d_internal_pvt_solver = std::make_shared<Rtklib_Solver>(internal_rtk, dump_ls_pvt_filename, false, false);
d_internal_pvt_solver->set_averaging_depth(1); d_internal_pvt_solver->set_averaging_depth(1);
d_internal_pvt_solver->set_pre_2009_file(conf_.pre_2009_file); d_internal_pvt_solver->set_pre_2009_file(conf_.pre_2009_file);
} }
else else
{ {
// only one solver, customized by the user options // only one solver, customized by the user options
d_internal_pvt_solver = std::make_shared<Rtklib_Solver>(rtk, static_cast<int32_t>(nchannels), dump_ls_pvt_filename, d_dump, d_dump_mat); d_internal_pvt_solver = std::make_shared<Rtklib_Solver>(rtk, dump_ls_pvt_filename, d_dump, d_dump_mat);
d_internal_pvt_solver->set_averaging_depth(1); d_internal_pvt_solver->set_averaging_depth(1);
d_internal_pvt_solver->set_pre_2009_file(conf_.pre_2009_file); d_internal_pvt_solver->set_pre_2009_file(conf_.pre_2009_file);
d_user_pvt_solver = d_internal_pvt_solver; d_user_pvt_solver = d_internal_pvt_solver;
} }
d_gps_ephemeris_sptr_type_hash_code = typeid(std::shared_ptr<Gps_Ephemeris>).hash_code(); d_mapStringValues["1C"] = evGPS_1C;
d_gps_iono_sptr_type_hash_code = typeid(std::shared_ptr<Gps_Iono>).hash_code(); d_mapStringValues["2S"] = evGPS_2S;
d_gps_utc_model_sptr_type_hash_code = typeid(std::shared_ptr<Gps_Utc_Model>).hash_code(); d_mapStringValues["L5"] = evGPS_L5;
d_gps_cnav_ephemeris_sptr_type_hash_code = typeid(std::shared_ptr<Gps_CNAV_Ephemeris>).hash_code(); d_mapStringValues["1B"] = evGAL_1B;
d_gps_cnav_iono_sptr_type_hash_code = typeid(std::shared_ptr<Gps_CNAV_Iono>).hash_code(); d_mapStringValues["5X"] = evGAL_5X;
d_gps_cnav_utc_model_sptr_type_hash_code = typeid(std::shared_ptr<Gps_CNAV_Utc_Model>).hash_code(); d_mapStringValues["E6"] = evGAL_E6;
d_gps_almanac_sptr_type_hash_code = typeid(std::shared_ptr<Gps_Almanac>).hash_code(); d_mapStringValues["7X"] = evGAL_7X;
d_galileo_ephemeris_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_Ephemeris>).hash_code(); d_mapStringValues["1G"] = evGLO_1G;
d_galileo_iono_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_Iono>).hash_code(); d_mapStringValues["2G"] = evGLO_2G;
d_galileo_utc_model_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_Utc_Model>).hash_code(); d_mapStringValues["B1"] = evBDS_B1;
d_galileo_almanac_helper_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_Almanac_Helper>).hash_code(); d_mapStringValues["B2"] = evBDS_B2;
d_galileo_almanac_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_Almanac>).hash_code(); d_mapStringValues["B3"] = evBDS_B3;
d_glonass_gnav_ephemeris_sptr_type_hash_code = typeid(std::shared_ptr<Glonass_Gnav_Ephemeris>).hash_code();
d_glonass_gnav_utc_model_sptr_type_hash_code = typeid(std::shared_ptr<Glonass_Gnav_Utc_Model>).hash_code();
d_glonass_gnav_almanac_sptr_type_hash_code = typeid(std::shared_ptr<Glonass_Gnav_Almanac>).hash_code();
d_beidou_dnav_ephemeris_sptr_type_hash_code = typeid(std::shared_ptr<Beidou_Dnav_Ephemeris>).hash_code();
d_beidou_dnav_iono_sptr_type_hash_code = typeid(std::shared_ptr<Beidou_Dnav_Iono>).hash_code();
d_beidou_dnav_utc_model_sptr_type_hash_code = typeid(std::shared_ptr<Beidou_Dnav_Utc_Model>).hash_code();
d_beidou_dnav_almanac_sptr_type_hash_code = typeid(std::shared_ptr<Beidou_Dnav_Almanac>).hash_code();
d_galileo_has_data_sptr_type_hash_code = typeid(std::shared_ptr<Galileo_HAS_data>).hash_code();
// set the RTKLIB trace (debug) level // set the RTKLIB trace (debug) level
tracelevel(conf_.rtk_trace_level); tracelevel(conf_.rtk_trace_level);

View File

@@ -250,7 +250,6 @@ private:
int32_t d_geojson_rate_ms; int32_t d_geojson_rate_ms;
int32_t d_nmea_rate_ms; int32_t d_nmea_rate_ms;
int32_t d_an_rate_ms; int32_t d_an_rate_ms;
int32_t d_last_status_print_seg; // for status printer
int32_t d_output_rate_ms; int32_t d_output_rate_ms;
int32_t d_display_rate_ms; int32_t d_display_rate_ms;
int32_t d_report_rate_ms; int32_t d_report_rate_ms;

View File

@@ -30,11 +30,9 @@
#include <unistd.h> // for write(), read(), close() #include <unistd.h> // for write(), read(), close()
An_Packet_Printer::An_Packet_Printer(const std::string& an_dump_devname) An_Packet_Printer::An_Packet_Printer(const std::string& an_dump_devname) : d_an_devname(an_dump_devname),
d_an_dev_descriptor(init_serial(d_an_devname))
{ {
d_an_devname = an_dump_devname;
d_an_dev_descriptor = init_serial(d_an_devname);
if (d_an_dev_descriptor != -1) if (d_an_dev_descriptor != -1)
{ {
DLOG(INFO) << "AN Printer writing on " << d_an_devname; DLOG(INFO) << "AN Printer writing on " << d_an_devname;
@@ -192,44 +190,42 @@ void An_Packet_Printer::update_sdr_gnss_packet(sdr_gnss_packet_t* _packet, const
*/ */
void An_Packet_Printer::encode_sdr_gnss_packet(sdr_gnss_packet_t* sdr_gnss_packet, an_packet_t* _packet) const void An_Packet_Printer::encode_sdr_gnss_packet(sdr_gnss_packet_t* sdr_gnss_packet, an_packet_t* _packet) const
{ {
if (_packet != nullptr) _packet->id = SDR_GNSS_PACKET_ID;
_packet->length = SDR_GNSS_PACKET_LENGTH;
uint8_t offset = 0;
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->nsvfix), offset, _packet->data, sizeof(sdr_gnss_packet->nsvfix));
offset += sizeof(sdr_gnss_packet->nsvfix);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->gps_satellites), offset, _packet->data, sizeof(sdr_gnss_packet->gps_satellites));
offset += sizeof(sdr_gnss_packet->gps_satellites);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->galileo_satellites), offset, _packet->data, sizeof(sdr_gnss_packet->galileo_satellites));
offset += sizeof(sdr_gnss_packet->galileo_satellites);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->microseconds), offset, _packet->data, sizeof(sdr_gnss_packet->microseconds));
offset += sizeof(sdr_gnss_packet->microseconds);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->latitude), offset, _packet->data, sizeof(sdr_gnss_packet->latitude));
offset += sizeof(sdr_gnss_packet->latitude);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->longitude), offset, _packet->data, sizeof(sdr_gnss_packet->longitude));
offset += sizeof(sdr_gnss_packet->longitude);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->height), offset, _packet->data, sizeof(sdr_gnss_packet->height));
offset += sizeof(sdr_gnss_packet->height);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[0]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[0]));
offset += sizeof(sdr_gnss_packet->velocity[0]);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[1]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[1]));
offset += sizeof(sdr_gnss_packet->velocity[1]);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[2]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[2]));
offset += sizeof(sdr_gnss_packet->velocity[2]);
for (auto& sat : sdr_gnss_packet->sats)
{ {
_packet->id = SDR_GNSS_PACKET_ID; LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.prn), offset, _packet->data, sizeof(sat.prn));
_packet->length = SDR_GNSS_PACKET_LENGTH; offset += sizeof(sat.prn);
uint8_t offset = 0; LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.snr), offset, _packet->data, sizeof(sat.snr));
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->nsvfix), offset, _packet->data, sizeof(sdr_gnss_packet->nsvfix)); offset += sizeof(sat.snr);
offset += sizeof(sdr_gnss_packet->nsvfix); LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.doppler), offset, _packet->data, sizeof(sat.doppler));
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->gps_satellites), offset, _packet->data, sizeof(sdr_gnss_packet->gps_satellites)); offset += sizeof(sat.doppler);
offset += sizeof(sdr_gnss_packet->gps_satellites);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->galileo_satellites), offset, _packet->data, sizeof(sdr_gnss_packet->galileo_satellites));
offset += sizeof(sdr_gnss_packet->galileo_satellites);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->microseconds), offset, _packet->data, sizeof(sdr_gnss_packet->microseconds));
offset += sizeof(sdr_gnss_packet->microseconds);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->latitude), offset, _packet->data, sizeof(sdr_gnss_packet->latitude));
offset += sizeof(sdr_gnss_packet->latitude);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->longitude), offset, _packet->data, sizeof(sdr_gnss_packet->longitude));
offset += sizeof(sdr_gnss_packet->longitude);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->height), offset, _packet->data, sizeof(sdr_gnss_packet->height));
offset += sizeof(sdr_gnss_packet->height);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[0]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[0]));
offset += sizeof(sdr_gnss_packet->velocity[0]);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[1]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[1]));
offset += sizeof(sdr_gnss_packet->velocity[1]);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->velocity[2]), offset, _packet->data, sizeof(sdr_gnss_packet->velocity[2]));
offset += sizeof(sdr_gnss_packet->velocity[2]);
for (auto& sat : sdr_gnss_packet->sats)
{
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.prn), offset, _packet->data, sizeof(sat.prn));
offset += sizeof(sat.prn);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.snr), offset, _packet->data, sizeof(sat.snr));
offset += sizeof(sat.snr);
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sat.doppler), offset, _packet->data, sizeof(sat.doppler));
offset += sizeof(sat.doppler);
}
offset = static_cast<uint8_t>(SDR_GNSS_PACKET_LENGTH - sizeof(sdr_gnss_packet->status));
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->status), offset, _packet->data, sizeof(sdr_gnss_packet->status));
} }
offset = static_cast<uint8_t>(SDR_GNSS_PACKET_LENGTH - sizeof(sdr_gnss_packet->status));
LSB_bytes_to_array(reinterpret_cast<uint8_t*>(&sdr_gnss_packet->status), offset, _packet->data, sizeof(sdr_gnss_packet->status));
an_packet_encode(_packet); an_packet_encode(_packet);
} }

View File

@@ -35,7 +35,7 @@
class Rtklib_Solver; class Rtklib_Solver;
typedef struct struct sdr_gnss_packet_t
{ {
uint8_t nsvfix; // number of sats used in PVT fix uint8_t nsvfix; // number of sats used in PVT fix
uint8_t gps_satellites; // number of tracked GPS satellites uint8_t gps_satellites; // number of tracked GPS satellites
@@ -53,18 +53,18 @@ typedef struct
int16_t doppler; // in [Hz], saturates at +32767 / -32768 Hz int16_t doppler; // in [Hz], saturates at +32767 / -32768 Hz
} sats[6]; } sats[6];
uint32_t reserved = 0; uint32_t reserved;
uint16_t status; uint16_t status;
} sdr_gnss_packet_t; };
typedef struct struct an_packet_t
{ {
uint8_t id; uint8_t id;
uint8_t length; uint8_t length;
uint8_t header[5]; // AN_PACKET_HEADER_SIZE uint8_t header[5]; // AN_PACKET_HEADER_SIZE
uint8_t data[126]; // AN_MAXIMUM_PACKET_SIZE uint8_t data[126]; // AN_MAXIMUM_PACKET_SIZE
} an_packet_t; };
/*! /*!

View File

@@ -28,10 +28,9 @@
#include <sstream> // for stringstream #include <sstream> // for stringstream
GeoJSON_Printer::GeoJSON_Printer(const std::string& base_path) GeoJSON_Printer::GeoJSON_Printer(const std::string& base_path) : geojson_base_path(base_path),
first_pos(true)
{ {
first_pos = true;
geojson_base_path = base_path;
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());
const fs::path p(geojson_base_path); const fs::path p(geojson_base_path);
if (!fs::exists(p)) if (!fs::exists(p))

View File

@@ -28,11 +28,10 @@
#include <sstream> // for stringstream #include <sstream> // for stringstream
Gpx_Printer::Gpx_Printer(const std::string& base_path) Gpx_Printer::Gpx_Printer(const std::string& base_path) : indent(" "),
gpx_base_path(base_path),
positions_printed(false)
{ {
positions_printed = false;
indent = " ";
gpx_base_path = base_path;
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());
const fs::path p(gpx_base_path); const fs::path p(gpx_base_path);
if (!fs::exists(p)) if (!fs::exists(p))

View File

@@ -33,10 +33,12 @@
#include <sstream> // for std::stringstream #include <sstream> // for std::stringstream
Has_Simple_Printer::Has_Simple_Printer(const std::string& base_path, const std::string& filename, bool time_tag_name) Has_Simple_Printer::Has_Simple_Printer(const std::string& base_path,
const std::string& filename,
bool time_tag_name) : d_has_base_path(base_path),
d_data_printed(false)
{ {
d_data_printed = false;
d_has_base_path = base_path;
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());
const fs::path p(d_has_base_path); const fs::path p(d_has_base_path);
if (!fs::exists(p)) if (!fs::exists(p))

View File

@@ -30,11 +30,10 @@
#include <sys/types.h> // for mode_t #include <sys/types.h> // for mode_t
Kml_Printer::Kml_Printer(const std::string& base_path) Kml_Printer::Kml_Printer(const std::string& base_path) : positions_printed(false),
indent(" "),
kml_base_path(base_path)
{ {
positions_printed = false;
indent = " ";
kml_base_path = base_path;
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());
const fs::path p(kml_base_path); const fs::path p(kml_base_path);
if (!fs::exists(p)) if (!fs::exists(p))

View File

@@ -21,15 +21,16 @@
#include <sstream> #include <sstream>
Monitor_Ephemeris_Udp_Sink::Monitor_Ephemeris_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port, bool protobuf_enabled) : socket{io_context} Monitor_Ephemeris_Udp_Sink::Monitor_Ephemeris_Udp_Sink(const std::vector<std::string>& addresses,
const uint16_t& port,
bool protobuf_enabled) : socket{io_context},
use_protobuf(protobuf_enabled)
{ {
for (const auto& address : addresses) for (const auto& address : addresses)
{ {
boost::asio::ip::udp::endpoint endpoint(boost::asio::ip::address::from_string(address, error), port); boost::asio::ip::udp::endpoint endpoint(boost::asio::ip::address::from_string(address, error), port);
endpoints.push_back(endpoint); endpoints.push_back(endpoint);
} }
use_protobuf = protobuf_enabled;
if (use_protobuf) if (use_protobuf)
{ {
serdes_gal = Serdes_Galileo_Eph(); serdes_gal = Serdes_Galileo_Eph();

View File

@@ -21,7 +21,10 @@
#include <sstream> #include <sstream>
Monitor_Pvt_Udp_Sink::Monitor_Pvt_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port, bool protobuf_enabled) : socket{io_context} Monitor_Pvt_Udp_Sink::Monitor_Pvt_Udp_Sink(const std::vector<std::string>& addresses,
const uint16_t& port,
bool protobuf_enabled) : socket{io_context},
use_protobuf(protobuf_enabled)
{ {
for (const auto& address : addresses) for (const auto& address : addresses)
{ {
@@ -29,7 +32,6 @@ Monitor_Pvt_Udp_Sink::Monitor_Pvt_Udp_Sink(const std::vector<std::string>& addre
endpoints.push_back(endpoint); endpoints.push_back(endpoint);
} }
use_protobuf = protobuf_enabled;
if (use_protobuf) if (use_protobuf)
{ {
serdes = Serdes_Monitor_Pvt(); serdes = Serdes_Monitor_Pvt();

View File

@@ -33,10 +33,13 @@
#include <utility> #include <utility>
Nmea_Printer::Nmea_Printer(const std::string& filename, bool flag_nmea_output_file, bool flag_nmea_tty_port, std::string nmea_dump_devname, const std::string& base_path) Nmea_Printer::Nmea_Printer(const std::string& filename,
bool flag_nmea_output_file,
bool flag_nmea_tty_port,
std::string nmea_dump_devname,
const std::string& base_path) : nmea_base_path(base_path),
d_flag_nmea_output_file(flag_nmea_output_file)
{ {
nmea_base_path = base_path;
d_flag_nmea_output_file = flag_nmea_output_file;
if (d_flag_nmea_output_file == true) if (d_flag_nmea_output_file == true)
{ {
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());

View File

@@ -22,23 +22,23 @@
#include <cstddef> #include <cstddef>
Pvt_Solution::Pvt_Solution() Pvt_Solution::Pvt_Solution() : d_latitude_d(0.0),
d_longitude_d(0.0),
d_height_m(0.0),
d_rx_dt_s(0.0),
d_rx_clock_drift_ppm(0.0),
d_speed_over_ground_m_s(0.0),
d_course_over_ground_d(0.0),
d_avg_latitude_d(0.0),
d_avg_longitude_d(0.0),
d_avg_height_m(0.0),
d_averaging_depth(0),
d_valid_observations(false),
d_pre_2009_file(false),
d_valid_position(false),
d_flag_averaging(false)
{ {
d_latitude_d = 0.0;
d_longitude_d = 0.0;
d_height_m = 0.0;
d_speed_over_ground_m_s = 0.0;
d_course_over_ground_d = 0.0;
d_avg_latitude_d = 0.0;
d_avg_longitude_d = 0.0;
d_avg_height_m = 0.0;
d_flag_averaging = false;
b_valid_position = false;
d_averaging_depth = 0;
d_valid_observations = 0;
d_rx_dt_s = 0.0;
d_rx_clock_drift_ppm = 0.0;
d_pre_2009_file = false; // disabled by default
} }
@@ -130,7 +130,7 @@ void Pvt_Solution::perform_pos_averaging()
d_avg_latitude_d = d_avg_latitude_d / static_cast<double>(d_averaging_depth); d_avg_latitude_d = d_avg_latitude_d / static_cast<double>(d_averaging_depth);
d_avg_longitude_d = d_avg_longitude_d / static_cast<double>(d_averaging_depth); d_avg_longitude_d = d_avg_longitude_d / static_cast<double>(d_averaging_depth);
d_avg_height_m = d_avg_height_m / static_cast<double>(d_averaging_depth); d_avg_height_m = d_avg_height_m / static_cast<double>(d_averaging_depth);
b_valid_position = true; d_valid_position = true;
} }
else else
{ {
@@ -143,12 +143,12 @@ void Pvt_Solution::perform_pos_averaging()
d_avg_latitude_d = d_latitude_d; d_avg_latitude_d = d_latitude_d;
d_avg_longitude_d = d_longitude_d; d_avg_longitude_d = d_longitude_d;
d_avg_height_m = d_height_m; d_avg_height_m = d_height_m;
b_valid_position = false; d_valid_position = false;
} }
} }
else else
{ {
b_valid_position = true; d_valid_position = true;
} }
} }
@@ -245,13 +245,13 @@ bool Pvt_Solution::is_averaging() const
bool Pvt_Solution::is_valid_position() const bool Pvt_Solution::is_valid_position() const
{ {
return b_valid_position; return d_valid_position;
} }
void Pvt_Solution::set_valid_position(bool is_valid) void Pvt_Solution::set_valid_position(bool is_valid)
{ {
b_valid_position = is_valid; d_valid_position = is_valid;
} }

View File

@@ -118,7 +118,7 @@ private:
int d_valid_observations; int d_valid_observations;
bool d_pre_2009_file; // Flag to correct week rollover in post processing mode for signals older than 2009 bool d_pre_2009_file; // Flag to correct week rollover in post processing mode for signals older than 2009
bool b_valid_position; bool d_valid_position;
bool d_flag_averaging; bool d_flag_averaging;
}; };

View File

@@ -56,65 +56,15 @@
#include <vector> #include <vector>
Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path, const std::string& base_name) Rinex_Printer::Rinex_Printer(int32_t conf_version,
const std::string& base_path,
const std::string& base_name) : d_fake_cnav_iode(1),
d_numberTypesObservations(4),
d_rinex_header_updated(false),
d_rinex_header_written(false),
d_pre_2009_file(false)
{ {
d_pre_2009_file = false;
d_rinex_header_updated = false;
d_rinex_header_written = false;
std::string base_rinex_path = base_path;
fs::path full_path(fs::current_path());
const fs::path p(base_rinex_path);
if (!fs::exists(p))
{
std::string new_folder;
for (const auto& folder : fs::path(base_rinex_path))
{
new_folder += folder.string();
errorlib::error_code ec;
if (!fs::exists(new_folder))
{
if (!fs::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder.\n";
base_rinex_path = full_path.string();
}
}
new_folder += fs::path::preferred_separator;
}
}
else
{
base_rinex_path = p.string();
}
if (base_rinex_path != ".")
{
std::cout << "RINEX files will be stored at " << base_rinex_path << '\n';
}
navfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV", base_name);
obsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS", base_name);
sbsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS", base_name);
navGalfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV", base_name);
navMixfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV", base_name);
navGlofilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV", base_name);
navBdsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_BDS_NAV", base_name);
Rinex_Printer::navFile.open(navfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::obsFile.open(obsfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::sbsFile.open(sbsfilename, std::ios::out | std::ios::app);
Rinex_Printer::navGalFile.open(navGalfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navMixFile.open(navMixfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navGloFile.open(navGlofilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navBdsFile.open(navBdsfilename, std::ios::out | std::ios::in | std::ios::app);
if (!Rinex_Printer::navFile.is_open() or !Rinex_Printer::obsFile.is_open() or
!Rinex_Printer::sbsFile.is_open() or !Rinex_Printer::navGalFile.is_open() or
!Rinex_Printer::navMixFile.is_open() or !Rinex_Printer::navGloFile.is_open())
{
std::cout << "RINEX files cannot be saved. Wrong permissions?\n";
}
// RINEX v3.02 codes // RINEX v3.02 codes
satelliteSystem["GPS"] = "G"; satelliteSystem["GPS"] = "G";
satelliteSystem["GLONASS"] = "R"; satelliteSystem["GLONASS"] = "R";
@@ -199,6 +149,59 @@ Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path,
observationCode["GPS_L1_CA_v2"] = "1"; observationCode["GPS_L1_CA_v2"] = "1";
observationCode["GLONASS_G1_CA_v2"] = "1"; observationCode["GLONASS_G1_CA_v2"] = "1";
std::string base_rinex_path = base_path;
fs::path full_path(fs::current_path());
const fs::path p(base_rinex_path);
if (!fs::exists(p))
{
std::string new_folder;
for (const auto& folder : fs::path(base_rinex_path))
{
new_folder += folder.string();
errorlib::error_code ec;
if (!fs::exists(new_folder))
{
if (!fs::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder.\n";
base_rinex_path = full_path.string();
}
}
new_folder += fs::path::preferred_separator;
}
}
else
{
base_rinex_path = p.string();
}
if (base_rinex_path != ".")
{
std::cout << "RINEX files will be stored at " << base_rinex_path << '\n';
}
navfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV", base_name);
obsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS", base_name);
sbsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS", base_name);
navGalfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV", base_name);
navMixfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV", base_name);
navGlofilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV", base_name);
navBdsfilename = base_rinex_path + fs::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_BDS_NAV", base_name);
Rinex_Printer::navFile.open(navfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::obsFile.open(obsfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::sbsFile.open(sbsfilename, std::ios::out | std::ios::app);
Rinex_Printer::navGalFile.open(navGalfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navMixFile.open(navMixfilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navGloFile.open(navGlofilename, std::ios::out | std::ios::in | std::ios::app);
Rinex_Printer::navBdsFile.open(navBdsfilename, std::ios::out | std::ios::in | std::ios::app);
if (!Rinex_Printer::navFile.is_open() or !Rinex_Printer::obsFile.is_open() or
!Rinex_Printer::sbsFile.is_open() or !Rinex_Printer::navGalFile.is_open() or
!Rinex_Printer::navMixFile.is_open() or !Rinex_Printer::navGloFile.is_open())
{
std::cout << "RINEX files cannot be saved. Wrong permissions?\n";
}
if (conf_version == 2) if (conf_version == 2)
{ {
d_version = 2; d_version = 2;
@@ -209,9 +212,6 @@ Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path,
d_version = 3; d_version = 3;
d_stringVersion = "3.02"; d_stringVersion = "3.02";
} }
d_numberTypesObservations = 4; // Number of available types of observable in the system
d_fake_cnav_iode = 1;
} }

View File

@@ -35,15 +35,13 @@
#include <sstream> // for std::stringstream #include <sstream> // for std::stringstream
Rtcm::Rtcm(uint16_t port) Rtcm::Rtcm(uint16_t port) : RTCM_port(port), server_is_running(false)
{ {
RTCM_port = port;
preamble = std::bitset<8>("11010011"); preamble = std::bitset<8>("11010011");
reserved_field = std::bitset<6>("000000"); reserved_field = std::bitset<6>("000000");
rtcm_message_queue = std::make_shared<Concurrent_Queue<std::string>>(); rtcm_message_queue = std::make_shared<Concurrent_Queue<std::string>>();
boost::asio::ip::tcp::endpoint endpoint(boost::asio::ip::tcp::v4(), RTCM_port); boost::asio::ip::tcp::endpoint endpoint(boost::asio::ip::tcp::v4(), RTCM_port);
servers.emplace_back(io_context, endpoint); servers.emplace_back(io_context, endpoint);
server_is_running = false;
} }

View File

@@ -38,12 +38,23 @@
#include <unistd.h> // for close, write #include <unistd.h> // for close, write
Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump, bool flag_rtcm_server, bool flag_rtcm_tty_port, uint16_t rtcm_tcp_port, uint16_t rtcm_station_id, const std::string& rtcm_dump_devname, bool time_tag_name, const std::string& base_path) Rtcm_Printer::Rtcm_Printer(const std::string& filename,
bool flag_rtcm_file_dump,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
const std::string& rtcm_dump_devname,
bool time_tag_name,
const std::string& base_path) : rtcm_base_path(base_path),
rtcm_devname(rtcm_dump_devname),
port(rtcm_tcp_port),
station_id(rtcm_station_id),
d_rtcm_writing_started(false),
d_rtcm_file_dump(flag_rtcm_file_dump)
{ {
const boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time(); const boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time();
const tm timeinfo = boost::posix_time::to_tm(pt); const tm timeinfo = boost::posix_time::to_tm(pt);
d_rtcm_file_dump = flag_rtcm_file_dump;
rtcm_base_path = base_path;
if (d_rtcm_file_dump) if (d_rtcm_file_dump)
{ {
fs::path full_path(fs::current_path()); fs::path full_path(fs::current_path());
@@ -134,7 +145,6 @@ Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump
} }
} }
rtcm_devname = rtcm_dump_devname;
if (flag_rtcm_tty_port == true) if (flag_rtcm_tty_port == true)
{ {
rtcm_dev_descriptor = init_serial(rtcm_devname.c_str()); rtcm_dev_descriptor = init_serial(rtcm_devname.c_str());
@@ -148,10 +158,6 @@ Rtcm_Printer::Rtcm_Printer(const std::string& filename, bool flag_rtcm_file_dump
rtcm_dev_descriptor = -1; rtcm_dev_descriptor = -1;
} }
port = rtcm_tcp_port;
station_id = rtcm_station_id;
d_rtcm_writing_started = false;
rtcm = std::make_unique<Rtcm>(port); rtcm = std::make_unique<Rtcm>(port);
if (flag_rtcm_server) if (flag_rtcm_server)

View File

@@ -43,14 +43,16 @@
#include <vector> #include <vector>
Rtklib_Solver::Rtklib_Solver(const rtk_t &rtk, int nchannels, const std::string &dump_filename, bool flag_dump_to_file, bool flag_dump_to_mat) Rtklib_Solver::Rtklib_Solver(const rtk_t &rtk,
const std::string &dump_filename,
bool flag_dump_to_file,
bool flag_dump_to_mat) : d_rtk(rtk),
d_dump_filename(dump_filename),
d_flag_dump_enabled(flag_dump_to_file),
d_flag_dump_mat_enabled(flag_dump_to_mat)
{ {
// init empty ephemeris for all the available GNSS channels // init empty ephemeris for all the available GNSS channels
rtk_ = rtk;
d_nchannels = nchannels;
d_dump_filename = dump_filename;
d_flag_dump_enabled = flag_dump_to_file;
d_flag_dump_mat_enabled = flag_dump_to_mat;
this->set_averaging_flag(false); this->set_averaging_flag(false);
// ############# ENABLE DATA FILE LOG ################# // ############# ENABLE DATA FILE LOG #################
@@ -351,31 +353,31 @@ bool Rtklib_Solver::save_matfile() const
double Rtklib_Solver::get_gdop() const double Rtklib_Solver::get_gdop() const
{ {
return dop_[0]; return d_dop[0];
} }
double Rtklib_Solver::get_pdop() const double Rtklib_Solver::get_pdop() const
{ {
return dop_[1]; return d_dop[1];
} }
double Rtklib_Solver::get_hdop() const double Rtklib_Solver::get_hdop() const
{ {
return dop_[2]; return d_dop[2];
} }
double Rtklib_Solver::get_vdop() const double Rtklib_Solver::get_vdop() const
{ {
return dop_[3]; return d_dop[3];
} }
Monitor_Pvt Rtklib_Solver::get_monitor_pvt() const Monitor_Pvt Rtklib_Solver::get_monitor_pvt() const
{ {
return monitor_pvt; return d_monitor_pvt;
} }
@@ -398,7 +400,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
int valid_obs = 0; // valid observations counter int valid_obs = 0; // valid observations counter
int glo_valid_obs = 0; // GLONASS L1/L2 valid observations counter int glo_valid_obs = 0; // GLONASS L1/L2 valid observations counter
obs_data.fill({}); d_obs_data.fill({});
std::vector<eph_t> eph_data(MAXOBS); std::vector<eph_t> eph_data(MAXOBS);
std::vector<geph_t> geph_data(MAXOBS); std::vector<geph_t> geph_data(MAXOBS);
@@ -455,7 +457,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second); eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second);
// convert observation from GNSS-SDR class to RTKLIB structure // convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs{}; obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN, galileo_ephemeris_iter->second.WN,
0); 0);
@@ -479,7 +481,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{ {
if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO)))
{ {
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i + glo_valid_obs], d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs],
gnss_observables_iter->second, gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN, galileo_ephemeris_iter->second.WN,
2); // Band 3 (L5/E5) 2); // Band 3 (L5/E5)
@@ -497,7 +499,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs = {{0, 0}, '0', '0', {}, {}, obsd_t newobs = {{0, 0}, '0', '0', {}, {},
{default_code_, default_code_, default_code_}, {default_code_, default_code_, default_code_},
{}, {0.0, 0.0, 0.0}, {}}; {}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN, galileo_ephemeris_iter->second.WN,
2); // Band 3 (L5/E5) 2); // Band 3 (L5/E5)
@@ -525,7 +527,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
eph_data[valid_obs] = eph_to_rtklib(gps_ephemeris_iter->second, this->is_pre_2009()); eph_data[valid_obs] = eph_to_rtklib(gps_ephemeris_iter->second, this->is_pre_2009());
// convert observation from GNSS-SDR class to RTKLIB structure // convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs{}; obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
gps_ephemeris_iter->second.WN, gps_ephemeris_iter->second.WN,
0, 0,
@@ -555,7 +557,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
if (eph_data[i].sat == static_cast<int>(gnss_observables_iter->second.PRN)) if (eph_data[i].sat == static_cast<int>(gnss_observables_iter->second.PRN))
{ {
eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second);
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i + glo_valid_obs], d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs],
gnss_observables_iter->second, gnss_observables_iter->second,
eph_data[i].week, eph_data[i].week,
1); // Band 2 (L2) 1); // Band 2 (L2)
@@ -574,7 +576,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs = {{0, 0}, '0', '0', {}, {}, obsd_t newobs = {{0, 0}, '0', '0', {}, {},
{default_code_, default_code_, default_code_}, {default_code_, default_code_, default_code_},
{}, {0.0, 0.0, 0.0}, {}}; {}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.WN, gps_cnav_ephemeris_iter->second.WN,
1); // Band 2 (L2) 1); // Band 2 (L2)
@@ -603,7 +605,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
if (eph_data[i].sat == static_cast<int>(gnss_observables_iter->second.PRN)) if (eph_data[i].sat == static_cast<int>(gnss_observables_iter->second.PRN))
{ {
eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second); eph_data[i] = eph_to_rtklib(gps_cnav_ephemeris_iter->second);
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i], d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i],
gnss_observables_iter->second, gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.WN, gps_cnav_ephemeris_iter->second.WN,
2); // Band 3 (L5) 2); // Band 3 (L5)
@@ -621,7 +623,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs = {{0, 0}, '0', '0', {}, {}, obsd_t newobs = {{0, 0}, '0', '0', {}, {},
{default_code_, default_code_, default_code_}, {default_code_, default_code_, default_code_},
{}, {0.0, 0.0, 0.0}, {}}; {}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
gps_cnav_ephemeris_iter->second.WN, gps_cnav_ephemeris_iter->second.WN,
2); // Band 3 (L5) 2); // Band 3 (L5)
@@ -649,7 +651,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc);
// convert observation from GNSS-SDR class to RTKLIB structure // convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs{}; obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
glonass_gnav_ephemeris_iter->second.d_WN, glonass_gnav_ephemeris_iter->second.d_WN,
0); // Band 0 (L1) 0); // Band 0 (L1)
@@ -672,7 +674,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{ {
if (geph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS))) if (geph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS)))
{ {
obs_data[i + valid_obs] = insert_obs_to_rtklib(obs_data[i + valid_obs], d_obs_data[i + valid_obs] = insert_obs_to_rtklib(d_obs_data[i + valid_obs],
gnss_observables_iter->second, gnss_observables_iter->second,
glonass_gnav_ephemeris_iter->second.d_WN, glonass_gnav_ephemeris_iter->second.d_WN,
1); // Band 1 (L2) 1); // Band 1 (L2)
@@ -687,7 +689,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc); geph_data[glo_valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second, gnav_utc);
// convert observation from GNSS-SDR class to RTKLIB structure // convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs{}; obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
glonass_gnav_ephemeris_iter->second.d_WN, glonass_gnav_ephemeris_iter->second.d_WN,
1); // Band 1 (L2) 1); // Band 1 (L2)
@@ -715,7 +717,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second); eph_data[valid_obs] = eph_to_rtklib(beidou_ephemeris_iter->second);
// convert observation from GNSS-SDR class to RTKLIB structure // convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs{}; obsd_t newobs{};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
0); 0);
@@ -737,7 +739,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
{ {
if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS))) if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS)))
{ {
obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(obs_data[i + glo_valid_obs], d_obs_data[i + glo_valid_obs] = insert_obs_to_rtklib(d_obs_data[i + glo_valid_obs],
gnss_observables_iter->second, gnss_observables_iter->second,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
2); // Band 3 (L2/G2/B3) 2); // Band 3 (L2/G2/B3)
@@ -755,7 +757,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
obsd_t newobs = {{0, 0}, '0', '0', {}, {}, obsd_t newobs = {{0, 0}, '0', '0', {}, {},
{default_code_, default_code_, default_code_}, {default_code_, default_code_, default_code_},
{}, {0.0, 0.0, 0.0}, {}}; {}, {0.0, 0.0, 0.0}, {}};
obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs, d_obs_data[valid_obs + glo_valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET, beidou_ephemeris_iter->second.WN + BEIDOU_DNAV_BDT2GPST_WEEK_NUM_OFFSET,
2); // Band 2 (L2/G2) 2); // Band 2 (L2/G2)
@@ -878,25 +880,25 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
} }
} }
result = rtkpos(&rtk_, obs_data.data(), valid_obs + glo_valid_obs, &nav_data); result = rtkpos(&d_rtk, d_obs_data.data(), valid_obs + glo_valid_obs, &nav_data);
if (result == 0) if (result == 0)
{ {
LOG(INFO) << "RTKLIB rtkpos error: " << rtk_.errbuf; LOG(INFO) << "RTKLIB rtkpos error: " << d_rtk.errbuf;
rtk_.neb = 0; // clear error buffer to avoid repeating the error message d_rtk.neb = 0; // clear error buffer to avoid repeating the error message
this->set_time_offset_s(0.0); // reset rx time estimation this->set_time_offset_s(0.0); // reset rx time estimation
this->set_num_valid_observations(0); this->set_num_valid_observations(0);
} }
else else
{ {
this->set_num_valid_observations(rtk_.sol.ns); // record the number of valid satellites used by the PVT solver this->set_num_valid_observations(d_rtk.sol.ns); // record the number of valid satellites used by the PVT solver
pvt_sol = rtk_.sol; pvt_sol = d_rtk.sol;
// DOP computation // DOP computation
unsigned int used_sats = 0; unsigned int used_sats = 0;
for (unsigned int i = 0; i < MAXSAT; i++) for (unsigned int i = 0; i < MAXSAT; i++)
{ {
pvt_ssat[i] = rtk_.ssat[i]; pvt_ssat[i] = d_rtk.ssat[i];
if (rtk_.ssat[i].vs == 1) if (d_rtk.ssat[i].vs == 1)
{ {
used_sats++; used_sats++;
} }
@@ -904,7 +906,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
std::vector<double> azel(used_sats * 2); std::vector<double> azel(used_sats * 2);
int index_aux = 0; int index_aux = 0;
for (auto &i : rtk_.ssat) for (auto &i : d_rtk.ssat)
{ {
if (i.vs == 1) if (i.vs == 1)
{ {
@@ -916,7 +918,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
if (index_aux > 0) if (index_aux > 0)
{ {
dops(index_aux, azel.data(), 0.0, dop_.data()); dops(index_aux, azel.data(), 0.0, d_dop.data());
} }
this->set_valid_position(true); this->set_valid_position(true);
std::array<double, 4> rx_position_and_time{}; std::array<double, 4> rx_position_and_time{};
@@ -924,7 +926,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
rx_position_and_time[1] = pvt_sol.rr[1]; // [m] rx_position_and_time[1] = pvt_sol.rr[1]; // [m]
rx_position_and_time[2] = pvt_sol.rr[2]; // [m] rx_position_and_time[2] = pvt_sol.rr[2]; // [m]
// todo: fix this ambiguity in the RTKLIB units in receiver clock offset! // todo: fix this ambiguity in the RTKLIB units in receiver clock offset!
if (rtk_.opt.mode == PMODE_SINGLE) if (d_rtk.opt.mode == PMODE_SINGLE)
{ {
// if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s]
// add also the clock offset from gps to galileo (pvt_sol.dtr[2]) // add also the clock offset from gps to galileo (pvt_sol.dtr[2])
@@ -977,53 +979,53 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
// ######## PVT MONITOR ######### // ######## PVT MONITOR #########
// TOW // TOW
monitor_pvt.TOW_at_current_symbol_ms = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms; d_monitor_pvt.TOW_at_current_symbol_ms = gnss_observables_map.cbegin()->second.TOW_at_current_symbol_ms;
// WEEK // WEEK
monitor_pvt.week = adjgpsweek(nav_data.eph[0].week, this->is_pre_2009()); d_monitor_pvt.week = adjgpsweek(nav_data.eph[0].week, this->is_pre_2009());
// PVT GPS time // PVT GPS time
monitor_pvt.RX_time = gnss_observables_map.cbegin()->second.RX_time; d_monitor_pvt.RX_time = gnss_observables_map.cbegin()->second.RX_time;
// User clock offset [s] // User clock offset [s]
monitor_pvt.user_clk_offset = rx_position_and_time[3]; d_monitor_pvt.user_clk_offset = rx_position_and_time[3];
// ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double) // ECEF POS X,Y,X [m] + ECEF VEL X,Y,X [m/s] (6 x double)
monitor_pvt.pos_x = pvt_sol.rr[0]; d_monitor_pvt.pos_x = pvt_sol.rr[0];
monitor_pvt.pos_y = pvt_sol.rr[1]; d_monitor_pvt.pos_y = pvt_sol.rr[1];
monitor_pvt.pos_z = pvt_sol.rr[2]; d_monitor_pvt.pos_z = pvt_sol.rr[2];
monitor_pvt.vel_x = pvt_sol.rr[3]; d_monitor_pvt.vel_x = pvt_sol.rr[3];
monitor_pvt.vel_y = pvt_sol.rr[4]; d_monitor_pvt.vel_y = pvt_sol.rr[4];
monitor_pvt.vel_z = pvt_sol.rr[5]; d_monitor_pvt.vel_z = pvt_sol.rr[5];
// position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double) // position variance/covariance (m^2) {c_xx,c_yy,c_zz,c_xy,c_yz,c_zx} (6 x double)
monitor_pvt.cov_xx = pvt_sol.qr[0]; d_monitor_pvt.cov_xx = pvt_sol.qr[0];
monitor_pvt.cov_yy = pvt_sol.qr[1]; d_monitor_pvt.cov_yy = pvt_sol.qr[1];
monitor_pvt.cov_zz = pvt_sol.qr[2]; d_monitor_pvt.cov_zz = pvt_sol.qr[2];
monitor_pvt.cov_xy = pvt_sol.qr[3]; d_monitor_pvt.cov_xy = pvt_sol.qr[3];
monitor_pvt.cov_yz = pvt_sol.qr[4]; d_monitor_pvt.cov_yz = pvt_sol.qr[4];
monitor_pvt.cov_zx = pvt_sol.qr[5]; d_monitor_pvt.cov_zx = pvt_sol.qr[5];
// GEO user position Latitude [deg] // GEO user position Latitude [deg]
monitor_pvt.latitude = this->get_latitude(); d_monitor_pvt.latitude = this->get_latitude();
// GEO user position Longitude [deg] // GEO user position Longitude [deg]
monitor_pvt.longitude = this->get_longitude(); d_monitor_pvt.longitude = this->get_longitude();
// GEO user position Height [m] // GEO user position Height [m]
monitor_pvt.height = this->get_height(); d_monitor_pvt.height = this->get_height();
// NUMBER OF VALID SATS // NUMBER OF VALID SATS
monitor_pvt.valid_sats = pvt_sol.ns; d_monitor_pvt.valid_sats = pvt_sol.ns;
// RTKLIB solution status // RTKLIB solution status
monitor_pvt.solution_status = pvt_sol.stat; d_monitor_pvt.solution_status = pvt_sol.stat;
// RTKLIB solution type (0:xyz-ecef,1:enu-baseline) // RTKLIB solution type (0:xyz-ecef,1:enu-baseline)
monitor_pvt.solution_type = pvt_sol.type; d_monitor_pvt.solution_type = pvt_sol.type;
// AR ratio factor for validation // AR ratio factor for validation
monitor_pvt.AR_ratio_factor = pvt_sol.ratio; d_monitor_pvt.AR_ratio_factor = pvt_sol.ratio;
// AR ratio threshold for validation // AR ratio threshold for validation
monitor_pvt.AR_ratio_threshold = pvt_sol.thres; d_monitor_pvt.AR_ratio_threshold = pvt_sol.thres;
// GDOP / PDOP/ HDOP/ VDOP // GDOP / PDOP/ HDOP/ VDOP
monitor_pvt.gdop = dop_[0]; d_monitor_pvt.gdop = d_dop[0];
monitor_pvt.pdop = dop_[1]; d_monitor_pvt.pdop = d_dop[1];
monitor_pvt.hdop = dop_[2]; d_monitor_pvt.hdop = d_dop[2];
monitor_pvt.vdop = dop_[3]; d_monitor_pvt.vdop = d_dop[3];
this->set_rx_vel({enuv[0], enuv[1], enuv[2]}); this->set_rx_vel({enuv[0], enuv[1], enuv[2]});
@@ -1031,7 +1033,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
this->set_clock_drift_ppm(clock_drift_ppm); this->set_clock_drift_ppm(clock_drift_ppm);
// User clock drift [ppm] // User clock drift [ppm]
monitor_pvt.user_clk_drift_ppm = clock_drift_ppm; d_monitor_pvt.user_clk_drift_ppm = clock_drift_ppm;
// ######## LOG FILE ######### // ######## LOG FILE #########
if (d_flag_dump_enabled == true) if (d_flag_dump_enabled == true)
@@ -1104,10 +1106,10 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
d_dump_file.write(reinterpret_cast<char *>(&pvt_sol.thres), sizeof(float)); d_dump_file.write(reinterpret_cast<char *>(&pvt_sol.thres), sizeof(float));
// GDOP / PDOP/ HDOP/ VDOP // GDOP / PDOP/ HDOP/ VDOP
d_dump_file.write(reinterpret_cast<char *>(&dop_[0]), sizeof(double)); d_dump_file.write(reinterpret_cast<char *>(&d_dop[0]), sizeof(double));
d_dump_file.write(reinterpret_cast<char *>(&dop_[1]), sizeof(double)); d_dump_file.write(reinterpret_cast<char *>(&d_dop[1]), sizeof(double));
d_dump_file.write(reinterpret_cast<char *>(&dop_[2]), sizeof(double)); d_dump_file.write(reinterpret_cast<char *>(&d_dop[2]), sizeof(double));
d_dump_file.write(reinterpret_cast<char *>(&dop_[3]), sizeof(double)); d_dump_file.write(reinterpret_cast<char *>(&d_dop[3]), sizeof(double));
} }
catch (const std::ifstream::failure &e) catch (const std::ifstream::failure &e)
{ {

View File

@@ -75,7 +75,7 @@
class Rtklib_Solver : public Pvt_Solution class Rtklib_Solver : public Pvt_Solution
{ {
public: public:
Rtklib_Solver(const rtk_t& rtk, int nchannels, const std::string& dump_filename, bool flag_dump_to_file, bool flag_dump_to_mat); Rtklib_Solver(const rtk_t& rtk, const std::string& dump_filename, bool flag_dump_to_file, bool flag_dump_to_mat);
~Rtklib_Solver(); ~Rtklib_Solver();
bool get_PVT(const std::map<int, Gnss_Synchro>& gnss_observables_map, bool flag_averaging); bool get_PVT(const std::map<int, Gnss_Synchro>& gnss_observables_map, bool flag_averaging);
@@ -116,13 +116,12 @@ public:
private: private:
bool save_matfile() const; bool save_matfile() const;
std::array<obsd_t, MAXOBS> obs_data{}; std::array<obsd_t, MAXOBS> d_obs_data{};
std::array<double, 4> dop_{}; std::array<double, 4> d_dop{};
rtk_t rtk_{}; rtk_t d_rtk{};
Monitor_Pvt monitor_pvt{}; Monitor_Pvt d_monitor_pvt{};
std::string d_dump_filename; std::string d_dump_filename;
std::ofstream d_dump_file; std::ofstream d_dump_file;
int d_nchannels; // Number of available channels for positioning
bool d_flag_dump_enabled; bool d_flag_dump_enabled;
bool d_flag_dump_mat_enabled; bool d_flag_dump_mat_enabled;
}; };

View File

@@ -49,9 +49,8 @@ public:
// google::protobuf::ShutdownProtobufLibrary(); // google::protobuf::ShutdownProtobufLibrary();
} }
inline Serdes_Galileo_Eph(const Serdes_Galileo_Eph& other) noexcept //!< Copy constructor inline Serdes_Galileo_Eph(const Serdes_Galileo_Eph& other) noexcept : monitor_(other.monitor_) //!< Copy constructor
{ {
this->monitor_ = other.monitor_;
} }
inline Serdes_Galileo_Eph& operator=(const Serdes_Galileo_Eph& rhs) noexcept //!< Copy assignment operator inline Serdes_Galileo_Eph& operator=(const Serdes_Galileo_Eph& rhs) noexcept //!< Copy assignment operator
@@ -60,9 +59,8 @@ public:
return *this; return *this;
} }
inline Serdes_Galileo_Eph(Serdes_Galileo_Eph&& other) noexcept //!< Move constructor inline Serdes_Galileo_Eph(Serdes_Galileo_Eph&& other) noexcept : monitor_(std::move(other.monitor_)) //!< Move constructor
{ {
this->monitor_ = std::move(other.monitor_);
} }
inline Serdes_Galileo_Eph& operator=(Serdes_Galileo_Eph&& other) noexcept //!< Move assignment operator inline Serdes_Galileo_Eph& operator=(Serdes_Galileo_Eph&& other) noexcept //!< Move assignment operator

View File

@@ -48,9 +48,8 @@ public:
// google::protobuf::ShutdownProtobufLibrary(); // google::protobuf::ShutdownProtobufLibrary();
} }
inline Serdes_Gps_Eph(const Serdes_Gps_Eph& other) noexcept //!< Copy constructor inline Serdes_Gps_Eph(const Serdes_Gps_Eph& other) noexcept : monitor_(other.monitor_) //!< Copy constructor
{ {
this->monitor_ = other.monitor_;
} }
inline Serdes_Gps_Eph& operator=(const Serdes_Gps_Eph& rhs) noexcept //!< Copy assignment operator inline Serdes_Gps_Eph& operator=(const Serdes_Gps_Eph& rhs) noexcept //!< Copy assignment operator
@@ -59,9 +58,8 @@ public:
return *this; return *this;
} }
inline Serdes_Gps_Eph(Serdes_Gps_Eph&& other) noexcept //!< Move constructor inline Serdes_Gps_Eph(Serdes_Gps_Eph&& other) noexcept : monitor_(std::move(other.monitor_)) //!< Move constructor
{ {
this->monitor_ = std::move(other.monitor_);
} }
inline Serdes_Gps_Eph& operator=(Serdes_Gps_Eph&& other) noexcept //!< Move assignment operator inline Serdes_Gps_Eph& operator=(Serdes_Gps_Eph&& other) noexcept //!< Move assignment operator

View File

@@ -49,9 +49,8 @@ public:
// google::protobuf::ShutdownProtobufLibrary(); // google::protobuf::ShutdownProtobufLibrary();
} }
inline Serdes_Monitor_Pvt(const Serdes_Monitor_Pvt& other) noexcept //!< Copy constructor inline Serdes_Monitor_Pvt(const Serdes_Monitor_Pvt& other) noexcept : monitor_(other.monitor_) //!< Copy constructor
{ {
this->monitor_ = other.monitor_;
} }
inline Serdes_Monitor_Pvt& operator=(const Serdes_Monitor_Pvt& rhs) noexcept //!< Copy assignment operator inline Serdes_Monitor_Pvt& operator=(const Serdes_Monitor_Pvt& rhs) noexcept //!< Copy assignment operator
@@ -60,9 +59,8 @@ public:
return *this; return *this;
} }
inline Serdes_Monitor_Pvt(Serdes_Monitor_Pvt&& other) noexcept //!< Move constructor inline Serdes_Monitor_Pvt(Serdes_Monitor_Pvt&& other) noexcept : monitor_(std::move(other.monitor_)) //!< Move constructor
{ {
this->monitor_ = std::move(other.monitor_);
} }
inline Serdes_Monitor_Pvt& operator=(Serdes_Monitor_Pvt&& other) noexcept //!< Move assignment operator inline Serdes_Monitor_Pvt& operator=(Serdes_Monitor_Pvt&& other) noexcept //!< Move assignment operator

View File

@@ -49,7 +49,20 @@ hybrid_observables_gs_sptr hybrid_observables_gs_make(const Obs_Conf &conf_)
hybrid_observables_gs::hybrid_observables_gs(const Obs_Conf &conf_) : gr::block("hybrid_observables_gs", hybrid_observables_gs::hybrid_observables_gs(const Obs_Conf &conf_) : gr::block("hybrid_observables_gs",
gr::io_signature::make(conf_.nchannels_in, conf_.nchannels_in, sizeof(Gnss_Synchro)), gr::io_signature::make(conf_.nchannels_in, conf_.nchannels_in, sizeof(Gnss_Synchro)),
gr::io_signature::make(conf_.nchannels_out, conf_.nchannels_out, sizeof(Gnss_Synchro))) gr::io_signature::make(conf_.nchannels_out, conf_.nchannels_out, sizeof(Gnss_Synchro))),
d_conf(conf_),
d_dump_filename(conf_.dump_filename),
d_smooth_filter_M(static_cast<double>(conf_.smoothing_factor)),
d_T_rx_step_s(static_cast<double>(conf_.observable_interval_ms) / 1000.0),
d_T_rx_TOW_ms(0U),
d_T_rx_step_ms(conf_.observable_interval_ms),
d_T_status_report_timer_ms(0),
d_nchannels_in(conf_.nchannels_in),
d_nchannels_out(conf_.nchannels_out),
d_T_rx_TOW_set(false),
d_dump(conf_.dump),
d_dump_mat(conf_.dump_mat && d_dump)
{ {
// PVT input message port // PVT input message port
this->message_port_register_in(pmt::mp("pvt_to_observables")); this->message_port_register_in(pmt::mp("pvt_to_observables"));
@@ -63,16 +76,32 @@ hybrid_observables_gs::hybrid_observables_gs(const Obs_Conf &conf_) : gr::block(
boost::bind(&hybrid_observables_gs::msg_handler_pvt_to_observables, this, _1)); boost::bind(&hybrid_observables_gs::msg_handler_pvt_to_observables, this, _1));
#endif #endif
#endif #endif
// Send Channel status to gnss_flowgraph // Send Channel status to gnss_flowgraph
this->message_port_register_out(pmt::mp("status")); this->message_port_register_out(pmt::mp("status"));
d_conf = conf_;
d_dump = conf_.dump;
d_dump_mat = conf_.dump_mat and d_dump;
d_dump_filename = conf_.dump_filename;
d_nchannels_out = conf_.nchannels_out;
d_nchannels_in = conf_.nchannels_in;
d_gnss_synchro_history = std::make_unique<Gnss_circular_deque<Gnss_Synchro>>(1000, d_nchannels_out); d_gnss_synchro_history = std::make_unique<Gnss_circular_deque<Gnss_Synchro>>(1000, d_nchannels_out);
d_Rx_clock_buffer.set_capacity(std::min(std::max(200U / d_T_rx_step_ms, 3U), 10U));
d_Rx_clock_buffer.clear();
d_channel_last_pll_lock = std::vector<bool>(d_nchannels_out, false);
d_channel_last_pseudorange_smooth = std::vector<double>(d_nchannels_out, 0.0);
d_channel_last_carrier_phase_rads = std::vector<double>(d_nchannels_out, 0.0);
d_mapStringValues["1C"] = evGPS_1C;
d_mapStringValues["2S"] = evGPS_2S;
d_mapStringValues["L5"] = evGPS_L5;
d_mapStringValues["1B"] = evGAL_1B;
d_mapStringValues["5X"] = evGAL_5X;
d_mapStringValues["E6"] = evGAL_E6;
d_mapStringValues["7X"] = evGAL_7X;
d_mapStringValues["1G"] = evGLO_1G;
d_mapStringValues["2G"] = evGLO_2G;
d_mapStringValues["B1"] = evBDS_B1;
d_mapStringValues["B2"] = evBDS_B2;
d_mapStringValues["B3"] = evBDS_B3;
// ############# ENABLE DATA FILE LOG ################# // ############# ENABLE DATA FILE LOG #################
if (d_dump) if (d_dump)
{ {
@@ -117,31 +146,6 @@ hybrid_observables_gs::hybrid_observables_gs(const Obs_Conf &conf_) : gr::block(
d_dump = false; d_dump = false;
} }
} }
d_T_rx_TOW_ms = 0U;
d_T_rx_step_ms = conf_.observable_interval_ms;
d_T_rx_step_s = static_cast<double>(d_T_rx_step_ms) / 1000.0;
d_T_rx_TOW_set = false;
d_T_status_report_timer_ms = 0;
d_Rx_clock_buffer.set_capacity(std::min(std::max(200U / d_T_rx_step_ms, 3U), 10U));
d_Rx_clock_buffer.clear();
d_channel_last_pll_lock = std::vector<bool>(d_nchannels_out, false);
d_channel_last_pseudorange_smooth = std::vector<double>(d_nchannels_out, 0.0);
d_channel_last_carrier_phase_rads = std::vector<double>(d_nchannels_out, 0.0);
d_smooth_filter_M = static_cast<double>(conf_.smoothing_factor);
d_mapStringValues["1C"] = evGPS_1C;
d_mapStringValues["2S"] = evGPS_2S;
d_mapStringValues["L5"] = evGPS_L5;
d_mapStringValues["1B"] = evGAL_1B;
d_mapStringValues["5X"] = evGAL_5X;
d_mapStringValues["E6"] = evGAL_E6;
d_mapStringValues["7X"] = evGAL_7X;
d_mapStringValues["1G"] = evGLO_1G;
d_mapStringValues["2G"] = evGLO_2G;
d_mapStringValues["B1"] = evBDS_B1;
d_mapStringValues["B2"] = evBDS_B2;
d_mapStringValues["B3"] = evBDS_B3;
} }

View File

@@ -18,14 +18,13 @@
#include "obs_conf.h" #include "obs_conf.h"
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
Obs_Conf::Obs_Conf() Obs_Conf::Obs_Conf() : dump_filename("obs_dump.dat"),
smoothing_factor(FLAGS_carrier_smoothing_factor),
nchannels_in(0U),
nchannels_out(0U),
observable_interval_ms(20U),
enable_carrier_smoothing(false),
dump(false),
dump_mat(false)
{ {
dump_filename = std::string("obs_dump.dat");
smoothing_factor = FLAGS_carrier_smoothing_factor;
nchannels_in = 0U;
nchannels_out = 0U;
observable_interval_ms = 20U;
enable_carrier_smoothing = false;
dump = false;
dump_mat = false;
} }

View File

@@ -143,7 +143,7 @@ void NmeaPrinterTest::conf()
TEST_F(NmeaPrinterTest, PrintLine) TEST_F(NmeaPrinterTest, PrintLine)
{ {
std::string filename("nmea_test.nmea"); std::string filename("nmea_test.nmea");
std::shared_ptr<Rtklib_Solver> pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); std::shared_ptr<Rtklib_Solver> pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
boost::posix_time::ptime pt(boost::gregorian::date(1994, boost::date_time::Nov, 19), boost::posix_time::ptime pt(boost::gregorian::date(1994, boost::date_time::Nov, 19),
boost::posix_time::hours(22) + boost::posix_time::minutes(54) + boost::posix_time::seconds(46)); boost::posix_time::hours(22) + boost::posix_time::minutes(54) + boost::posix_time::seconds(46));

View File

@@ -141,7 +141,7 @@ void RinexPrinterTest::conf()
TEST_F(RinexPrinterTest, GalileoObsHeader) TEST_F(RinexPrinterTest, GalileoObsHeader)
{ {
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
auto eph = Galileo_Ephemeris(); auto eph = Galileo_Ephemeris();
eph.PRN = 1; eph.PRN = 1;
pvt_solution->galileo_ephemeris_map[1] = eph; pvt_solution->galileo_ephemeris_map[1] = eph;
@@ -227,7 +227,7 @@ TEST_F(RinexPrinterTest, GalileoObsHeader)
TEST_F(RinexPrinterTest, GlonassObsHeader) TEST_F(RinexPrinterTest, GlonassObsHeader)
{ {
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
auto eph = Glonass_Gnav_Ephemeris(); auto eph = Glonass_Gnav_Ephemeris();
eph.PRN = 1; eph.PRN = 1;
pvt_solution->glonass_gnav_ephemeris_map[1] = eph; pvt_solution->glonass_gnav_ephemeris_map[1] = eph;
@@ -287,7 +287,7 @@ TEST_F(RinexPrinterTest, MixedObsHeader)
auto eph_gps = Gps_Ephemeris(); auto eph_gps = Gps_Ephemeris();
eph_gal.PRN = 1; eph_gal.PRN = 1;
eph_gps.PRN = 1; eph_gps.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->galileo_ephemeris_map[1] = eph_gal; pvt_solution->galileo_ephemeris_map[1] = eph_gal;
pvt_solution->gps_ephemeris_map[1] = eph_gps; pvt_solution->gps_ephemeris_map[1] = eph_gps;
@@ -357,7 +357,7 @@ TEST_F(RinexPrinterTest, MixedObsHeaderGpsGlo)
auto eph_gps = Gps_Ephemeris(); auto eph_gps = Gps_Ephemeris();
eph_glo.PRN = 1; eph_glo.PRN = 1;
eph_gps.PRN = 1; eph_gps.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->glonass_gnav_ephemeris_map[1] = eph_glo; pvt_solution->glonass_gnav_ephemeris_map[1] = eph_glo;
pvt_solution->gps_ephemeris_map[1] = eph_gps; pvt_solution->gps_ephemeris_map[1] = eph_gps;
@@ -424,7 +424,7 @@ TEST_F(RinexPrinterTest, GalileoObsLog)
bool no_more_finds = false; bool no_more_finds = false;
auto eph = Galileo_Ephemeris(); auto eph = Galileo_Ephemeris();
eph.PRN = 1; eph.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->galileo_ephemeris_map[1] = eph; pvt_solution->galileo_ephemeris_map[1] = eph;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;
@@ -504,7 +504,7 @@ TEST_F(RinexPrinterTest, GlonassObsLog)
bool no_more_finds = false; bool no_more_finds = false;
auto eph = Glonass_Gnav_Ephemeris(); auto eph = Glonass_Gnav_Ephemeris();
eph.PRN = 22; eph.PRN = 22;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->glonass_gnav_ephemeris_map[1] = eph; pvt_solution->glonass_gnav_ephemeris_map[1] = eph;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;
@@ -586,7 +586,7 @@ TEST_F(RinexPrinterTest, GpsObsLogDualBand)
auto eph_cnav = Gps_CNAV_Ephemeris(); auto eph_cnav = Gps_CNAV_Ephemeris();
eph.PRN = 1; eph.PRN = 1;
eph_cnav.PRN = 1; eph_cnav.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->gps_ephemeris_map[1] = eph; pvt_solution->gps_ephemeris_map[1] = eph;
pvt_solution->gps_cnav_ephemeris_map[1] = eph_cnav; pvt_solution->gps_cnav_ephemeris_map[1] = eph_cnav;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;
@@ -674,7 +674,7 @@ TEST_F(RinexPrinterTest, GpsObsLogDualBand)
TEST_F(RinexPrinterTest, GalileoObsLogDualBand) TEST_F(RinexPrinterTest, GalileoObsLogDualBand)
{ {
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
auto eph = Galileo_Ephemeris(); auto eph = Galileo_Ephemeris();
eph.PRN = 1; eph.PRN = 1;
pvt_solution->galileo_ephemeris_map[1] = eph; pvt_solution->galileo_ephemeris_map[1] = eph;
@@ -774,7 +774,7 @@ TEST_F(RinexPrinterTest, MixedObsLog)
auto eph_gal = Galileo_Ephemeris(); auto eph_gal = Galileo_Ephemeris();
eph_gps.PRN = 1; eph_gps.PRN = 1;
eph_gal.PRN = 1; eph_gal.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->gps_ephemeris_map[1] = eph_gps; pvt_solution->gps_ephemeris_map[1] = eph_gps;
pvt_solution->galileo_ephemeris_map[1] = eph_gal; pvt_solution->galileo_ephemeris_map[1] = eph_gal;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;
@@ -898,7 +898,7 @@ TEST_F(RinexPrinterTest, MixedObsLogGpsGlo)
auto eph_glo = Glonass_Gnav_Ephemeris(); auto eph_glo = Glonass_Gnav_Ephemeris();
eph_gps.PRN = 1; eph_gps.PRN = 1;
eph_glo.PRN = 1; eph_glo.PRN = 1;
auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, 12, "filename", false, false); auto pvt_solution = std::make_shared<Rtklib_Solver>(rtk, "filename", false, false);
pvt_solution->gps_ephemeris_map[1] = eph_gps; pvt_solution->gps_ephemeris_map[1] = eph_gps;
pvt_solution->glonass_gnav_ephemeris_map[1] = eph_glo; pvt_solution->glonass_gnav_ephemeris_map[1] = eph_glo;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;