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:
commit
7abb877f69
@ -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")
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -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)
|
||||||
{
|
{
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -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);
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
|
@ -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
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|
||||||
|
@ -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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -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);
|
||||||
|
@ -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();
|
||||||
|
@ -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);
|
||||||
|
@ -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();
|
||||||
|
@ -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);
|
||||||
|
@ -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,13 +47,55 @@
|
|||||||
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;
|
||||||
nmea_file_descriptor.open(nmea_filename.c_str(), std::ios::out);
|
d_flag_nmea_output_file = flag_nmea_output_file;
|
||||||
if (nmea_file_descriptor.is_open())
|
if (d_flag_nmea_output_file == true)
|
||||||
{
|
{
|
||||||
DLOG(INFO) << "NMEA printer writing on " << nmea_filename.c_str();
|
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);
|
||||||
|
if (nmea_file_descriptor.is_open())
|
||||||
|
{
|
||||||
|
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;
|
||||||
@ -94,13 +139,13 @@ int Nmea_Printer::init_serial(std::string serial_device)
|
|||||||
int64_t PARITY;
|
int64_t PARITY;
|
||||||
|
|
||||||
fd = open(serial_device.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
|
fd = open(serial_device.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
|
||||||
if (fd == -1) return fd; //failed to open TTY port
|
if (fd == -1) return fd; // failed to open TTY port
|
||||||
|
|
||||||
if (fcntl(fd, F_SETFL, 0) == -1) LOG(INFO) << "Error enabling direct I/O"; // clear all flags on descriptor, enable direct I/O
|
if (fcntl(fd, F_SETFL, 0) == -1) LOG(INFO) << "Error enabling direct I/O"; // clear all flags on descriptor, enable direct I/O
|
||||||
tcgetattr(fd, &options); // read serial port options
|
tcgetattr(fd, &options); // read serial port options
|
||||||
|
|
||||||
BAUD = B9600;
|
BAUD = B9600;
|
||||||
//BAUD = B38400;
|
// BAUD = B38400;
|
||||||
DATABITS = CS8;
|
DATABITS = CS8;
|
||||||
STOPBITS = 0;
|
STOPBITS = 0;
|
||||||
PARITYON = 0;
|
PARITYON = 0;
|
||||||
@ -108,7 +153,7 @@ int Nmea_Printer::init_serial(std::string serial_device)
|
|||||||
|
|
||||||
options.c_cflag = BAUD | DATABITS | STOPBITS | PARITYON | PARITY | CLOCAL | CREAD;
|
options.c_cflag = BAUD | DATABITS | STOPBITS | PARITYON | PARITY | CLOCAL | CREAD;
|
||||||
// enable receiver, set 8 bit data, ignore control lines
|
// enable receiver, set 8 bit data, ignore control lines
|
||||||
//options.c_cflag |= (CLOCAL | CREAD | CS8);
|
// options.c_cflag |= (CLOCAL | CREAD | CS8);
|
||||||
options.c_iflag = IGNPAR;
|
options.c_iflag = IGNPAR;
|
||||||
|
|
||||||
// set the new port options
|
// set the new port options
|
||||||
@ -139,34 +184,36 @@ bool Nmea_Printer::Print_Nmea_Line(const std::shared_ptr<rtklib_solver>& pvt_dat
|
|||||||
|
|
||||||
// generate the NMEA sentences
|
// generate the NMEA sentences
|
||||||
|
|
||||||
//GPRMC
|
// GPRMC
|
||||||
GPRMC = get_GPRMC();
|
GPRMC = get_GPRMC();
|
||||||
//GPGGA (Global Positioning System Fixed Data)
|
// GPGGA (Global Positioning System Fixed Data)
|
||||||
GPGGA = get_GPGGA();
|
GPGGA = get_GPGGA();
|
||||||
//GPGSA
|
// GPGSA
|
||||||
GPGSA = get_GPGSA();
|
GPGSA = get_GPGSA();
|
||||||
//GPGSV
|
// GPGSV
|
||||||
GPGSV = get_GPGSV();
|
GPGSV = get_GPGSV();
|
||||||
|
|
||||||
// write to log file
|
// write to log file
|
||||||
try
|
if (d_flag_nmea_output_file)
|
||||||
{
|
{
|
||||||
//GPRMC
|
try
|
||||||
nmea_file_descriptor << GPRMC;
|
{
|
||||||
//GPGGA (Global Positioning System Fixed Data)
|
// GPRMC
|
||||||
nmea_file_descriptor << GPGGA;
|
nmea_file_descriptor << GPRMC;
|
||||||
//GPGSA
|
// GPGGA (Global Positioning System Fixed Data)
|
||||||
nmea_file_descriptor << GPGSA;
|
nmea_file_descriptor << GPGGA;
|
||||||
//GPGSV
|
// GPGSA
|
||||||
nmea_file_descriptor << GPGSV;
|
nmea_file_descriptor << GPGSA;
|
||||||
}
|
// GPGSV
|
||||||
catch (const std::exception& ex)
|
nmea_file_descriptor << GPGSV;
|
||||||
{
|
}
|
||||||
DLOG(INFO) << "NMEA printer can not write on output file" << nmea_filename.c_str();
|
catch (const std::exception& ex)
|
||||||
;
|
{
|
||||||
|
DLOG(INFO) << "NMEA printer can not write on output file" << nmea_filename.c_str();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//write to serial device
|
// write to serial device
|
||||||
if (nmea_dev_descriptor != -1)
|
if (nmea_dev_descriptor != -1)
|
||||||
{
|
{
|
||||||
if (write(nmea_dev_descriptor, GPRMC.c_str(), GPRMC.length()) == -1)
|
if (write(nmea_dev_descriptor, GPRMC.c_str(), GPRMC.length()) == -1)
|
||||||
@ -284,7 +331,7 @@ std::string Nmea_Printer::longitude_to_hm(double longitude)
|
|||||||
|
|
||||||
std::string Nmea_Printer::get_UTC_NMEA_time(boost::posix_time::ptime d_position_UTC_time)
|
std::string Nmea_Printer::get_UTC_NMEA_time(boost::posix_time::ptime d_position_UTC_time)
|
||||||
{
|
{
|
||||||
//UTC Time: hhmmss.sss
|
// UTC Time: hhmmss.sss
|
||||||
std::stringstream sentence_str;
|
std::stringstream sentence_str;
|
||||||
|
|
||||||
boost::posix_time::time_duration td = d_position_UTC_time.time_of_day();
|
boost::posix_time::time_duration td = d_position_UTC_time.time_of_day();
|
||||||
@ -335,20 +382,19 @@ std::string Nmea_Printer::get_GPRMC()
|
|||||||
double speed_over_ground_knots = 0;
|
double speed_over_ground_knots = 0;
|
||||||
double course_over_ground_deg = 0;
|
double course_over_ground_deg = 0;
|
||||||
|
|
||||||
//boost::posix_time::ptime d_position_UTC_time=boost::posix_time::microsec_clock::universal_time();
|
// boost::posix_time::ptime d_position_UTC_time=boost::posix_time::microsec_clock::universal_time();
|
||||||
|
|
||||||
std::stringstream sentence_str;
|
std::stringstream sentence_str;
|
||||||
|
|
||||||
//GPRMC (RMC-Recommended,Minimum Specific GNSS Data)
|
// GPRMC (RMC-Recommended,Minimum Specific GNSS Data)
|
||||||
std::string sentence_header;
|
std::string sentence_header;
|
||||||
sentence_header = "$GPRMC,";
|
sentence_header = "$GPRMC,";
|
||||||
sentence_str << sentence_header;
|
sentence_str << sentence_header;
|
||||||
|
|
||||||
//UTC Time: hhmmss.sss
|
// UTC Time: hhmmss.sss
|
||||||
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";
|
||||||
@ -373,13 +419,13 @@ std::string Nmea_Printer::get_GPRMC()
|
|||||||
sentence_str << "," << longitude_to_hm(d_PVT_data->get_longitude());
|
sentence_str << "," << longitude_to_hm(d_PVT_data->get_longitude());
|
||||||
}
|
}
|
||||||
|
|
||||||
//Speed over ground (knots)
|
// Speed over ground (knots)
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
||||||
sentence_str.precision(2);
|
sentence_str.precision(2);
|
||||||
sentence_str << speed_over_ground_knots;
|
sentence_str << speed_over_ground_knots;
|
||||||
|
|
||||||
//course over ground (degrees)
|
// course over ground (degrees)
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
||||||
sentence_str.precision(2);
|
sentence_str.precision(2);
|
||||||
@ -403,11 +449,11 @@ std::string Nmea_Printer::get_GPRMC()
|
|||||||
year_strs << std::dec << year;
|
year_strs << std::dec << year;
|
||||||
sentence_str << std::dec << year_strs.str().substr(2);
|
sentence_str << std::dec << year_strs.str().substr(2);
|
||||||
|
|
||||||
//Magnetic Variation (degrees)
|
// Magnetic Variation (degrees)
|
||||||
// ToDo: Implement magnetic compass
|
// ToDo: Implement magnetic compass
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
|
|
||||||
//Magnetic Variation (E or W)
|
// Magnetic Variation (E or W)
|
||||||
// ToDo: Implement magnetic compass
|
// ToDo: Implement magnetic compass
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
|
|
||||||
@ -429,7 +475,7 @@ std::string Nmea_Printer::get_GPRMC()
|
|||||||
|
|
||||||
std::string Nmea_Printer::get_GPGSA()
|
std::string Nmea_Printer::get_GPGSA()
|
||||||
{
|
{
|
||||||
//$GPGSA,A,3,07,02,26,27,09,04,15, , , , , ,1.8,1.0,1.5*33
|
// $GPGSA,A,3,07,02,26,27,09,04,15, , , , , ,1.8,1.0,1.5*33
|
||||||
// GSA-GNSS DOP and Active Satellites
|
// GSA-GNSS DOP and Active Satellites
|
||||||
bool valid_fix = d_PVT_data->is_valid_position();
|
bool valid_fix = d_PVT_data->is_valid_position();
|
||||||
int n_sats_used = d_PVT_data->get_num_valid_observations();
|
int n_sats_used = d_PVT_data->get_num_valid_observations();
|
||||||
@ -480,14 +526,14 @@ std::string Nmea_Printer::get_GPGSA()
|
|||||||
sentence_str.precision(1);
|
sentence_str.precision(1);
|
||||||
sentence_str.fill('0');
|
sentence_str.fill('0');
|
||||||
sentence_str << pdop;
|
sentence_str << pdop;
|
||||||
//HDOP
|
// HDOP
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
||||||
sentence_str.width(2);
|
sentence_str.width(2);
|
||||||
sentence_str.precision(1);
|
sentence_str.precision(1);
|
||||||
sentence_str.fill('0');
|
sentence_str.fill('0');
|
||||||
sentence_str << hdop;
|
sentence_str << hdop;
|
||||||
//VDOP
|
// VDOP
|
||||||
sentence_str << ",";
|
sentence_str << ",";
|
||||||
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
sentence_str.setf(std::ios::fixed, std::ios::floatfield);
|
||||||
sentence_str.width(2);
|
sentence_str.width(2);
|
||||||
@ -548,7 +594,7 @@ std::string Nmea_Printer::get_GPGSV()
|
|||||||
frame_str.fill('0');
|
frame_str.fill('0');
|
||||||
frame_str << std::dec << n_sats_used;
|
frame_str << std::dec << n_sats_used;
|
||||||
|
|
||||||
//satellites info
|
// satellites info
|
||||||
for (int j = 0; j < 4; j++)
|
for (int j = 0; j < 4; j++)
|
||||||
{
|
{
|
||||||
// write satellite info
|
// write satellite info
|
||||||
@ -595,13 +641,13 @@ std::string Nmea_Printer::get_GPGSV()
|
|||||||
sentence_str << frame_str.str();
|
sentence_str << frame_str.str();
|
||||||
}
|
}
|
||||||
return sentence_str.str();
|
return sentence_str.str();
|
||||||
//$GPGSV,2,1,07,07,79,048,42,02,51,062,43,26,36,256,42,27,27,138,42*71
|
// $GPGSV,2,1,07,07,79,048,42,02,51,062,43,26,36,256,42,27,27,138,42*71
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
std::string Nmea_Printer::get_GPGGA()
|
std::string Nmea_Printer::get_GPGGA()
|
||||||
{
|
{
|
||||||
//boost::posix_time::ptime d_position_UTC_time=boost::posix_time::microsec_clock::universal_time();
|
// boost::posix_time::ptime d_position_UTC_time=boost::posix_time::microsec_clock::universal_time();
|
||||||
bool valid_fix = d_PVT_data->is_valid_position();
|
bool valid_fix = d_PVT_data->is_valid_position();
|
||||||
int n_channels = d_PVT_data->get_num_valid_observations(); //d_nchannels
|
int n_channels = d_PVT_data->get_num_valid_observations(); //d_nchannels
|
||||||
double hdop = d_PVT_data->get_hdop();
|
double hdop = d_PVT_data->get_hdop();
|
||||||
@ -618,12 +664,12 @@ std::string Nmea_Printer::get_GPGGA()
|
|||||||
|
|
||||||
std::stringstream sentence_str;
|
std::stringstream sentence_str;
|
||||||
|
|
||||||
//GPGGA (Global Positioning System Fixed Data)
|
// GPGGA (Global Positioning System Fixed Data)
|
||||||
std::string sentence_header;
|
std::string sentence_header;
|
||||||
sentence_header = "$GPGGA,";
|
sentence_header = "$GPGGA,";
|
||||||
sentence_str << sentence_header;
|
sentence_str << sentence_header;
|
||||||
|
|
||||||
//UTC Time: hhmmss.sss
|
// UTC Time: hhmmss.sss
|
||||||
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());
|
||||||
|
|
||||||
if (d_PVT_data->is_averaging() == true)
|
if (d_PVT_data->is_averaging() == true)
|
||||||
@ -708,5 +754,5 @@ std::string Nmea_Printer::get_GPGGA()
|
|||||||
// end NMEA sentence
|
// end NMEA sentence
|
||||||
sentence_str << "\r\n";
|
sentence_str << "\r\n";
|
||||||
return sentence_str.str();
|
return sentence_str.str();
|
||||||
//$GPGGA,104427.591,5920.7009,N,01803.2938,E,1,05,3.3,78.2,M,23.2,M,0.0,0000*4A
|
// $GPGGA,104427.591,5920.7009,N,01803.2938,E,1,05,3.3,78.2,M,23.2,M,0.0,0000*4A
|
||||||
}
|
}
|
||||||
|
@ -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
|
||||||
@ -66,7 +66,8 @@ public:
|
|||||||
~Nmea_Printer();
|
~Nmea_Printer();
|
||||||
|
|
||||||
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
|
||||||
|
69
src/algorithms/PVT/libs/pvt_conf.cc
Normal file
69
src/algorithms/PVT/libs/pvt_conf.cc
Normal 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(".");
|
||||||
|
}
|
85
src/algorithms/PVT/libs/pvt_conf.h
Normal file
85
src/algorithms/PVT/libs/pvt_conf.h
Normal 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
|
@ -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";
|
||||||
|
@ -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();
|
||||||
|
|
||||||
|
@ -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,11 +127,18 @@ 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;
|
||||||
rtcm_file_descriptor.open(rtcm_filename.c_str(), std::ios::out);
|
if (d_rtcm_file_dump)
|
||||||
if (rtcm_file_descriptor.is_open())
|
|
||||||
{
|
{
|
||||||
DLOG(INFO) << "RTCM printer writing on " << rtcm_filename.c_str();
|
rtcm_file_descriptor.open(rtcm_filename.c_str(), std::ios::out);
|
||||||
|
if (rtcm_file_descriptor.is_open())
|
||||||
|
{
|
||||||
|
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;
|
||||||
@ -341,14 +386,17 @@ 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
|
||||||
try
|
if (d_rtcm_file_dump)
|
||||||
{
|
{
|
||||||
rtcm_file_descriptor << message << std::endl;
|
try
|
||||||
}
|
{
|
||||||
catch (const std::exception& ex)
|
rtcm_file_descriptor << message << std::endl;
|
||||||
{
|
}
|
||||||
DLOG(INFO) << "RTCM printer cannot write on the output file " << rtcm_filename.c_str();
|
catch (const std::exception& ex)
|
||||||
return false;
|
{
|
||||||
|
DLOG(INFO) << "RTCM printer cannot write on the output file " << rtcm_filename.c_str();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//write to serial device
|
//write to serial device
|
||||||
|
@ -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.
|
||||||
@ -142,7 +142,8 @@ public:
|
|||||||
uint32_t lock_time(const Glonass_Gnav_Ephemeris& eph, double obs_time, const Gnss_Synchro& gnss_synchro);
|
uint32_t lock_time(const Glonass_Gnav_Ephemeris& eph, double obs_time, const Gnss_Synchro& gnss_synchro);
|
||||||
|
|
||||||
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
|
||||||
|
@ -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.";
|
||||||
|
|
||||||
|
@ -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";
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user