1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-12-15 12:40:35 +00:00

Merge branch 'next' of https://github.com/gnss-sdr/gnss-sdr into next

This commit is contained in:
Carles Fernandez 2018-10-28 10:14:45 +01:00
commit 7abb877f69
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
21 changed files with 1429 additions and 938 deletions

View File

@ -351,7 +351,7 @@ set(GNSSSDR_ARMADILLO_LOCAL_VERSION "9.200.x")
set(GNSSSDR_GTEST_LOCAL_VERSION "1.8.1") set(GNSSSDR_GTEST_LOCAL_VERSION "1.8.1")
set(GNSSSDR_GNSS_SIM_LOCAL_VERSION "master") set(GNSSSDR_GNSS_SIM_LOCAL_VERSION "master")
set(GNSSSDR_GPSTK_LOCAL_VERSION "2.10.6") set(GNSSSDR_GPSTK_LOCAL_VERSION "2.10.6")
set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.12") set(GNSSSDR_MATIO_LOCAL_VERSION "1.5.13")

View File

@ -30,6 +30,7 @@
#include "rtklib_pvt.h" #include "rtklib_pvt.h"
#include "pvt_conf.h"
#include "configuration_interface.h" #include "configuration_interface.h"
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <boost/archive/xml_oarchive.hpp> #include <boost/archive/xml_oarchive.hpp>
@ -54,84 +55,85 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {
Pvt_Conf pvt_output_parameters = Pvt_Conf();
// dump parameters // dump parameters
std::string default_dump_filename = "./pvt.dat"; std::string default_dump_filename = "./pvt.dat";
std::string default_nmea_dump_filename = "./nmea_pvt.nmea"; std::string default_nmea_dump_filename = "./nmea_pvt.nmea";
std::string default_nmea_dump_devname = "/dev/tty1"; std::string default_nmea_dump_devname = "/dev/tty1";
std::string default_rtcm_dump_devname = "/dev/pts/1"; std::string default_rtcm_dump_devname = "/dev/pts/1";
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
dump_ = configuration->property(role + ".dump", false); pvt_output_parameters.dump = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename); pvt_output_parameters.dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
// output rate // output rate
int output_rate_ms = configuration->property(role + ".output_rate_ms", 500); pvt_output_parameters.output_rate_ms = configuration->property(role + ".output_rate_ms", 500);
// display rate // display rate
int display_rate_ms = configuration->property(role + ".display_rate_ms", 500); pvt_output_parameters.display_rate_ms = configuration->property(role + ".display_rate_ms", 500);
// NMEA Printer settings // NMEA Printer settings
bool flag_nmea_tty_port = configuration->property(role + ".flag_nmea_tty_port", false); pvt_output_parameters.flag_nmea_tty_port = configuration->property(role + ".flag_nmea_tty_port", false);
std::string nmea_dump_filename = configuration->property(role + ".nmea_dump_filename", default_nmea_dump_filename); pvt_output_parameters.nmea_dump_filename = configuration->property(role + ".nmea_dump_filename", default_nmea_dump_filename);
std::string nmea_dump_devname = configuration->property(role + ".nmea_dump_devname", default_nmea_dump_devname); std::string nmea_dump_devname = configuration->property(role + ".nmea_dump_devname", default_nmea_dump_devname);
// RINEX version // RINEX version
int rinex_version = configuration->property(role + ".rinex_version", 3); pvt_output_parameters.rinex_version = configuration->property(role + ".rinex_version", 3);
if (FLAGS_RINEX_version.compare("3.01") == 0) if (FLAGS_RINEX_version.compare("3.01") == 0)
{ {
rinex_version = 3; pvt_output_parameters.rinex_version = 3;
} }
else if (FLAGS_RINEX_version.compare("3.02") == 0) else if (FLAGS_RINEX_version.compare("3.02") == 0)
{ {
rinex_version = 3; pvt_output_parameters.rinex_version = 3;
} }
else if (FLAGS_RINEX_version.compare("3") == 0) else if (FLAGS_RINEX_version.compare("3") == 0)
{ {
rinex_version = 3; pvt_output_parameters.rinex_version = 3;
} }
else if (FLAGS_RINEX_version.compare("2.11") == 0) else if (FLAGS_RINEX_version.compare("2.11") == 0)
{ {
rinex_version = 2; pvt_output_parameters.rinex_version = 2;
} }
else if (FLAGS_RINEX_version.compare("2.10") == 0) else if (FLAGS_RINEX_version.compare("2.10") == 0)
{ {
rinex_version = 2; pvt_output_parameters.rinex_version = 2;
} }
else if (FLAGS_RINEX_version.compare("2") == 0) else if (FLAGS_RINEX_version.compare("2") == 0)
{ {
rinex_version = 2; pvt_output_parameters.rinex_version = 2;
} }
int rinexobs_rate_ms = bc::lcm(configuration->property(role + ".rinexobs_rate_ms", 1000), output_rate_ms); pvt_output_parameters.rinexobs_rate_ms = bc::lcm(configuration->property(role + ".rinexobs_rate_ms", 1000), pvt_output_parameters.output_rate_ms);
int rinexnav_rate_ms = bc::lcm(configuration->property(role + ".rinexnav_rate_ms", 6000), output_rate_ms); pvt_output_parameters.rinexnav_rate_ms = bc::lcm(configuration->property(role + ".rinexnav_rate_ms", 6000), pvt_output_parameters.output_rate_ms);
// RTCM Printer settings // RTCM Printer settings
bool flag_rtcm_tty_port = configuration->property(role + ".flag_rtcm_tty_port", false); pvt_output_parameters.flag_rtcm_tty_port = configuration->property(role + ".flag_rtcm_tty_port", false);
std::string rtcm_dump_devname = configuration->property(role + ".rtcm_dump_devname", default_rtcm_dump_devname); pvt_output_parameters.rtcm_dump_devname = configuration->property(role + ".rtcm_dump_devname", default_rtcm_dump_devname);
bool flag_rtcm_server = configuration->property(role + ".flag_rtcm_server", false); pvt_output_parameters.flag_rtcm_server = configuration->property(role + ".flag_rtcm_server", false);
unsigned short rtcm_tcp_port = configuration->property(role + ".rtcm_tcp_port", 2101); pvt_output_parameters.rtcm_tcp_port = configuration->property(role + ".rtcm_tcp_port", 2101);
unsigned short rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234); pvt_output_parameters.rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234);
// RTCM message rates: least common multiple with output_rate_ms // RTCM message rates: least common multiple with output_rate_ms
int rtcm_MT1019_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), output_rate_ms); int rtcm_MT1019_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), pvt_output_parameters.output_rate_ms);
int rtcm_MT1020_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1020_rate_ms", 5000), output_rate_ms); int rtcm_MT1020_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1020_rate_ms", 5000), pvt_output_parameters.output_rate_ms);
int rtcm_MT1045_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), output_rate_ms); int rtcm_MT1045_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), pvt_output_parameters.output_rate_ms);
int rtcm_MSM_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), output_rate_ms); int rtcm_MSM_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), pvt_output_parameters.output_rate_ms);
int rtcm_MT1077_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), output_rate_ms); int rtcm_MT1077_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms);
int rtcm_MT1087_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1087_rate_ms", rtcm_MSM_rate_ms), output_rate_ms); int rtcm_MT1087_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1087_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms);
int rtcm_MT1097_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), output_rate_ms); int rtcm_MT1097_rate_ms = bc::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), pvt_output_parameters.output_rate_ms);
std::map<int, int> rtcm_msg_rate_ms; //std::map<int, int> rtcm_msg_rate_ms;
rtcm_msg_rate_ms[1019] = rtcm_MT1019_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[1019] = rtcm_MT1019_rate_ms;
rtcm_msg_rate_ms[1020] = rtcm_MT1020_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[1020] = rtcm_MT1020_rate_ms;
rtcm_msg_rate_ms[1045] = rtcm_MT1045_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[1045] = rtcm_MT1045_rate_ms;
for (int k = 1071; k < 1078; k++) // All GPS MSM for (int k = 1071; k < 1078; k++) // All GPS MSM
{ {
rtcm_msg_rate_ms[k] = rtcm_MT1077_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1077_rate_ms;
} }
for (int k = 1081; k < 1088; k++) // All GLONASS MSM for (int k = 1081; k < 1088; k++) // All GLONASS MSM
{ {
rtcm_msg_rate_ms[k] = rtcm_MT1087_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1087_rate_ms;
} }
for (int k = 1091; k < 1098; k++) // All Galileo MSM for (int k = 1091; k < 1098; k++) // All Galileo MSM
{ {
rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms; pvt_output_parameters.rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms;
} }
// Infer the type of receiver // Infer the type of receiver
@ -176,42 +178,42 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
int glo_1G_count = configuration->property("Channels_1G.count", 0); int glo_1G_count = configuration->property("Channels_1G.count", 0);
int glo_2G_count = configuration->property("Channels_2G.count", 0); int glo_2G_count = configuration->property("Channels_2G.count", 0);
unsigned int type_of_receiver = 0; //unsigned int type_of_receiver = 0;
// *******************WARNING!!!!!!!*********** // *******************WARNING!!!!!!!***********
// GPS L5 only configurable for single frequency, single system at the moment!!!!!! // GPS L5 only configurable for single frequency, single system at the moment!!!!!!
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 1; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 1;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 2; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 2;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 3; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 3;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 4; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 4;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 5; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 5;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 6; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 6;
if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 7; if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 7;
//if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 8; //if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 8;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 9; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 9;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 10; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 10;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 11; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 11;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 12; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 12;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 13; //if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 13;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 14; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 14;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 15; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 15;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 16; //if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 16;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 17; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 17;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 18; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 18;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 19; //if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 19;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 20; //if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 20;
if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 21; if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 21;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count = 0)) type_of_receiver = 22; //if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count = 0)) pvt_output_parameters.type_of_receiver = 22;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0)) type_of_receiver = 23; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0)) pvt_output_parameters.type_of_receiver = 23;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 24; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) pvt_output_parameters.type_of_receiver = 24;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0)) type_of_receiver = 25; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0)) pvt_output_parameters.type_of_receiver = 25;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 26; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 26;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 27; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 27;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 28; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) pvt_output_parameters.type_of_receiver = 28;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 29; if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) pvt_output_parameters.type_of_receiver = 29;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 30; if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) pvt_output_parameters.type_of_receiver = 30;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 31; if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) pvt_output_parameters.type_of_receiver = 31;
//RTKLIB PVT solver options //RTKLIB PVT solver options
// Settings 1 // Settings 1
int positioning_mode = -1; int positioning_mode = -1;
@ -477,8 +479,29 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
rtkinit(&rtk, &rtklib_configuration_options); rtkinit(&rtk, &rtklib_configuration_options);
// Outputs
bool default_output_enabled = configuration->property(role + ".output_enabled", true);
pvt_output_parameters.output_enabled = default_output_enabled;
pvt_output_parameters.rinex_output_enabled = configuration->property(role + ".rinex_output_enabled", default_output_enabled);
pvt_output_parameters.gpx_output_enabled = configuration->property(role + ".gpx_output_enabled", default_output_enabled);
pvt_output_parameters.geojson_output_enabled = configuration->property(role + ".geojson_output_enabled", default_output_enabled);
pvt_output_parameters.kml_output_enabled = configuration->property(role + ".kml_output_enabled", default_output_enabled);
pvt_output_parameters.xml_output_enabled = configuration->property(role + ".xml_output_enabled", default_output_enabled);
pvt_output_parameters.nmea_output_file_enabled = configuration->property(role + ".nmea_output_file_enabled", default_output_enabled);
pvt_output_parameters.rtcm_output_file_enabled = configuration->property(role + ".rtcm_output_file_enabled", default_output_enabled);
std::string default_output_path = configuration->property(role + ".output_path", std::string("."));
pvt_output_parameters.output_path = default_output_path;
pvt_output_parameters.rinex_output_path = configuration->property(role + ".rinex_output_path", default_output_path);
pvt_output_parameters.gpx_output_path = configuration->property(role + ".gpx_output_path", default_output_path);
pvt_output_parameters.geojson_output_path = configuration->property(role + ".geojson_output_path", default_output_path);
pvt_output_parameters.kml_output_path = configuration->property(role + ".kml_output_path", default_output_path);
pvt_output_parameters.xml_output_path = configuration->property(role + ".xml_output_path", default_output_path);
pvt_output_parameters.nmea_output_file_path = configuration->property(role + ".nmea_output_file_path", default_output_path);
pvt_output_parameters.rtcm_output_file_path = configuration->property(role + ".rtcm_output_file_path", default_output_path);
// make PVT object // make PVT object
pvt_ = rtklib_make_pvt_cc(in_streams_, dump_, dump_filename_, output_rate_ms, display_rate_ms, flag_nmea_tty_port, nmea_dump_filename, nmea_dump_devname, rinex_version, rinexobs_rate_ms, rinexnav_rate_ms, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_msg_rate_ms, rtcm_dump_devname, type_of_receiver, rtk); pvt_ = rtklib_make_pvt_cc(in_streams_, pvt_output_parameters, rtk);
DLOG(INFO) << "pvt(" << pvt_->unique_id() << ")"; DLOG(INFO) << "pvt(" << pvt_->unique_id() << ")";
if (out_streams_ > 0) if (out_streams_ > 0)
{ {

View File

@ -31,6 +31,7 @@
#include "rtklib_pvt_cc.h" #include "rtklib_pvt_cc.h"
#include "galileo_almanac.h" #include "galileo_almanac.h"
#include "galileo_almanac_helper.h" #include "galileo_almanac_helper.h"
#include "pvt_conf.h"
#include "display.h" #include "display.h"
#include <boost/archive/xml_oarchive.hpp> #include <boost/archive/xml_oarchive.hpp>
#include <boost/archive/xml_iarchive.hpp> #include <boost/archive/xml_iarchive.hpp>
@ -56,43 +57,11 @@ using google::LogMessage;
rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t nchannels, rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t nchannels,
bool dump, const Pvt_Conf& conf_,
std::string dump_filename,
int32_t output_rate_ms,
int32_t display_rate_ms,
bool flag_nmea_tty_port,
std::string nmea_dump_filename,
std::string nmea_dump_devname,
int32_t rinex_version,
int32_t rinexobs_rate_ms,
int32_t rinexnav_rate_ms,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
std::map<int, int> rtcm_msg_rate_ms,
std::string rtcm_dump_devname,
const uint32_t type_of_receiver,
rtk_t& rtk) rtk_t& rtk)
{ {
return rtklib_pvt_cc_sptr(new rtklib_pvt_cc(nchannels, return rtklib_pvt_cc_sptr(new rtklib_pvt_cc(nchannels,
dump, conf_,
dump_filename,
output_rate_ms,
display_rate_ms,
flag_nmea_tty_port,
nmea_dump_filename,
nmea_dump_devname,
rinex_version,
rinexobs_rate_ms,
rinexnav_rate_ms,
flag_rtcm_server,
flag_rtcm_tty_port,
rtcm_tcp_port,
rtcm_station_id,
rtcm_msg_rate_ms,
rtcm_dump_devname,
type_of_receiver,
rtk)); rtk));
} }
@ -270,34 +239,18 @@ std::map<int, Gps_Ephemeris> rtklib_pvt_cc::get_GPS_L1_ephemeris_map()
rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels, rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
bool dump, const Pvt_Conf& conf_,
std::string dump_filename,
int32_t output_rate_ms,
int32_t display_rate_ms,
bool flag_nmea_tty_port,
std::string nmea_dump_filename,
std::string nmea_dump_devname,
int32_t rinex_version,
int32_t rinexobs_rate_ms,
int32_t rinexnav_rate_ms,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
std::map<int, int> rtcm_msg_rate_ms,
std::string rtcm_dump_devname,
const uint32_t type_of_receiver,
rtk_t& rtk) : gr::sync_block("rtklib_pvt_cc", rtk_t& rtk) : gr::sync_block("rtklib_pvt_cc",
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_output_rate_ms = output_rate_ms; d_output_rate_ms = conf_.output_rate_ms;
d_display_rate_ms = display_rate_ms; d_display_rate_ms = conf_.display_rate_ms;
d_dump = dump; d_dump = conf_.dump;
d_nchannels = nchannels; d_nchannels = nchannels;
d_dump_filename = dump_filename; d_dump_filename = conf_.dump_filename;
std::string dump_ls_pvt_filename = dump_filename; std::string dump_ls_pvt_filename = conf_.dump_filename;
type_of_rx = type_of_receiver; type_of_rx = conf_.type_of_receiver;
// GPS Ephemeris data message port in // GPS Ephemeris data message port in
this->message_port_register_in(pmt::mp("telemetry")); this->message_port_register_in(pmt::mp("telemetry"));
@ -306,28 +259,54 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
// initialize kml_printer // initialize kml_printer
std::string kml_dump_filename; std::string kml_dump_filename;
kml_dump_filename = d_dump_filename; kml_dump_filename = d_dump_filename;
d_kml_dump = std::make_shared<Kml_Printer>(); d_kml_output_enabled = conf_.kml_output_enabled;
if (d_kml_output_enabled)
{
d_kml_dump = std::make_shared<Kml_Printer>(conf_.kml_output_path);
d_kml_dump->set_headers(kml_dump_filename); d_kml_dump->set_headers(kml_dump_filename);
}
else
{
d_kml_dump = nullptr;
}
// initialize gpx_printer // initialize gpx_printer
std::string gpx_dump_filename; std::string gpx_dump_filename;
gpx_dump_filename = d_dump_filename; gpx_dump_filename = d_dump_filename;
d_gpx_dump = std::make_shared<Gpx_Printer>(); d_gpx_output_enabled = conf_.gpx_output_enabled;
if (d_gpx_output_enabled)
{
d_gpx_dump = std::make_shared<Gpx_Printer>(conf_.gpx_output_path);
d_gpx_dump->set_headers(gpx_dump_filename); d_gpx_dump->set_headers(gpx_dump_filename);
}
else
{
d_gpx_dump = nullptr;
}
// initialize geojson_printer // initialize geojson_printer
std::string geojson_dump_filename; std::string geojson_dump_filename;
geojson_dump_filename = d_dump_filename; geojson_dump_filename = d_dump_filename;
d_geojson_printer = std::make_shared<GeoJSON_Printer>();
d_geojson_output_enabled = conf_.geojson_output_enabled;
if (d_geojson_output_enabled)
{
d_geojson_printer = std::make_shared<GeoJSON_Printer>(conf_.geojson_output_path);
d_geojson_printer->set_headers(geojson_dump_filename); d_geojson_printer->set_headers(geojson_dump_filename);
}
else
{
d_geojson_printer = nullptr;
}
// initialize nmea_printer // initialize nmea_printer
d_nmea_printer = std::make_shared<Nmea_Printer>(nmea_dump_filename, flag_nmea_tty_port, nmea_dump_devname); d_nmea_printer = std::make_shared<Nmea_Printer>(conf_.nmea_dump_filename, conf_.nmea_output_file_enabled, conf_.flag_nmea_tty_port, conf_.nmea_dump_devname, conf_.nmea_output_file_path);
// initialize rtcm_printer // initialize rtcm_printer
std::string rtcm_dump_filename; std::string rtcm_dump_filename;
rtcm_dump_filename = d_dump_filename; rtcm_dump_filename = d_dump_filename;
d_rtcm_printer = std::make_shared<Rtcm_Printer>(rtcm_dump_filename, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_dump_devname); d_rtcm_printer = std::make_shared<Rtcm_Printer>(rtcm_dump_filename, conf_.rtcm_output_file_enabled, conf_.flag_rtcm_server, conf_.flag_rtcm_tty_port, conf_.rtcm_tcp_port, conf_.rtcm_station_id, conf_.rtcm_dump_devname, true, conf_.rtcm_output_file_path);
std::map<int, int> rtcm_msg_rate_ms = conf_.rtcm_msg_rate_ms;
if (rtcm_msg_rate_ms.find(1019) != rtcm_msg_rate_ms.end()) if (rtcm_msg_rate_ms.find(1019) != rtcm_msg_rate_ms.end())
{ {
d_rtcm_MT1019_rate_ms = rtcm_msg_rate_ms[1019]; d_rtcm_MT1019_rate_ms = rtcm_msg_rate_ms[1019];
@ -383,10 +362,55 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
// initialize RINEX printer // initialize RINEX printer
b_rinex_header_written = false; b_rinex_header_written = false;
b_rinex_header_updated = false; b_rinex_header_updated = false;
d_rinex_version = rinex_version; b_rinex_output_enabled = conf_.rinex_output_enabled;
rp = std::make_shared<Rinex_Printer>(d_rinex_version); d_rinex_version = conf_.rinex_version;
d_rinexobs_rate_ms = rinexobs_rate_ms; if (b_rinex_output_enabled)
d_rinexnav_rate_ms = rinexnav_rate_ms; {
rp = std::make_shared<Rinex_Printer>(d_rinex_version, conf_.rinex_output_path);
}
else
{
rp = nullptr;
}
d_rinexobs_rate_ms = conf_.rinexobs_rate_ms;
d_rinexnav_rate_ms = conf_.rinexnav_rate_ms;
// XML printer
d_xml_storage = conf_.xml_output_enabled;
if (d_xml_storage)
{
xml_base_path = conf_.xml_output_path;
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(xml_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(xml_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
xml_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
xml_base_path = p.string();
}
if (xml_base_path.compare(".") != 0)
{
std::cout << "XML files will be stored at " << xml_base_path << std::endl;
}
xml_base_path = xml_base_path + boost::filesystem::path::preferred_separator;
}
dump_ls_pvt_filename.append("_pvt.dat"); dump_ls_pvt_filename.append("_pvt.dat");
@ -397,7 +421,6 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
d_last_status_print_seg = 0; d_last_status_print_seg = 0;
// Create Sys V message queue // Create Sys V message queue
first_fix = true; first_fix = true;
sysv_msg_key = 1101; sysv_msg_key = 1101;
@ -414,9 +437,10 @@ rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
rtklib_pvt_cc::~rtklib_pvt_cc() rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
msgctl(sysv_msqid, IPC_RMID, NULL); msgctl(sysv_msqid, IPC_RMID, NULL);
if (d_xml_storage)
{
// save GPS L2CM ephemeris to XML file // save GPS L2CM ephemeris to XML file
std::string file_name = "gps_cnav_ephemeris.xml"; std::string file_name = xml_base_path + "gps_cnav_ephemeris.xml";
if (d_ls_pvt->gps_cnav_ephemeris_map.empty() == false) if (d_ls_pvt->gps_cnav_ephemeris_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -438,7 +462,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// save GPS L1 CA ephemeris to XML file // save GPS L1 CA ephemeris to XML file
file_name = "gps_ephemeris.xml"; file_name = xml_base_path + "gps_ephemeris.xml";
if (d_ls_pvt->gps_ephemeris_map.empty() == false) if (d_ls_pvt->gps_ephemeris_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -460,7 +484,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// save Galileo E1 ephemeris to XML file // save Galileo E1 ephemeris to XML file
file_name = "gal_ephemeris.xml"; file_name = xml_base_path + "gal_ephemeris.xml";
if (d_ls_pvt->galileo_ephemeris_map.empty() == false) if (d_ls_pvt->galileo_ephemeris_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -482,7 +506,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// save GLONASS GNAV ephemeris to XML file // save GLONASS GNAV ephemeris to XML file
file_name = "eph_GLONASS_GNAV.xml"; file_name = xml_base_path + "eph_GLONASS_GNAV.xml";
if (d_ls_pvt->glonass_gnav_ephemeris_map.empty() == false) if (d_ls_pvt->glonass_gnav_ephemeris_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -504,7 +528,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// Save GPS UTC model parameters // Save GPS UTC model parameters
file_name = "gps_utc_model.xml"; file_name = xml_base_path + "gps_utc_model.xml";
if (d_ls_pvt->gps_utc_model.valid) if (d_ls_pvt->gps_utc_model.valid)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -526,7 +550,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// Save Galileo UTC model parameters // Save Galileo UTC model parameters
file_name = "gal_utc_model.xml"; file_name = xml_base_path + "gal_utc_model.xml";
if (d_ls_pvt->galileo_utc_model.Delta_tLS_6 != 0.0) if (d_ls_pvt->galileo_utc_model.Delta_tLS_6 != 0.0)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -547,8 +571,74 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
LOG(INFO) << "Failed to save Galileo UTC model parameters, not valid data"; LOG(INFO) << "Failed to save Galileo UTC model parameters, not valid data";
} }
// Save GPS iono parameters
file_name = xml_base_path + "gps_iono.xml";
if (d_ls_pvt->gps_iono.valid == true)
{
std::ofstream ofs;
try
{
ofs.open(file_name.c_str(), std::ofstream::trunc | std::ofstream::out);
boost::archive::xml_oarchive xml(ofs);
xml << boost::serialization::make_nvp("GNSS-SDR_iono_model", d_ls_pvt->gps_iono);
LOG(INFO) << "Saved GPS ionospheric model parameters";
}
catch (std::exception& e)
{
LOG(WARNING) << e.what();
}
}
else
{
LOG(INFO) << "Failed to save GPS ionospheric model parameters, not valid data";
}
// Save GPS CNAV iono parameters
file_name = xml_base_path + "gps_cnav_iono.xml";
if (d_ls_pvt->gps_cnav_iono.valid == true)
{
std::ofstream ofs;
try
{
ofs.open(file_name.c_str(), std::ofstream::trunc | std::ofstream::out);
boost::archive::xml_oarchive xml(ofs);
xml << boost::serialization::make_nvp("GNSS-SDR_cnav_iono_model", d_ls_pvt->gps_cnav_iono);
LOG(INFO) << "Saved GPS CNAV ionospheric model parameters";
}
catch (std::exception& e)
{
LOG(WARNING) << e.what();
}
}
else
{
LOG(INFO) << "Failed to save GPS CNAV ionospheric model parameters, not valid data";
}
// Save Galileo iono parameters
file_name = xml_base_path + "gal_iono.xml";
if (d_ls_pvt->galileo_iono.ai0_5 != 0.0)
{
std::ofstream ofs;
try
{
ofs.open(file_name.c_str(), std::ofstream::trunc | std::ofstream::out);
boost::archive::xml_oarchive xml(ofs);
xml << boost::serialization::make_nvp("GNSS-SDR_gal_iono_model", d_ls_pvt->galileo_iono);
LOG(INFO) << "Saved Galileo ionospheric model parameters";
}
catch (std::exception& e)
{
LOG(WARNING) << e.what();
}
}
else
{
LOG(INFO) << "Failed to save Galileo ionospheric model parameters, not valid data";
}
// save GPS almanac to XML file // save GPS almanac to XML file
file_name = "gps_almanac.xml"; file_name = xml_base_path + "gps_almanac.xml";
if (d_ls_pvt->gps_almanac_map.empty() == false) if (d_ls_pvt->gps_almanac_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -570,7 +660,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// Save Galileo almanac // Save Galileo almanac
file_name = "gal_almanac.xml"; file_name = xml_base_path + "gal_almanac.xml";
if (d_ls_pvt->galileo_almanac_map.empty() == false) if (d_ls_pvt->galileo_almanac_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -592,7 +682,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// Save GPS CNAV UTC model parameters // Save GPS CNAV UTC model parameters
file_name = "gps_cnav_utc_model.xml"; file_name = xml_base_path + "gps_cnav_utc_model.xml";
if (d_ls_pvt->gps_cnav_utc_model.valid) if (d_ls_pvt->gps_cnav_utc_model.valid)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -614,7 +704,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// save GLONASS GNAV ephemeris to XML file // save GLONASS GNAV ephemeris to XML file
file_name = "glo_gnav_ephemeris.xml"; file_name = xml_base_path + "glo_gnav_ephemeris.xml";
if (d_ls_pvt->glonass_gnav_ephemeris_map.empty() == false) if (d_ls_pvt->glonass_gnav_ephemeris_map.empty() == false)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -636,7 +726,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
} }
// save GLONASS UTC model parameters to XML file // save GLONASS UTC model parameters to XML file
file_name = "glo_utc_model.xml"; file_name = xml_base_path + "glo_utc_model.xml";
if (d_ls_pvt->glonass_gnav_utc_model.valid) if (d_ls_pvt->glonass_gnav_utc_model.valid)
{ {
std::ofstream ofs; std::ofstream ofs;
@ -657,6 +747,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
LOG(INFO) << "Failed to save GLONASS GNAV ephemeris, not valid data"; LOG(INFO) << "Failed to save GLONASS GNAV ephemeris, not valid data";
} }
} }
}
bool rtklib_pvt_cc::observables_pairCompare_min(const std::pair<int, Gnss_Synchro>& a, const std::pair<int, Gnss_Synchro>& b) bool rtklib_pvt_cc::observables_pairCompare_min(const std::pair<int, Gnss_Synchro>& a, const std::pair<int, Gnss_Synchro>& b)
@ -897,9 +988,9 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
send_sys_v_ttff_msg(ttff); send_sys_v_ttff_msg(ttff);
first_fix = false; first_fix = false;
} }
d_kml_dump->print_position(d_ls_pvt, false); if (d_kml_output_enabled) d_kml_dump->print_position(d_ls_pvt, false);
d_gpx_dump->print_position(d_ls_pvt, false); if (d_gpx_output_enabled) d_gpx_dump->print_position(d_ls_pvt, false);
d_geojson_printer->print_position(d_ls_pvt, false); if (d_geojson_output_enabled) d_geojson_printer->print_position(d_ls_pvt, false);
d_nmea_printer->Print_Nmea_Line(d_ls_pvt, false); d_nmea_printer->Print_Nmea_Line(d_ls_pvt, false);
/* /*
@ -937,15 +1028,15 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
* 30 | Galileo E1B + GLONASS L2 C/A * 30 | Galileo E1B + GLONASS L2 C/A
* 31 | GPS L2C + GLONASS L2 C/A * 31 | GPS L2C + GLONASS L2 C/A
*/ */
// ####################### RINEX FILES #################
std::map<int, Galileo_Ephemeris>::const_iterator galileo_ephemeris_iter; std::map<int, Galileo_Ephemeris>::const_iterator galileo_ephemeris_iter;
std::map<int, Gps_Ephemeris>::const_iterator gps_ephemeris_iter; std::map<int, Gps_Ephemeris>::const_iterator gps_ephemeris_iter;
std::map<int, Gps_CNAV_Ephemeris>::const_iterator gps_cnav_ephemeris_iter; std::map<int, Gps_CNAV_Ephemeris>::const_iterator gps_cnav_ephemeris_iter;
std::map<int, Glonass_Gnav_Ephemeris>::const_iterator glonass_gnav_ephemeris_iter; std::map<int, Glonass_Gnav_Ephemeris>::const_iterator glonass_gnav_ephemeris_iter;
std::map<int, Gnss_Synchro>::const_iterator gnss_observables_iter; std::map<int, Gnss_Synchro>::const_iterator gnss_observables_iter;
// ####################### RINEX FILES #################
if (b_rinex_output_enabled)
{
if (!b_rinex_header_written) // & we have utc data in nav message! if (!b_rinex_header_written) // & we have utc data in nav message!
{ {
galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin(); galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin();
@ -1175,6 +1266,8 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
} }
} }
} }
if (b_rinex_header_written) // The header is already written, we can now log the navigation message data if (b_rinex_header_written) // The header is already written, we can now log the navigation message data
{ {
if (flag_write_RINEX_nav_output) if (flag_write_RINEX_nav_output)
@ -1505,7 +1598,7 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
} }
} }
} }
}
// ####################### RTCM MESSAGES ################# // ####################### RTCM MESSAGES #################
try try
{ {

View File

@ -38,6 +38,7 @@
#include "geojson_printer.h" #include "geojson_printer.h"
#include "rinex_printer.h" #include "rinex_printer.h"
#include "rtcm_printer.h" #include "rtcm_printer.h"
#include "pvt_conf.h"
#include "rtklib_solver.h" #include "rtklib_solver.h"
#include <gnuradio/sync_block.h> #include <gnuradio/sync_block.h>
#include <sys/types.h> #include <sys/types.h>
@ -55,23 +56,7 @@ class rtklib_pvt_cc;
typedef boost::shared_ptr<rtklib_pvt_cc> rtklib_pvt_cc_sptr; typedef boost::shared_ptr<rtklib_pvt_cc> rtklib_pvt_cc_sptr;
rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t n_channels, rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t n_channels,
bool dump, const Pvt_Conf& conf_,
std::string dump_filename,
int32_t output_rate_ms,
int32_t display_rate_ms,
bool flag_nmea_tty_port,
std::string nmea_dump_filename,
std::string nmea_dump_devname,
int32_t rinex_version,
int32_t rinexobs_rate_ms,
int32_t rinexnav_rate_ms,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
std::map<int, int> rtcm_msg_rate_ms,
std::string rtcm_dump_devname,
const uint32_t type_of_receiver,
rtk_t& rtk); rtk_t& rtk);
/*! /*!
@ -81,28 +66,13 @@ class rtklib_pvt_cc : public gr::sync_block
{ {
private: private:
friend rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t nchannels, friend rtklib_pvt_cc_sptr rtklib_make_pvt_cc(uint32_t nchannels,
bool dump, const Pvt_Conf& conf_,
std::string dump_filename,
int32_t output_rate_ms,
int32_t display_rate_ms,
bool flag_nmea_tty_port,
std::string nmea_dump_filename,
std::string nmea_dump_devname,
int32_t rinex_version,
int32_t rinexobs_rate_ms,
int32_t rinexnav_rate_ms,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
std::map<int, int> rtcm_msg_rate_ms,
std::string rtcm_dump_devname,
const uint32_t type_of_receiver,
rtk_t& rtk); rtk_t& rtk);
void msg_handler_telemetry(pmt::pmt_t msg); void msg_handler_telemetry(pmt::pmt_t msg);
bool d_dump; bool d_dump;
bool b_rinex_output_enabled;
bool b_rinex_header_written; bool b_rinex_header_written;
bool b_rinex_header_updated; bool b_rinex_header_updated;
double d_rinex_version; double d_rinex_version;
@ -134,6 +104,10 @@ private:
std::shared_ptr<Rtcm_Printer> d_rtcm_printer; std::shared_ptr<Rtcm_Printer> d_rtcm_printer;
double d_rx_time; double d_rx_time;
bool d_geojson_output_enabled;
bool d_gpx_output_enabled;
bool d_kml_output_enabled;
std::shared_ptr<rtklib_solver> d_ls_pvt; std::shared_ptr<rtklib_solver> d_ls_pvt;
std::map<int, Gnss_Synchro> gnss_observables_map; std::map<int, Gnss_Synchro> gnss_observables_map;
@ -156,24 +130,13 @@ private:
bool load_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_xml_storage;
std::string xml_base_path;
public: public:
rtklib_pvt_cc(uint32_t nchannels, rtklib_pvt_cc(uint32_t nchannels,
bool dump, std::string dump_filename, const Pvt_Conf& conf_,
int32_t output_rate_ms,
int32_t display_rate_ms,
bool flag_nmea_tty_port,
std::string nmea_dump_filename,
std::string nmea_dump_devname,
int32_t rinex_version,
int32_t rinexobs_rate_ms,
int32_t rinexnav_rate_ms,
bool flag_rtcm_server,
bool flag_rtcm_tty_port,
uint16_t rtcm_tcp_port,
uint16_t rtcm_station_id,
std::map<int, int> rtcm_msg_rate_ms,
std::string rtcm_dump_devname,
const uint32_t type_of_receiver,
rtk_t& rtk); rtk_t& rtk);
/*! /*!

View File

@ -29,6 +29,7 @@ set(PVT_LIB_SOURCES
rtcm_printer.cc rtcm_printer.cc
geojson_printer.cc geojson_printer.cc
rtklib_solver.cc rtklib_solver.cc
pvt_conf.cc
) )
set(PVT_LIB_HEADERS set(PVT_LIB_HEADERS
@ -42,6 +43,7 @@ set(PVT_LIB_HEADERS
rtcm_printer.h rtcm_printer.h
geojson_printer.h geojson_printer.h
rtklib_solver.h rtklib_solver.h
pvt_conf.h
) )

View File

@ -32,14 +32,48 @@
#include "geojson_printer.h" #include "geojson_printer.h"
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <iomanip> #include <iomanip>
#include <sstream> #include <sstream>
GeoJSON_Printer::GeoJSON_Printer() GeoJSON_Printer::GeoJSON_Printer(const std::string& base_path)
{ {
first_pos = true; first_pos = true;
geojson_base_path = base_path;
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(geojson_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(geojson_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
geojson_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
geojson_base_path = p.string();
}
if (geojson_base_path.compare(".") != 0)
{
std::cout << "GeoJSON files will be stored at " << geojson_base_path << std::endl;
}
geojson_base_path = geojson_base_path + boost::filesystem::path::preferred_separator;
} }
@ -96,6 +130,7 @@ bool GeoJSON_Printer::set_headers(std::string filename, bool time_tag_name)
{ {
filename_ = filename + ".geojson"; filename_ = filename + ".geojson";
} }
filename_ = geojson_base_path + filename_;
geojson_file.open(filename_.c_str()); geojson_file.open(filename_.c_str());
@ -124,6 +159,7 @@ bool GeoJSON_Printer::set_headers(std::string filename, bool time_tag_name)
} }
else else
{ {
std::cout << "File " << filename_ << " cannot be saved. Wrong permissions?" << std::endl;
return false; return false;
} }
} }

View File

@ -50,9 +50,10 @@ private:
std::ofstream geojson_file; std::ofstream geojson_file;
bool first_pos; bool first_pos;
std::string filename_; std::string filename_;
std::string geojson_base_path;
public: public:
GeoJSON_Printer(); GeoJSON_Printer(const std::string& base_path = ".");
~GeoJSON_Printer(); ~GeoJSON_Printer();
bool set_headers(std::string filename, bool time_tag_name = true); bool set_headers(std::string filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values); bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values);

View File

@ -32,11 +32,53 @@
#include "gpx_printer.h" #include "gpx_printer.h"
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <sstream> #include <sstream>
using google::LogMessage; using google::LogMessage;
Gpx_Printer::Gpx_Printer(const std::string& base_path)
{
positions_printed = false;
indent = " ";
gpx_base_path = base_path;
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(gpx_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(gpx_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
gpx_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
gpx_base_path = p.string();
}
if (gpx_base_path.compare(".") != 0)
{
std::cout << "GPX files will be stored at " << gpx_base_path << std::endl;
}
gpx_base_path = gpx_base_path + boost::filesystem::path::preferred_separator;
}
bool Gpx_Printer::set_headers(std::string filename, bool time_tag_name) bool Gpx_Printer::set_headers(std::string filename, bool time_tag_name)
{ {
boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time(); boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time();
@ -84,6 +126,8 @@ bool Gpx_Printer::set_headers(std::string filename, bool time_tag_name)
{ {
gpx_filename = filename + ".gpx"; gpx_filename = filename + ".gpx";
} }
gpx_filename = gpx_base_path + gpx_filename;
gpx_file.open(gpx_filename.c_str()); gpx_file.open(gpx_filename.c_str());
if (gpx_file.is_open()) if (gpx_file.is_open())
@ -105,6 +149,7 @@ bool Gpx_Printer::set_headers(std::string filename, bool time_tag_name)
} }
else else
{ {
std::cout << "File " << gpx_filename << " cannot be saved. Wrong permissions?" << std::endl;
return false; return false;
} }
} }
@ -171,13 +216,6 @@ bool Gpx_Printer::close_file()
} }
Gpx_Printer::Gpx_Printer()
{
positions_printed = false;
indent = " ";
}
Gpx_Printer::~Gpx_Printer() Gpx_Printer::~Gpx_Printer()
{ {
close_file(); close_file();

View File

@ -52,9 +52,10 @@ private:
bool positions_printed; bool positions_printed;
std::string gpx_filename; std::string gpx_filename;
std::string indent; std::string indent;
std::string gpx_base_path;
public: public:
Gpx_Printer(); Gpx_Printer(const std::string& base_path = ".");
~Gpx_Printer(); ~Gpx_Printer();
bool set_headers(std::string filename, bool time_tag_name = true); bool set_headers(std::string filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<rtklib_solver>& position, bool print_average_values); bool print_position(const std::shared_ptr<rtklib_solver>& position, bool print_average_values);

View File

@ -31,11 +31,52 @@
#include "kml_printer.h" #include "kml_printer.h"
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <sstream> #include <sstream>
using google::LogMessage; using google::LogMessage;
Kml_Printer::Kml_Printer(const std::string& base_path)
{
positions_printed = false;
kml_base_path = base_path;
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(kml_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(kml_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
kml_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
kml_base_path = p.string();
}
if (kml_base_path.compare(".") != 0)
{
std::cout << "KML files will be stored at " << kml_base_path << std::endl;
}
kml_base_path = kml_base_path + boost::filesystem::path::preferred_separator;
}
bool Kml_Printer::set_headers(std::string filename, bool time_tag_name) bool Kml_Printer::set_headers(std::string filename, bool time_tag_name)
{ {
boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time(); boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time();
@ -83,6 +124,7 @@ bool Kml_Printer::set_headers(std::string filename, bool time_tag_name)
{ {
kml_filename = filename + ".kml"; kml_filename = filename + ".kml";
} }
kml_filename = kml_base_path + kml_filename;
kml_file.open(kml_filename.c_str()); kml_file.open(kml_filename.c_str());
if (kml_file.is_open()) if (kml_file.is_open())
@ -119,6 +161,7 @@ bool Kml_Printer::set_headers(std::string filename, bool time_tag_name)
} }
else else
{ {
std::cout << "File " << kml_filename << " cannot be saved. Wrong permissions?" << std::endl;
return false; return false;
} }
} }
@ -178,12 +221,6 @@ bool Kml_Printer::close_file()
} }
Kml_Printer::Kml_Printer()
{
positions_printed = false;
}
Kml_Printer::~Kml_Printer() Kml_Printer::~Kml_Printer()
{ {
close_file(); close_file();

View File

@ -50,9 +50,10 @@ private:
std::ofstream kml_file; std::ofstream kml_file;
bool positions_printed; bool positions_printed;
std::string kml_filename; std::string kml_filename;
std::string kml_base_path;
public: public:
Kml_Printer(); Kml_Printer(const std::string& base_path = std::string("."));
~Kml_Printer(); ~Kml_Printer();
bool set_headers(std::string filename, bool time_tag_name = true); bool set_headers(std::string filename, bool time_tag_name = true);
bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values); bool print_position(const std::shared_ptr<Pvt_Solution>& position, bool print_average_values);

View File

@ -35,6 +35,9 @@
#include "nmea_printer.h" #include "nmea_printer.h"
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <cstdint> #include <cstdint>
#include <fcntl.h> #include <fcntl.h>
@ -44,14 +47,56 @@
using google::LogMessage; using google::LogMessage;
Nmea_Printer::Nmea_Printer(std::string filename, bool flag_nmea_tty_port, std::string nmea_dump_devname) Nmea_Printer::Nmea_Printer(std::string filename, bool flag_nmea_output_file, bool flag_nmea_tty_port, std::string nmea_dump_devname, const std::string& base_path)
{ {
nmea_filename = filename; nmea_base_path = base_path;
d_flag_nmea_output_file = flag_nmea_output_file;
if (d_flag_nmea_output_file == true)
{
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(nmea_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(nmea_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
nmea_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
nmea_base_path = p.string();
}
if ((nmea_base_path.compare(".") != 0) and (d_flag_nmea_output_file == true))
{
std::cout << "NMEA files will be stored at " << nmea_base_path << std::endl;
}
nmea_base_path = nmea_base_path + boost::filesystem::path::preferred_separator;
nmea_filename = nmea_base_path + filename;
nmea_file_descriptor.open(nmea_filename.c_str(), std::ios::out); nmea_file_descriptor.open(nmea_filename.c_str(), std::ios::out);
if (nmea_file_descriptor.is_open()) if (nmea_file_descriptor.is_open())
{ {
DLOG(INFO) << "NMEA printer writing on " << nmea_filename.c_str(); DLOG(INFO) << "NMEA printer writing on " << nmea_filename.c_str();
} }
else
{
std::cout << "File " << nmea_filename << " cannot be saved. Wrong permissions?" << std::endl;
}
}
nmea_devname = nmea_dump_devname; nmea_devname = nmea_dump_devname;
if (flag_nmea_tty_port == true) if (flag_nmea_tty_port == true)
@ -149,6 +194,8 @@ bool Nmea_Printer::Print_Nmea_Line(const std::shared_ptr<rtklib_solver>& pvt_dat
GPGSV = get_GPGSV(); GPGSV = get_GPGSV();
// write to log file // write to log file
if (d_flag_nmea_output_file)
{
try try
{ {
// GPRMC // GPRMC
@ -163,7 +210,7 @@ bool Nmea_Printer::Print_Nmea_Line(const std::shared_ptr<rtklib_solver>& pvt_dat
catch (const std::exception& ex) catch (const std::exception& ex)
{ {
DLOG(INFO) << "NMEA printer can not write on output file" << nmea_filename.c_str(); DLOG(INFO) << "NMEA printer can not write on output file" << nmea_filename.c_str();
; }
} }
// write to serial device // write to serial device
@ -348,7 +395,6 @@ std::string Nmea_Printer::get_GPRMC()
sentence_str << get_UTC_NMEA_time(d_PVT_data->get_position_UTC_time()); sentence_str << get_UTC_NMEA_time(d_PVT_data->get_position_UTC_time());
// Status: A: data valid, V: data NOT valid // Status: A: data valid, V: data NOT valid
if (valid_fix == true) if (valid_fix == true)
{ {
sentence_str << ",A"; sentence_str << ",A";

View File

@ -53,7 +53,7 @@ public:
/*! /*!
* \brief Default constructor. * \brief Default constructor.
*/ */
Nmea_Printer(std::string filename, bool flag_nmea_tty_port, std::string nmea_dump_filename); Nmea_Printer(std::string filename, bool flag_nmea_output_file, bool flag_nmea_tty_port, std::string nmea_dump_filename, const std::string& base_path = ".");
/*! /*!
* \brief Print NMEA PVT and satellite info to the initialized device * \brief Print NMEA PVT and satellite info to the initialized device
@ -67,6 +67,7 @@ public:
private: private:
std::string nmea_filename; // String with the NMEA log filename std::string nmea_filename; // String with the NMEA log filename
std::string nmea_base_path;
std::ofstream nmea_file_descriptor; // Output file stream for NMEA log file std::ofstream nmea_file_descriptor; // Output file stream for NMEA log file
std::string nmea_devname; std::string nmea_devname;
int nmea_dev_descriptor; // NMEA serial device descriptor (i.e. COM port) int nmea_dev_descriptor; // NMEA serial device descriptor (i.e. COM port)
@ -82,6 +83,7 @@ private:
std::string latitude_to_hm(double lat); std::string latitude_to_hm(double lat);
char checkSum(std::string sentence); char checkSum(std::string sentence);
bool print_avg_pos; bool print_avg_pos;
bool d_flag_nmea_output_file;
}; };
#endif #endif

View File

@ -0,0 +1,69 @@
/*!
* \file pvt_conf.cc
* \brief Class that contains all the configuration parameters for a PVT block
* \author Carles Fernandez, 2018. cfernandez(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "pvt_conf.h"
Pvt_Conf::Pvt_Conf()
{
type_of_receiver = 0U;
output_rate_ms = 0;
display_rate_ms = 0;
rinex_version = 0;
rinexobs_rate_ms = 0;
rinexnav_rate_ms = 0;
dump = false;
flag_nmea_tty_port = false;
flag_rtcm_server = false;
flag_rtcm_tty_port = false;
rtcm_tcp_port = 0U;
rtcm_station_id = 0U;
output_enabled = true;
rinex_output_enabled = true;
gpx_output_enabled = true;
geojson_output_enabled = true;
nmea_output_file_enabled = true;
kml_output_enabled = true;
xml_output_enabled = true;
rtcm_output_file_enabled = true;
output_path = std::string(".");
rinex_output_path = std::string(".");
gpx_output_path = std::string(".");
geojson_output_path = std::string(".");
nmea_output_file_path = std::string(".");
kml_output_path = std::string(".");
xml_output_path = std::string(".");
rtcm_output_file_path = std::string(".");
}

View File

@ -0,0 +1,85 @@
/*!
* \file pvt_conf.h
* \brief Class that contains all the configuration parameters for the PVT block
* \author Carles Fernandez, 2018. cfernandez(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_PVT_CONF_H_
#define GNSS_SDR_PVT_CONF_H_
#include <cstddef>
#include <cstdint>
#include <string>
#include <map>
class Pvt_Conf
{
public:
uint32_t type_of_receiver;
int32_t output_rate_ms;
int32_t display_rate_ms;
int32_t rinex_version;
int32_t rinexobs_rate_ms;
int32_t rinexnav_rate_ms;
std::map<int, int> rtcm_msg_rate_ms;
bool dump;
std::string dump_filename;
bool flag_nmea_tty_port;
std::string nmea_dump_filename;
std::string nmea_dump_devname;
bool flag_rtcm_server;
bool flag_rtcm_tty_port;
uint16_t rtcm_tcp_port;
uint16_t rtcm_station_id;
std::string rtcm_dump_devname;
bool output_enabled;
bool rinex_output_enabled;
bool gpx_output_enabled;
bool geojson_output_enabled;
bool nmea_output_file_enabled;
bool kml_output_enabled;
bool xml_output_enabled;
bool rtcm_output_file_enabled;
std::string output_path;
std::string rinex_output_path;
std::string gpx_output_path;
std::string geojson_output_path;
std::string nmea_output_file_path;
std::string kml_output_path;
std::string xml_output_path;
std::string rtcm_output_file_path;
Pvt_Conf();
};
#endif

View File

@ -33,6 +33,9 @@
#include <boost/date_time/gregorian/gregorian.hpp> #include <boost/date_time/gregorian/gregorian.hpp>
#include <boost/date_time/local_time/local_time.hpp> #include <boost/date_time/local_time/local_time.hpp>
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <unistd.h> // for getlogin_r() #include <unistd.h> // for getlogin_r()
#include <algorithm> // for min and max #include <algorithm> // for min and max
@ -48,14 +51,44 @@
using google::LogMessage; using google::LogMessage;
Rinex_Printer::Rinex_Printer(int32_t conf_version) Rinex_Printer::Rinex_Printer(int32_t conf_version, const std::string& base_path)
{ {
navfilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV"); std::string base_rinex_path = base_path;
obsfilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS"); boost::filesystem::path full_path(boost::filesystem::current_path());
sbsfilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS"); const boost::filesystem::path p(base_rinex_path);
navGalfilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV"); if (!boost::filesystem::exists(p))
navMixfilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV"); {
navGlofilename = Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV"); std::string new_folder;
for (auto& folder : boost::filesystem::path(base_rinex_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
base_rinex_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
base_rinex_path = p.string();
}
if (base_rinex_path.compare(".") != 0)
{
std::cout << "RINEX files will be stored at " << base_rinex_path << std::endl;
}
navfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GPS_NAV");
obsfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_OBS");
sbsfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_SBAS");
navGalfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GAL_NAV");
navMixfilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_MIXED_NAV");
navGlofilename = base_rinex_path + boost::filesystem::path::preferred_separator + Rinex_Printer::createFilename("RINEX_FILE_TYPE_GLO_NAV");
Rinex_Printer::navFile.open(navfilename, std::ios::out | std::ios::in | std::ios::app); 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::obsFile.open(obsfilename, std::ios::out | std::ios::in | std::ios::app);
@ -64,6 +97,13 @@ Rinex_Printer::Rinex_Printer(int32_t conf_version)
Rinex_Printer::navMixFile.open(navMixfilename, 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::navGloFile.open(navGlofilename, 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?" << std::endl;
}
// RINEX v3.02 codes // RINEX v3.02 codes
satelliteSystem["GPS"] = "G"; satelliteSystem["GPS"] = "G";
satelliteSystem["GLONASS"] = "R"; satelliteSystem["GLONASS"] = "R";

View File

@ -77,12 +77,12 @@ class Rinex_Printer
{ {
public: public:
/*! /*!
* \brief Default constructor. Creates GPS Navigation and Observables RINEX files and their headers * \brief Default constructor. Creates GNSS Navigation and Observables RINEX files and their headers
*/ */
Rinex_Printer(int version = 0); Rinex_Printer(int version = 0, const std::string& base_path = ".");
/*! /*!
* \brief Default destructor. Closes GPS Navigation and Observables RINEX files * \brief Default destructor. Closes GNSS Navigation and Observables RINEX files
*/ */
~Rinex_Printer(); ~Rinex_Printer();

View File

@ -33,6 +33,9 @@
#include "rtcm_printer.h" #include "rtcm_printer.h"
#include <boost/date_time/posix_time/posix_time.hpp> #include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/filesystem/operations.hpp> // for create_directories, exists
#include <boost/filesystem/path.hpp> // for path, operator<<
#include <boost/filesystem/path_traits.hpp> // for filesystem
#include <glog/logging.h> #include <glog/logging.h>
#include <iomanip> #include <iomanip>
#include <fcntl.h> // for O_RDWR #include <fcntl.h> // for O_RDWR
@ -42,10 +45,45 @@
using google::LogMessage; using google::LogMessage;
Rtcm_Printer::Rtcm_Printer(std::string filename, bool flag_rtcm_server, bool flag_rtcm_tty_port, uint16_t rtcm_tcp_port, uint16_t rtcm_station_id, std::string rtcm_dump_devname, bool time_tag_name) Rtcm_Printer::Rtcm_Printer(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, std::string rtcm_dump_devname, bool time_tag_name, const std::string& base_path)
{ {
boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time(); boost::posix_time::ptime pt = boost::posix_time::second_clock::local_time();
tm timeinfo = boost::posix_time::to_tm(pt); 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)
{
boost::filesystem::path full_path(boost::filesystem::current_path());
const boost::filesystem::path p(rtcm_base_path);
if (!boost::filesystem::exists(p))
{
std::string new_folder;
for (auto& folder : boost::filesystem::path(rtcm_base_path))
{
new_folder += folder.string();
boost::system::error_code ec;
if (!boost::filesystem::exists(new_folder))
{
if (!boost::filesystem::create_directory(new_folder, ec))
{
std::cout << "Could not create the " << new_folder << " folder." << std::endl;
rtcm_base_path = full_path.string();
}
}
new_folder += boost::filesystem::path::preferred_separator;
}
}
else
{
rtcm_base_path = p.string();
}
if (rtcm_base_path.compare(".") != 0)
{
std::cout << "RTCM binary file will be stored at " << rtcm_base_path << std::endl;
}
rtcm_base_path = rtcm_base_path + boost::filesystem::path::preferred_separator;
}
if (time_tag_name) if (time_tag_name)
{ {
@ -89,12 +127,19 @@ Rtcm_Printer::Rtcm_Printer(std::string filename, bool flag_rtcm_server, bool fla
{ {
rtcm_filename = filename + ".rtcm"; rtcm_filename = filename + ".rtcm";
} }
rtcm_filename = rtcm_base_path + rtcm_filename;
if (d_rtcm_file_dump)
{
rtcm_file_descriptor.open(rtcm_filename.c_str(), std::ios::out); rtcm_file_descriptor.open(rtcm_filename.c_str(), std::ios::out);
if (rtcm_file_descriptor.is_open()) if (rtcm_file_descriptor.is_open())
{ {
DLOG(INFO) << "RTCM printer writing on " << rtcm_filename.c_str(); DLOG(INFO) << "RTCM printer writing on " << rtcm_filename.c_str();
} }
else
{
std::cout << "File " << rtcm_filename << "cannot be saved. Wrong permissions?" << std::endl;
}
}
rtcm_devname = rtcm_dump_devname; rtcm_devname = rtcm_dump_devname;
if (flag_rtcm_tty_port == true) if (flag_rtcm_tty_port == true)
@ -341,6 +386,8 @@ void Rtcm_Printer::close_serial()
bool Rtcm_Printer::Print_Message(const std::string& message) bool Rtcm_Printer::Print_Message(const std::string& message)
{ {
//write to file //write to file
if (d_rtcm_file_dump)
{
try try
{ {
rtcm_file_descriptor << message << std::endl; rtcm_file_descriptor << message << std::endl;
@ -350,6 +397,7 @@ bool Rtcm_Printer::Print_Message(const std::string& message)
DLOG(INFO) << "RTCM printer cannot write on the output file " << rtcm_filename.c_str(); DLOG(INFO) << "RTCM printer cannot write on the output file " << rtcm_filename.c_str();
return false; return false;
} }
}
//write to serial device //write to serial device
if (rtcm_dev_descriptor != -1) if (rtcm_dev_descriptor != -1)

View File

@ -48,7 +48,7 @@ public:
/*! /*!
* \brief Default constructor. * \brief Default constructor.
*/ */
Rtcm_Printer(std::string filename, bool flag_rtcm_server, bool flag_rtcm_tty_port, uint16_t rtcm_tcp_port, uint16_t rtcm_station_id, std::string rtcm_dump_filename, bool time_tag_name = true); Rtcm_Printer(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, std::string rtcm_dump_filename, bool time_tag_name = true, const std::string& base_path = ".");
/*! /*!
* \brief Default destructor. * \brief Default destructor.
@ -143,6 +143,7 @@ public:
private: private:
std::string rtcm_filename; // String with the RTCM log filename std::string rtcm_filename; // String with the RTCM log filename
std::string rtcm_base_path;
std::ofstream rtcm_file_descriptor; // Output file stream for RTCM log file std::ofstream rtcm_file_descriptor; // Output file stream for RTCM log file
std::string rtcm_devname; std::string rtcm_devname;
uint16_t port; uint16_t port;
@ -152,6 +153,7 @@ private:
void close_serial(); void close_serial();
std::shared_ptr<Rtcm> rtcm; std::shared_ptr<Rtcm> rtcm;
bool Print_Message(const std::string& message); bool Print_Message(const std::string& message);
bool d_rtcm_file_dump;
}; };
#endif #endif

View File

@ -168,8 +168,9 @@ TEST_F(NmeaPrinterTest, PrintLine)
pvt_solution->set_valid_position(true); pvt_solution->set_valid_position(true);
bool flag_nmea_output_file = true;
ASSERT_NO_THROW({ ASSERT_NO_THROW({
std::shared_ptr<Nmea_Printer> nmea_printer = std::make_shared<Nmea_Printer>(filename, false, ""); std::shared_ptr<Nmea_Printer> nmea_printer = std::make_shared<Nmea_Printer>(filename, flag_nmea_output_file, false, "");
nmea_printer->Print_Nmea_Line(pvt_solution, false); nmea_printer->Print_Nmea_Line(pvt_solution, false);
}) << "Failure printing NMEA messages."; }) << "Failure printing NMEA messages.";
@ -206,8 +207,9 @@ TEST_F(NmeaPrinterTest, PrintLineLessthan10min)
pvt_solution->set_valid_position(true); pvt_solution->set_valid_position(true);
bool flag_nmea_output_file = true;
ASSERT_NO_THROW({ ASSERT_NO_THROW({
std::shared_ptr<Nmea_Printer> nmea_printer = std::make_shared<Nmea_Printer>(filename, false, ""); std::shared_ptr<Nmea_Printer> nmea_printer = std::make_shared<Nmea_Printer>(filename, flag_nmea_output_file, false, "");
nmea_printer->Print_Nmea_Line(pvt_solution, false); nmea_printer->Print_Nmea_Line(pvt_solution, false);
}) << "Failure printing NMEA messages."; }) << "Failure printing NMEA messages.";

View File

@ -39,9 +39,10 @@ TEST(RtcmPrinterTest, Instantiate)
bool flag_rtcm_tty_port = false; bool flag_rtcm_tty_port = false;
std::string rtcm_dump_devname = "/dev/pts/4"; std::string rtcm_dump_devname = "/dev/pts/4";
bool flag_rtcm_server = false; bool flag_rtcm_server = false;
bool rtcm_file_output_enabled = false;
unsigned short rtcm_tcp_port = 2101; unsigned short rtcm_tcp_port = 2101;
unsigned short rtcm_station_id = 1234; unsigned short rtcm_station_id = 1234;
std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_dump_devname)); std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, rtcm_file_output_enabled, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_dump_devname));
} }
@ -49,12 +50,13 @@ TEST(RtcmPrinterTest, Run)
{ {
std::string filename = "test.rtcm"; std::string filename = "test.rtcm";
bool flag_rtcm_tty_port = false; bool flag_rtcm_tty_port = false;
bool rtcm_file_output_enabled = false;
std::string rtcm_dump_devname = "/dev/pts/4"; std::string rtcm_dump_devname = "/dev/pts/4";
bool flag_rtcm_server = false; bool flag_rtcm_server = false;
unsigned short rtcm_tcp_port = 2101; unsigned short rtcm_tcp_port = 2101;
unsigned short rtcm_station_id = 1234; unsigned short rtcm_station_id = 1234;
std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_dump_devname)); std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, rtcm_file_output_enabled, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_dump_devname));
std::string reference_msg = "D300133ED7D30202980EDEEF34B4BD62AC0941986F33360B98"; std::string reference_msg = "D300133ED7D30202980EDEEF34B4BD62AC0941986F33360B98";