1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2024-12-13 11:40:33 +00:00

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

This commit is contained in:
Carles Fernandez 2017-09-10 10:51:17 +02:00
commit 047d9af6a3
64 changed files with 9129 additions and 330 deletions

3
.gitignore vendored
View File

@ -6,7 +6,10 @@ docs/latex
docs/GNSS-SDR_manual.pdf docs/GNSS-SDR_manual.pdf
src/tests/data/output.dat src/tests/data/output.dat
thirdparty/ thirdparty/
.settings
.project .project
.cproject .cproject
.idea
cmake-build-debug/
/install /install
.DS_Store .DS_Store

View File

@ -0,0 +1,76 @@
[GNSS-SDR]
;######### GLOBAL OPTIONS ##################
GNSS-SDR.internal_fs_hz=6625000
;######### SIGNAL_SOURCE CONFIG ############
SignalSource.implementation=File_Signal_Source
SignalSource.filename=/archive/NT1065_GLONASS_L1_20160831_fs6625e6_if0e3_schar_1m.bin
SignalSource.item_type=ibyte
SignalSource.sampling_frequency=6625000
;SignalSource.freq=0
;SignalSource.samples=66250000
SignalSource.samples=0
SignalSource.dump=false;
SignalSource.dump_filename=/archive/signal_glonass.bin
;######### SIGNAL_CONDITIONER CONFIG ############
SignalConditioner.implementation=Signal_Conditioner
DataTypeAdapter.implementation=Ibyte_To_Complex
InputFilter.implementation=Pass_Through
InputFilter.item_type=gr_complex
Resampler.implementation=Direct_Resampler
Resampler.sample_freq_in=6625000
Resampler.sample_freq_out=6625000
Resampler.item_type=gr_complex
;######### CHANNELS GLOBAL CONFIG ############
Channels_1G.count=5
Channels.in_acquisition=5
Channel0.signal=1G
Channel1.signal=1G
Channel2.signal=1G
Channel3.signal=1G
Channel4.signal=1G
Channel0.satellite=11
Channel1.satellite=2
Channel2.satellite=18
Channel3.satellite=12
Channel4.satellite=21
; Possible list includes 2, 12, 21, 22
;######### ACQUISITION GLOBAL CONFIG ############
Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition
Acquisition_1G.item_type=gr_complex
Acquisition_1G.threshold=0.0
Acquisition_1G.pfa=0.0001
Acquisition_1G.if=0
Acquisition_1G.doppler_max=10000
Acquisition_1G.doppler_step=250
Acquisition_1G.dump=false;
Acquisition_1G.dump_filename=/archive/glo_acquisition.dat
;Acquisition_1G.coherent_integration_time_ms=10
;######### TRACKING GLOBAL CONFIG ############
Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking
Tracking_1G.item_type=gr_complex
Tracking_1G.if=1
Tracking_1G.early_late_space_chips=0.5
Tracking_1G.pll_bw_hz=25.0;
Tracking_1G.dll_bw_hz=3.0;
Tracking_1G.dump=true;
Tracking_1G.dump_filename=/archive/glo_tracking_ch_
;######### TELEMETRY DECODER GPS CONFIG ############
TelemetryDecoder_1G.implementation=GPS_L1_CA_Telemetry_Decoder
;######### OBSERVABLES CONFIG ############
Observables.implementation=Hybrid_Observables
;######### PVT CONFIG ############
PVT.implementation=RTKLIB_PVT
PVT.averaging_depth=100
PVT.flag_averaging=true
PVT.output_rate_ms=10
PVT.display_rate_ms=500

View File

@ -34,7 +34,7 @@ DataTypeAdapter.dump=false
DataTypeAdapter.dump_filename=../data/DataTypeAdapter.dat DataTypeAdapter.dump_filename=../data/DataTypeAdapter.dat
;######### CHANNELS GLOBAL CONFIG ############ ;######### CHANNELS GLOBAL CONFIG ############
Channels_1C.count=8 Channels_1C.count=5
Channels.in_acquisition=1 Channels.in_acquisition=1
Channel.signal=1C Channel.signal=1C
@ -51,6 +51,7 @@ Acquisition_1C.threshold=0.05
Acquisition_1C.doppler_max=10000 Acquisition_1C.doppler_max=10000
Acquisition_1C.doppler_step=250 Acquisition_1C.doppler_step=250
;######### TRACKING GLOBAL CONFIG ############ ;######### TRACKING GLOBAL CONFIG ############
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking
Tracking_1C.item_type=gr_complex Tracking_1C.item_type=gr_complex

View File

@ -84,17 +84,24 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
unsigned short rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234); unsigned short 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 = boost::math::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), output_rate_ms); int rtcm_MT1019_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1019_rate_ms", 5000), output_rate_ms);
int rtcm_MT1020_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1020_rate_ms", 5000), output_rate_ms);
int rtcm_MT1045_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), output_rate_ms); int rtcm_MT1045_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1045_rate_ms", 5000), output_rate_ms);
int rtcm_MSM_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), output_rate_ms); int rtcm_MSM_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MSM_rate_ms", 1000), output_rate_ms);
int rtcm_MT1077_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), output_rate_ms); int rtcm_MT1077_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1077_rate_ms", rtcm_MSM_rate_ms), output_rate_ms);
int rtcm_MT1087_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1087_rate_ms", rtcm_MSM_rate_ms), output_rate_ms);
int rtcm_MT1097_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), output_rate_ms); int rtcm_MT1097_rate_ms = boost::math::lcm(configuration->property(role + ".rtcm_MT1097_rate_ms", rtcm_MSM_rate_ms), 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; rtcm_msg_rate_ms[1019] = rtcm_MT1019_rate_ms;
rtcm_msg_rate_ms[1020] = rtcm_MT1020_rate_ms;
rtcm_msg_rate_ms[1045] = rtcm_MT1045_rate_ms; 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; rtcm_msg_rate_ms[k] = rtcm_MT1077_rate_ms;
} }
for (int k = 1081; k < 1088; k++) // All GLONASS MSM
{
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; rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms;
@ -138,38 +145,48 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
* 20 | GPS L5 + Galileo E5b * 20 | GPS L5 + Galileo E5b
* 21 | GPS L1 C/A + Galileo E1B + GPS L2C * 21 | GPS L1 C/A + Galileo E1B + GPS L2C
* 22 | GPS L1 C/A + Galileo E1B + GPS L5 * 22 | GPS L1 C/A + Galileo E1B + GPS L5
* 23 | GLONASS L1 C/A
* 24 | GLONASS L2 C/A
* 25 | GLONASS L1 C/A + GLONASS L2 C/A
* 26 | GPS L1 C/A + GLONASS L1 C/A
* 27 | Galileo E1B + GLONASS L1 C/A
*/ */
int gps_1C_count = configuration->property("Channels_1C.count", 0); int gps_1C_count = configuration->property("Channels_1C.count", 0);
int gps_2S_count = configuration->property("Channels_2S.count", 0); int gps_2S_count = configuration->property("Channels_2S.count", 0);
int gal_1B_count = configuration->property("Channels_1B.count", 0); int gal_1B_count = configuration->property("Channels_1B.count", 0);
int gal_E5a_count = configuration->property("Channels_5X.count", 0); // GPS L5 or Galileo E5a ? int gal_E5a_count = configuration->property("Channels_5X.count", 0); // GPS L5 or Galileo E5a ?
int gal_E5b_count = configuration->property("Channels_7X.count", 0); int gal_E5b_count = configuration->property("Channels_7X.count", 0);
int glo_1G_count = configuration->property("Channels_1G.count", 0);
unsigned int type_of_receiver = 0; unsigned int type_of_receiver = 0;
if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 1; if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 1;
if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 2; if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 2;
if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 4; if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 4;
if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0)) type_of_receiver = 5; if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 5;
if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0)) type_of_receiver = 6; if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0)) type_of_receiver = 6;
if( (gps_1C_count != 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 7; if( (gps_1C_count != 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 7;
//if( (gps_1C_count != 0) && (gps_2S_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) && (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) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 9; if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 9;
if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0)) type_of_receiver = 10; if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 10;
if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0)) type_of_receiver = 11; if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0)) type_of_receiver = 11;
if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) 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) && (glo_1G_count == 0)) 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)) 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)) type_of_receiver = 14; if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 14;
if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0)) type_of_receiver = 15; if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0)) type_of_receiver = 15;
//if( (gps_1C_count == 0) && (gps_2S_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) && (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) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0)) type_of_receiver = 17; if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 17;
if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0)) type_of_receiver = 18; if( (gps_1C_count == 0) && (gps_2S_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0)) type_of_receiver = 18;
//if( (gps_1C_count == 0) && (gps_2S_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) && (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) && (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) && (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) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 21; if( (gps_1C_count != 0) && (gps_2S_count != 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0)) type_of_receiver = 21;
//if( (gps_1C_count == 0) && (gps_2S_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) && (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) && (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) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2R_count != 0)) type_of_receiver = 24;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_1G_count != 0)) type_of_receiver = 25;
if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0)) type_of_receiver = 26;
if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0)) type_of_receiver = 27;
//RTKLIB PVT solver options //RTKLIB PVT solver options
// Settings 1 // Settings 1
int positioning_mode = -1; int positioning_mode = -1;
@ -192,10 +209,10 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
} }
int num_bands = 0; int num_bands = 0;
if ((gps_1C_count > 0) || (gal_1B_count > 0)) num_bands = 1; if ((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0)) num_bands = 1;
if (((gps_1C_count > 0) || (gal_1B_count > 0)) && (gps_2S_count > 0) ) num_bands = 2; if (((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0)) && (gps_2S_count > 0) ) num_bands = 2;
if (((gps_1C_count > 0) || (gal_1B_count > 0)) && ((gal_E5a_count > 0) || (gal_E5b_count > 0)) ) num_bands = 2; if (((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0)) && ((gal_E5a_count > 0) || (gal_E5b_count > 0)) ) num_bands = 2;
if (((gps_1C_count > 0) || (gal_1B_count > 0)) && (gps_2S_count > 0) && ((gal_E5a_count > 0) || (gal_E5b_count > 0))) num_bands = 3; if (((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0)) && (gps_2S_count > 0) && ((gal_E5a_count > 0) || (gal_E5b_count > 0))) num_bands = 3;
int number_of_frequencies = configuration->property(role + ".num_bands", num_bands); /* (1:L1, 2:L1+L2, 3:L1+L2+L5) */ int number_of_frequencies = configuration->property(role + ".num_bands", num_bands); /* (1:L1, 2:L1+L2, 3:L1+L2+L5) */
if( (number_of_frequencies < 1) || (number_of_frequencies > 3) ) if( (number_of_frequencies < 1) || (number_of_frequencies > 3) )
{ {
@ -207,6 +224,7 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
if( (elevation_mask < 0.0) || (elevation_mask > 90.0) ) if( (elevation_mask < 0.0) || (elevation_mask > 90.0) )
{ {
//warn user and set the default //warn user and set the default
LOG(WARNING) << "Erroneous Elevation Mask. Setting to default value of 15.0 degrees";
elevation_mask = 15.0; elevation_mask = 15.0;
} }
@ -214,6 +232,7 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
if( (dynamics_model < 0) || (dynamics_model > 2) ) if( (dynamics_model < 0) || (dynamics_model > 2) )
{ {
//warn user and set the default //warn user and set the default
LOG(WARNING) << "Erroneous Dynamics Model configuration. Setting to default value of (0:none)";
dynamics_model = 0; dynamics_model = 0;
} }
@ -275,10 +294,12 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
int nsys = 0; int nsys = 0;
if ((gps_1C_count > 0) || (gps_2S_count > 0)) nsys += SYS_GPS; if ((gps_1C_count > 0) || (gps_2S_count > 0)) nsys += SYS_GPS;
if ((gal_1B_count > 0) || (gal_E5a_count > 0) || (gal_E5b_count > 0)) nsys += SYS_GAL; if ((gal_1B_count > 0) || (gal_E5a_count > 0) || (gal_E5b_count > 0)) nsys += SYS_GAL;
if ((glo_1G_count > 0)) nsys += SYS_GLO;
int navigation_system = configuration->property(role + ".navigation_system", nsys); /* (SYS_XXX) see src/algorithms/libs/rtklib/rtklib.h */ int navigation_system = configuration->property(role + ".navigation_system", nsys); /* (SYS_XXX) see src/algorithms/libs/rtklib/rtklib.h */
if( (navigation_system < 1) || (navigation_system > 255) ) /* GPS: 1 SBAS: 2 GPS+SBAS: 3 Galileo: 8 Galileo+GPS: 9 GPS+SBAS+Galileo: 11 All: 255 */ if( (navigation_system < 1) || (navigation_system > 255) ) /* GPS: 1 SBAS: 2 GPS+SBAS: 3 Galileo: 8 Galileo+GPS: 9 GPS+SBAS+Galileo: 11 All: 255 */
{ {
//warn user and set the default //warn user and set the default
LOG(WARNING) << "Erroneous Navigation System. Setting to default value of (0:none)";
navigation_system = nsys; navigation_system = nsys;
} }
@ -305,6 +326,7 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
if( (integer_ambiguity_resolution_glo < 0) || (integer_ambiguity_resolution_glo > 3) ) if( (integer_ambiguity_resolution_glo < 0) || (integer_ambiguity_resolution_glo > 3) )
{ {
//warn user and set the default //warn user and set the default
LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for GLONASS . Setting to default value of (1:on)";
integer_ambiguity_resolution_glo = 1; integer_ambiguity_resolution_glo = 1;
} }
@ -312,6 +334,7 @@ RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
if( (integer_ambiguity_resolution_bds < 0) || (integer_ambiguity_resolution_bds > 1) ) if( (integer_ambiguity_resolution_bds < 0) || (integer_ambiguity_resolution_bds > 1) )
{ {
//warn user and set the default //warn user and set the default
LOG(WARNING) << "Erroneous Integer Ambiguity Resolution for BEIDOU . Setting to default value of (1:on)";
integer_ambiguity_resolution_bds = 1; integer_ambiguity_resolution_bds = 1;
} }

View File

@ -181,6 +181,36 @@ void rtklib_pvt_cc::msg_handler_telemetry(pmt::pmt_t msg)
DLOG(INFO) << "New Galileo Almanac has arrived "; DLOG(INFO) << "New Galileo Almanac has arrived ";
} }
//**************** GLONASS GNAV Telemetry **************************
else if(pmt::any_ref(msg).type() == typeid(std::shared_ptr<Glonass_Gnav_Ephemeris>) )
{
// ### GLONASS GNAV EPHEMERIS ###
std::shared_ptr<Glonass_Gnav_Ephemeris> glonass_gnav_eph;
glonass_gnav_eph = boost::any_cast<std::shared_ptr<Glonass_Gnav_Ephemeris>>(pmt::any_ref(msg));
// TODO Add GLONASS with gps week number and tow,
// insert new ephemeris record
DLOG(INFO) << "GLONASS GNAV New Ephemeris record inserted in global map with TOW =" << glonass_gnav_eph->d_TOW
<< ", GLONASS GNAV Week Number =" << glonass_gnav_eph->d_WN
<< " and Ephemeris IOD = " << glonass_gnav_eph->compute_GLONASS_time(glonass_gnav_eph->d_t_b);
// update/insert new ephemeris record to the global ephemeris map
d_ls_pvt->glonass_gnav_ephemeris_map[glonass_gnav_eph->i_satellite_PRN] = *glonass_gnav_eph;
}
else if(pmt::any_ref(msg).type() == typeid(std::shared_ptr<Glonass_Gnav_Utc_Model>) )
{
// ### GLONASS GNAV UTC MODEL ###
std::shared_ptr<Glonass_Gnav_Utc_Model> glonass_gnav_utc_model;
glonass_gnav_utc_model = boost::any_cast<std::shared_ptr<Glonass_Gnav_Utc_Model>>(pmt::any_ref(msg));
d_ls_pvt->glonass_gnav_utc_model = *glonass_gnav_utc_model;
DLOG(INFO) << "New GLONASS GNAV UTC record has arrived ";
}
else if(pmt::any_ref(msg).type() == typeid(std::shared_ptr<Glonass_Gnav_Almanac>) )
{
// ### GLONASS GNAV Almanac ###
std::shared_ptr<Glonass_Gnav_Almanac> glonass_gnav_almanac;
glonass_gnav_almanac = boost::any_cast<std::shared_ptr<Glonass_Gnav_Almanac>>(pmt::any_ref(msg));
d_ls_pvt->glonass_gnav_almanac = *glonass_gnav_almanac;
DLOG(INFO) << "New GLONASS GNAV Almanac has arrived ";
}
else else
{ {
LOG(WARNING) << "msg_handler_telemetry unknown object type!"; LOG(WARNING) << "msg_handler_telemetry unknown object type!";
@ -249,6 +279,14 @@ rtklib_pvt_cc::rtklib_pvt_cc(unsigned int nchannels, bool dump, std::string dump
{ {
d_rtcm_MT1019_rate_ms = boost::math::lcm(5000, d_output_rate_ms); // default value if not set d_rtcm_MT1019_rate_ms = boost::math::lcm(5000, d_output_rate_ms); // default value if not set
} }
if(rtcm_msg_rate_ms.find(1020) != rtcm_msg_rate_ms.end())
{
d_rtcm_MT1020_rate_ms = rtcm_msg_rate_ms[1020];
}
else
{
d_rtcm_MT1020_rate_ms = boost::math::lcm(5000, d_output_rate_ms); // default value if not set
}
if(rtcm_msg_rate_ms.find(1045) != rtcm_msg_rate_ms.end()) if(rtcm_msg_rate_ms.find(1045) != rtcm_msg_rate_ms.end())
{ {
d_rtcm_MT1045_rate_ms = rtcm_msg_rate_ms[1045]; d_rtcm_MT1045_rate_ms = rtcm_msg_rate_ms[1045];
@ -265,6 +303,14 @@ rtklib_pvt_cc::rtklib_pvt_cc(unsigned int nchannels, bool dump, std::string dump
{ {
d_rtcm_MT1077_rate_ms = boost::math::lcm(1000, d_output_rate_ms); // default value if not set d_rtcm_MT1077_rate_ms = boost::math::lcm(1000, d_output_rate_ms); // default value if not set
} }
if(rtcm_msg_rate_ms.find(1087) != rtcm_msg_rate_ms.end()) // whatever between 1081 and 1087
{
d_rtcm_MT1087_rate_ms = rtcm_msg_rate_ms[1087];
}
else
{
d_rtcm_MT1087_rate_ms = boost::math::lcm(1000, d_output_rate_ms); // default value if not set
}
if(rtcm_msg_rate_ms.find(1097) != rtcm_msg_rate_ms.end()) // whatever between 1091 and 1097 if(rtcm_msg_rate_ms.find(1097) != rtcm_msg_rate_ms.end()) // whatever between 1091 and 1097
{ {
d_rtcm_MT1097_rate_ms = rtcm_msg_rate_ms[1097]; d_rtcm_MT1097_rate_ms = rtcm_msg_rate_ms[1097];
@ -286,8 +332,10 @@ rtklib_pvt_cc::rtklib_pvt_cc(unsigned int nchannels, bool dump, std::string dump
d_rx_time = 0.0; d_rx_time = 0.0;
last_pvt_display_T_rx_s = 0.0; last_pvt_display_T_rx_s = 0.0;
last_RTCM_1019_output_time = 0.0; last_RTCM_1019_output_time = 0.0;
last_RTCM_1020_output_time = 0.0;
last_RTCM_1045_output_time = 0.0; last_RTCM_1045_output_time = 0.0;
last_RTCM_1077_output_time = 0.0; last_RTCM_1077_output_time = 0.0;
last_RTCM_1087_output_time = 0.0;
last_RTCM_1097_output_time = 0.0; last_RTCM_1097_output_time = 0.0;
last_RTCM_MSM_output_time = 0.0; last_RTCM_MSM_output_time = 0.0;
last_RINEX_obs_output_time = 0.0; last_RINEX_obs_output_time = 0.0;
@ -335,7 +383,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
msgctl(sysv_msqid, IPC_RMID, NULL); msgctl(sysv_msqid, IPC_RMID, NULL);
//save GPS L2CM ephemeris to XML file //save GPS L2CM ephemeris to XML file
std::string file_name = "eph_GPS_L2CM.xml"; std::string file_name="eph_GPS_L2CM.xml";
if (d_ls_pvt->gps_cnav_ephemeris_map.size() > 0) if (d_ls_pvt->gps_cnav_ephemeris_map.size() > 0)
{ {
@ -347,7 +395,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
ofs.close(); ofs.close();
LOG(INFO) << "Saved GPS L2CM Ephemeris map data"; LOG(INFO) << "Saved GPS L2CM Ephemeris map data";
} }
catch (const std::exception & e) catch (std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -403,6 +451,28 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
LOG(WARNING) << "Failed to save Galileo E1 Ephemeris, map is empty"; LOG(WARNING) << "Failed to save Galileo E1 Ephemeris, map is empty";
} }
//save GLONASS GNAV ephemeris to XML file
file_name = "eph_GLONASS_GNAV.xml";
if (d_ls_pvt->glonass_gnav_ephemeris_map.size() > 0)
{
try
{
std::ofstream ofs(file_name.c_str(), std::ofstream::trunc | std::ofstream::out);
boost::archive::xml_oarchive xml(ofs);
xml << boost::serialization::make_nvp("GNSS-SDR_ephemeris_map", d_ls_pvt->glonass_gnav_ephemeris_map);
ofs.close();
LOG(INFO) << "Saved GLONASS GNAV Ephemeris map data";
}
catch (std::exception& e)
{
LOG(WARNING) << e.what();
}
}
else
{
LOG(WARNING) << "Failed to save GLONASS GNAV Ephemeris, map is empty";
}
if (d_dump_file.is_open() == true) if (d_dump_file.is_open() == true)
{ {
try try
@ -447,14 +517,17 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
bool flag_display_pvt = false; bool flag_display_pvt = false;
bool flag_compute_pvt_output = false; bool flag_compute_pvt_output = false;
bool flag_write_RTCM_1019_output = false; bool flag_write_RTCM_1019_output = false;
bool flag_write_RTCM_1020_output = false;
bool flag_write_RTCM_1045_output = false; bool flag_write_RTCM_1045_output = false;
bool flag_write_RTCM_1077_output = false; bool flag_write_RTCM_1077_output = false;
bool flag_write_RTCM_1087_output = false;
bool flag_write_RTCM_1097_output = false; bool flag_write_RTCM_1097_output = false;
bool flag_write_RTCM_MSM_output = false; bool flag_write_RTCM_MSM_output = false;
bool flag_write_RINEX_obs_output = false; bool flag_write_RINEX_obs_output = false;
bool flag_write_RINEX_nav_output = false; bool flag_write_RINEX_nav_output = false;
unsigned int gps_channel = 0; unsigned int gps_channel = 0;
unsigned int gal_channel = 0; unsigned int gal_channel = 0;
unsigned int glo_channel = 0;
gnss_observables_map.clear(); gnss_observables_map.clear();
const Gnss_Synchro **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer const Gnss_Synchro **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer
@ -467,10 +540,13 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
std::map<int,Gps_Ephemeris>::const_iterator tmp_eph_iter_gps = d_ls_pvt->gps_ephemeris_map.find(in[i][epoch].PRN); std::map<int,Gps_Ephemeris>::const_iterator tmp_eph_iter_gps = d_ls_pvt->gps_ephemeris_map.find(in[i][epoch].PRN);
std::map<int,Galileo_Ephemeris>::const_iterator tmp_eph_iter_gal = d_ls_pvt->galileo_ephemeris_map.find(in[i][epoch].PRN); std::map<int,Galileo_Ephemeris>::const_iterator tmp_eph_iter_gal = d_ls_pvt->galileo_ephemeris_map.find(in[i][epoch].PRN);
std::map<int,Gps_CNAV_Ephemeris>::const_iterator tmp_eph_iter_cnav = d_ls_pvt->gps_cnav_ephemeris_map.find(in[i][epoch].PRN); std::map<int,Gps_CNAV_Ephemeris>::const_iterator tmp_eph_iter_cnav = d_ls_pvt->gps_cnav_ephemeris_map.find(in[i][epoch].PRN);
std::map<int,Glonass_Gnav_Ephemeris>::const_iterator tmp_eph_iter_glo_gnav = d_ls_pvt->glonass_gnav_ephemeris_map.find(in[i][epoch].PRN);
if(((tmp_eph_iter_gps->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("1C") == 0)) if(((tmp_eph_iter_gps->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("1C") == 0))
|| ((tmp_eph_iter_cnav->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("2S") == 0)) || ((tmp_eph_iter_cnav->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("2S") == 0))
|| ((tmp_eph_iter_gal->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("1B") == 0)) || ((tmp_eph_iter_gal->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("1B") == 0))
|| ((tmp_eph_iter_gal->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("5X") == 0))) || ((tmp_eph_iter_gal->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("5X") == 0))
|| ((tmp_eph_iter_glo_gnav->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("1C") == 0))
|| ((tmp_eph_iter_glo_gnav->second.i_satellite_PRN == in[i][epoch].PRN) && (std::string(in[i][epoch].Signal).compare("2C") == 0)))
{ {
// store valid observables in a map. // store valid observables in a map.
gnss_observables_map.insert(std::pair<int,Gnss_Synchro>(i, in[i][epoch])); gnss_observables_map.insert(std::pair<int,Gnss_Synchro>(i, in[i][epoch]));
@ -497,6 +573,14 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
d_rtcm_printer->lock_time(d_ls_pvt->gps_cnav_ephemeris_map.find(in[i][epoch].PRN)->second, in[i][epoch].RX_time, in[i][epoch]); // keep track of locking time d_rtcm_printer->lock_time(d_ls_pvt->gps_cnav_ephemeris_map.find(in[i][epoch].PRN)->second, in[i][epoch].RX_time, in[i][epoch]); // keep track of locking time
} }
} }
if(d_ls_pvt->glonass_gnav_ephemeris_map.size() > 0)
{
if(tmp_eph_iter_glo_gnav != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
//d_rtcm_printer->lock_time(d_ls_pvt->glonass_gnav_ephemeris_map.find(in[i][epoch].PRN)->second, in[i][epoch].RX_time, in[i][epoch]); // keep track of locking time
}
}
} }
} }
@ -529,7 +613,11 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
flag_write_RTCM_1019_output = true; flag_write_RTCM_1019_output = true;
last_RTCM_1019_output_time = current_RX_time; last_RTCM_1019_output_time = current_RX_time;
} }
if ((std::fabs(current_RX_time - last_RTCM_1020_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1020_rate_ms)) && (d_rtcm_MT1020_rate_ms != 0) ) // allows deactivating messages by setting rate = 0
{
flag_write_RTCM_1020_output = true;
last_RTCM_1020_output_time = current_RX_time;
}
if ((std::fabs(current_RX_time - last_RTCM_1045_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1045_rate_ms)) && (d_rtcm_MT1045_rate_ms != 0) ) if ((std::fabs(current_RX_time - last_RTCM_1045_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1045_rate_ms)) && (d_rtcm_MT1045_rate_ms != 0) )
{ {
flag_write_RTCM_1045_output = true; flag_write_RTCM_1045_output = true;
@ -541,7 +629,11 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
flag_write_RTCM_1077_output = true; flag_write_RTCM_1077_output = true;
last_RTCM_1077_output_time = current_RX_time; last_RTCM_1077_output_time = current_RX_time;
} }
if ((std::fabs(current_RX_time - last_RTCM_1087_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1087_rate_ms)) && (d_rtcm_MT1087_rate_ms != 0) )
{
flag_write_RTCM_1087_output = true;
last_RTCM_1087_output_time = current_RX_time;
}
if ((std::fabs(current_RX_time - last_RTCM_1097_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1097_rate_ms)) && (d_rtcm_MT1097_rate_ms != 0) ) if ((std::fabs(current_RX_time - last_RTCM_1097_output_time) * 1000.0 >= static_cast<double>(d_rtcm_MT1097_rate_ms)) && (d_rtcm_MT1097_rate_ms != 0) )
{ {
flag_write_RTCM_1097_output = true; flag_write_RTCM_1097_output = true;
@ -613,6 +705,11 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
* 20 | GPS L5 + Galileo E5b * 20 | GPS L5 + Galileo E5b
* 21 | GPS L1 C/A + Galileo E1B + GPS L2C * 21 | GPS L1 C/A + Galileo E1B + GPS L2C
* 22 | GPS L1 C/A + Galileo E1B + GPS L5 * 22 | GPS L1 C/A + Galileo E1B + GPS L5
* 23 | GLONASS L1 C/A
* 24 | GLONASS L2 C/A
* 25 | GLONASS L1 C/A + GLONASS L2 C/A
* 26 | GPS L1 C/A + GLONASS L1 C/A
* 27 | Galileo E1B + GLONASS L1 C/A
*/ */
// ####################### RINEX FILES ################# // ####################### RINEX FILES #################
@ -620,6 +717,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
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, Gnss_Synchro>::const_iterator gnss_observables_iter; std::map<int, Gnss_Synchro>::const_iterator gnss_observables_iter;
if (!b_rinex_header_written) // & we have utc data in nav message! if (!b_rinex_header_written) // & we have utc data in nav message!
@ -627,6 +725,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin(); galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin();
gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.cbegin(); gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.cbegin();
gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin(); gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin();
glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.cbegin();
if(type_of_rx == 1) // GPS L1 C/A only if(type_of_rx == 1) // GPS L1 C/A only
{ {
@ -736,6 +835,58 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
b_rinex_header_written = true; // do not write header anymore b_rinex_header_written = true; // do not write header anymore
} }
} }
if(type_of_rx == 23) // GLONASS L1 C/A only
{
std::string signal("1C");
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.cend())
{
rp->rinex_obs_header(rp->obsFile, glonass_gnav_ephemeris_iter->second, d_rx_time, signal);
rp->rinex_nav_header(rp->navGloFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_written = true; // do not write header anymore
}
}
if(type_of_rx == 24) // GLONASS L2 C/A only
{
std::string signal("2C");
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.cend())
{
rp->rinex_obs_header(rp->obsFile, galileo_ephemeris_iter->second, d_rx_time, signal);
rp->rinex_nav_header(rp->navGloFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_written = true; // do not write header anymore
}
}
if(type_of_rx == 25) // GLONASS L1 C/A + GLONASS L2 C/A
{
std::string signal("1C 2C");
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.cend())
{
rp->rinex_obs_header(rp->obsFile, glonass_gnav_ephemeris_iter->second, d_rx_time, signal);
rp->rinex_nav_header(rp->navGloFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_written = true; // do not write header anymore
}
}
if(type_of_rx == 26) // GPS L1 C/A + GLONASS L1 C/A
{
if ((glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.cend()) && (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) )
{
std::string glo_signal("1C");
rp->rinex_obs_header(rp->obsFile, gps_ephemeris_iter->second, glonass_gnav_ephemeris_iter->second, d_rx_time, glo_signal);
rp->rinex_nav_header(rp->navMixFile, d_ls_pvt->gps_iono, d_ls_pvt->gps_utc_model, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_written = true; // do not write header anymore
}
}
if(type_of_rx == 27) // Galileo E1B + GLONASS L1 C/A
{
if ((glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.cend()) && (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend()) )
{
std::string glo_signal("1C");
std::string gal_signal("1B");
rp->rinex_obs_header(rp->obsFile, galileo_ephemeris_iter->second, glonass_gnav_ephemeris_iter->second, d_rx_time, glo_signal, gal_signal);
rp->rinex_nav_header(rp->navMixFile, d_ls_pvt->galileo_iono, d_ls_pvt->galileo_utc_model, d_ls_pvt->galileo_almanac, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_written = true; // do not write header anymore
}
}
} }
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
{ {
@ -765,10 +916,23 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
{ {
rp->log_rinex_nav(rp->navGalFile, d_ls_pvt->galileo_ephemeris_map); rp->log_rinex_nav(rp->navGalFile, d_ls_pvt->galileo_ephemeris_map);
} }
if((type_of_rx == 23) || (type_of_rx == 24) || (type_of_rx == 25)) // GLONASS L1 C/A, GLONASS L2 C/A
{
rp->log_rinex_nav(rp->navGloFile, d_ls_pvt->glonass_gnav_ephemeris_map);
}
if((type_of_rx == 26)) // GPS L1 C/A + GLONASS L1 C/A
{
rp->log_rinex_nav(rp->navMixFile, d_ls_pvt->gps_ephemeris_map, d_ls_pvt->glonass_gnav_ephemeris_map);
}
if((type_of_rx == 27)) // Galileo E1B + GLONASS L1 C/A
{
rp->log_rinex_nav(rp->navMixFile, d_ls_pvt->galileo_ephemeris_map, d_ls_pvt->glonass_gnav_ephemeris_map);
}
} }
galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin(); galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin();
gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.cbegin(); gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.cbegin();
gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin(); gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin();
glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.cbegin();
// Log observables into the RINEX file // Log observables into the RINEX file
if(flag_write_RINEX_obs_output) if(flag_write_RINEX_obs_output)
@ -890,6 +1054,73 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
b_rinex_header_updated = true; b_rinex_header_updated = true;
} }
} }
if(type_of_rx == 23) // GLONASS L1 C/A only
{
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
rp->log_rinex_obs(rp->obsFile, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, "1C");
}
if (!b_rinex_header_updated && (d_ls_pvt->glonass_gnav_utc_model.d_tau_c != 0))
{
rp->update_nav_header(rp->navGloFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
rp->update_obs_header(rp->obsFile, d_ls_pvt->glonass_gnav_utc_model);
b_rinex_header_updated = true;
}
}
if(type_of_rx == 24) // GLONASS L2 C/A only
{
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
rp->log_rinex_obs(rp->obsFile, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, "2C");
}
if (!b_rinex_header_updated && (d_ls_pvt->glonass_gnav_utc_model.d_tau_c != 0))
{
rp->update_nav_header(rp->navGloFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
rp->update_obs_header(rp->obsFile, d_ls_pvt->glonass_gnav_utc_model);
b_rinex_header_updated = true;
}
}
if(type_of_rx == 25) // GLONASS L1 C/A + GLONASS L2 C/A
{
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
rp->log_rinex_obs(rp->obsFile, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, "1C 2C");
}
if (!b_rinex_header_updated && (d_ls_pvt->glonass_gnav_utc_model.d_tau_c != 0))
{
rp->update_nav_header(rp->navMixFile, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
rp->update_obs_header(rp->obsFile, d_ls_pvt->glonass_gnav_utc_model);
b_rinex_header_updated = true;
}
}
if(type_of_rx == 26) // GPS L1 C/A + GLONASS L1 C/A
{
if ((glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end()) && (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end()) )
{
rp->log_rinex_obs(rp->obsFile, gps_ephemeris_iter->second, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map);
}
if (!b_rinex_header_updated && (d_ls_pvt->gps_utc_model.d_A0 != 0))
{
rp->update_obs_header(rp->obsFile, d_ls_pvt->gps_utc_model);
rp->update_nav_header(rp->navMixFile, d_ls_pvt->gps_iono, d_ls_pvt->gps_utc_model, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_updated = true; // do not write header anymore
}
}
if(type_of_rx == 27) // Galileo E1B + GLONASS L1 C/A
{
if ((glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end()) && (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.end()) )
{
std::string glo_signal("1C");
rp->log_rinex_obs(rp->obsFile, galileo_ephemeris_iter->second, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map);
}
if (!b_rinex_header_updated && (d_ls_pvt->galileo_utc_model.A0_6 != 0))
{
rp->update_obs_header(rp->obsFile, d_ls_pvt->galileo_utc_model);
rp->update_nav_header(rp->navMixFile, d_ls_pvt->galileo_iono, d_ls_pvt->galileo_utc_model, d_ls_pvt->galileo_almanac, d_ls_pvt->glonass_gnav_utc_model, d_ls_pvt->glonass_gnav_almanac);
b_rinex_header_updated = true; // do not write header anymore
}
}
} }
} }
@ -912,7 +1143,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
} }
} }
@ -931,7 +1162,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
gal_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin(); gal_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.cbegin();
if (gal_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend()) if (gal_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, gal_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, gal_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
} }
} }
@ -952,7 +1183,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin(); gps_cnav_ephemeris_iter = d_ls_pvt->gps_cnav_ephemeris_map.cbegin();
if ((gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) && (gps_cnav_ephemeris_iter != d_ls_pvt->gps_cnav_ephemeris_map.cend()) ) if ((gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) && (gps_cnav_ephemeris_iter != d_ls_pvt->gps_cnav_ephemeris_map.cend()) )
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, gps_cnav_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, gps_cnav_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
} }
} }
@ -1010,14 +1241,165 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend()) if (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, galileo_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, galileo_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
} }
if(flag_write_RTCM_MSM_output == true) if(flag_write_RTCM_MSM_output == true)
{ {
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
}
}
}
}
if((type_of_rx == 23) || (type_of_rx == 24) || (type_of_rx == 25)) // GLONASS
{
if(flag_write_RTCM_1020_output == true)
{
for(std::map<int,Glonass_Gnav_Ephemeris>::iterator glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.begin(); glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end(); glonass_gnav_ephemeris_iter++ )
{
d_rtcm_printer->Print_Rtcm_MT1020(glonass_gnav_ephemeris_iter->second, d_ls_pvt->glonass_gnav_utc_model);
}
}
std::map<int,Glonass_Gnav_Ephemeris>::iterator glo_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.begin();
if (glo_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, {}, glo_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
}
b_rtcm_writing_started = true;
}
if(type_of_rx == 26) // GPS L1 C/A + GLONASS L1 C/A
{
if(flag_write_RTCM_1019_output == true)
{
for(gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.begin(); gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end(); gps_ephemeris_iter++ )
{
d_rtcm_printer->Print_Rtcm_MT1019(gps_ephemeris_iter->second);
}
}
if(flag_write_RTCM_1020_output == true)
{
for(std::map<int,Glonass_Gnav_Ephemeris>::iterator glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.begin(); glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end(); glonass_gnav_ephemeris_iter++ )
{
d_rtcm_printer->Print_Rtcm_MT1020(glonass_gnav_ephemeris_iter->second, d_ls_pvt->glonass_gnav_utc_model);
}
}
if(flag_write_RTCM_MSM_output == true)
{
//gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.end();
//galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.end();
unsigned int i = 0;
for (gnss_observables_iter = gnss_observables_map.begin(); gnss_observables_iter != gnss_observables_map.end(); gnss_observables_iter++)
{
std::string system(&gnss_observables_iter->second.System, 1);
if(gps_channel == 0)
{
if(system.compare("G") == 0)
{
// This is a channel with valid GPS signal
gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end())
{
gps_channel = i;
}
}
}
if(glo_channel == 0)
{
if(system.compare("R") == 0)
{
glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
glo_channel = i;
}
}
}
i++;
}
if(flag_write_RTCM_MSM_output == true)
{
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, {}, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
}
}
if(flag_write_RTCM_MSM_output == true)
{
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end())
{
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
}
}
}
}
if(type_of_rx == 27) // GLONASS L1 C/A + Galileo E1B
{
if(flag_write_RTCM_1020_output == true)
{
for(std::map<int,Glonass_Gnav_Ephemeris>::iterator glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.begin(); glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end(); glonass_gnav_ephemeris_iter++ )
{
d_rtcm_printer->Print_Rtcm_MT1020(glonass_gnav_ephemeris_iter->second, d_ls_pvt->glonass_gnav_utc_model);
}
}
if(flag_write_RTCM_1045_output == true)
{
for(galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.begin(); galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.end(); galileo_ephemeris_iter++ )
{
d_rtcm_printer->Print_Rtcm_MT1045(galileo_ephemeris_iter->second);
}
}
if(flag_write_RTCM_MSM_output == true)
{
//gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.end();
//galileo_ephemeris_iter = d_ls_pvt->galileo_ephemeris_map.end();
unsigned int i = 0;
for (gnss_observables_iter = gnss_observables_map.begin(); gnss_observables_iter != gnss_observables_map.end(); gnss_observables_iter++)
{
std::string system(&gnss_observables_iter->second.System, 1);
if(gps_channel == 0)
{
if(system.compare("G") == 0)
{
// This is a channel with valid GPS signal
gps_ephemeris_iter = d_ls_pvt->gps_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end())
{
gps_channel = i;
}
}
}
if(glo_channel == 0)
{
if(system.compare("R") == 0)
{
glonass_gnav_ephemeris_iter = d_ls_pvt->glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
glo_channel = i;
}
}
}
i++;
}
if(flag_write_RTCM_MSM_output == true)
{
if (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.end())
{
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, galileo_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
}
}
if(flag_write_RTCM_MSM_output == true)
{
if (glonass_gnav_ephemeris_iter != d_ls_pvt->glonass_gnav_ephemeris_map.end())
{
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, {}, glonass_gnav_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
} }
} }
@ -1037,7 +1419,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
b_rtcm_writing_started = true; b_rtcm_writing_started = true;
} }
@ -1053,7 +1435,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if (gal_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend()) if (gal_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.cend())
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, gal_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, gal_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
b_rtcm_writing_started = true; b_rtcm_writing_started = true;
} }
@ -1069,7 +1451,7 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if ((gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) && (gps_cnav_ephemeris_iter != d_ls_pvt->gps_cnav_ephemeris_map.cend())) if ((gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.cend()) && (gps_cnav_ephemeris_iter != d_ls_pvt->gps_cnav_ephemeris_map.cend()))
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, gps_cnav_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, gps_cnav_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
b_rtcm_writing_started = true; b_rtcm_writing_started = true;
} }
@ -1122,12 +1504,12 @@ int rtklib_pvt_cc::work (int noutput_items, gr_vector_const_void_star &input_ite
if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end() && (d_rtcm_MT1077_rate_ms != 0)) if (gps_ephemeris_iter != d_ls_pvt->gps_ephemeris_map.end() && (d_rtcm_MT1077_rate_ms != 0))
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, gps_ephemeris_iter->second, {}, {}, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
if (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.end() && (d_rtcm_MT1097_rate_ms != 0) ) if (galileo_ephemeris_iter != d_ls_pvt->galileo_ephemeris_map.end() && (d_rtcm_MT1097_rate_ms != 0) )
{ {
d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, galileo_ephemeris_iter->second, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0); d_rtcm_printer->Print_Rtcm_MSM(7, {}, {}, galileo_ephemeris_iter->second, {}, d_rx_time, gnss_observables_map, 0, 0, 0, 0, 0);
} }
b_rtcm_writing_started = true; b_rtcm_writing_started = true;
} }

View File

@ -99,10 +99,12 @@ private:
bool b_rinex_header_written; bool b_rinex_header_written;
bool b_rinex_header_updated; bool b_rinex_header_updated;
bool b_rtcm_writing_started; bool b_rtcm_writing_started;
int d_rtcm_MT1045_rate_ms; int d_rtcm_MT1045_rate_ms; //!< Galileo Broadcast Ephemeris
int d_rtcm_MT1019_rate_ms; int d_rtcm_MT1019_rate_ms; //!< GPS Broadcast Ephemeris (orbits)
int d_rtcm_MT1077_rate_ms; int d_rtcm_MT1020_rate_ms; //!< GLONASS Broadcast Ephemeris (orbits)
int d_rtcm_MT1097_rate_ms; int d_rtcm_MT1077_rate_ms; //!< The type 7 Multiple Signal Message format for the USAs GPS system, popular
int d_rtcm_MT1087_rate_ms; //!< GLONASS MSM7. The type 7 Multiple Signal Message format for the Russian GLONASS system
int d_rtcm_MT1097_rate_ms; //!< Galileo MSM7. The type 7 Multiple Signal Message format for Europes Galileo system
int d_rtcm_MSM_rate_ms; int d_rtcm_MSM_rate_ms;
int d_last_status_print_seg; //for status printer int d_last_status_print_seg; //for status printer
@ -122,8 +124,10 @@ private:
double d_rx_time; double d_rx_time;
double last_pvt_display_T_rx_s; double last_pvt_display_T_rx_s;
double last_RTCM_1019_output_time; double last_RTCM_1019_output_time;
double last_RTCM_1020_output_time;
double last_RTCM_1045_output_time; double last_RTCM_1045_output_time;
double last_RTCM_1077_output_time; double last_RTCM_1077_output_time;
double last_RTCM_1087_output_time;
double last_RTCM_1097_output_time; double last_RTCM_1097_output_time;
double last_RTCM_MSM_output_time; double last_RTCM_MSM_output_time;
double last_RINEX_obs_output_time; double last_RINEX_obs_output_time;

View File

@ -727,6 +727,3 @@ std::string Nmea_Printer::get_GPGGA()
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
} }

File diff suppressed because it is too large Load Diff

View File

@ -61,8 +61,10 @@
#include "gps_navigation_message.h" #include "gps_navigation_message.h"
#include "gps_cnav_navigation_message.h" #include "gps_cnav_navigation_message.h"
#include "galileo_navigation_message.h" #include "galileo_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#include "Galileo_E1.h" #include "Galileo_E1.h"
#include "GLONASS_L1_CA.h"
#include "gnss_synchro.h" #include "gnss_synchro.h"
class Sbas_Raw_Msg; class Sbas_Raw_Msg;
@ -88,6 +90,7 @@ public:
std::fstream navFile ; //<! Output file stream for RINEX navigation data file std::fstream navFile ; //<! Output file stream for RINEX navigation data file
std::fstream sbsFile ; //<! Output file stream for RINEX SBAS raw data file std::fstream sbsFile ; //<! Output file stream for RINEX SBAS raw data file
std::fstream navGalFile ; //<! Output file stream for RINEX Galileo navigation data file std::fstream navGalFile ; //<! Output file stream for RINEX Galileo navigation data file
std::fstream navGloFile ; //<! Output file stream for RINEX GLONASS navigation data file
std::fstream navMixFile ; //<! Output file stream for RINEX Mixed navigation data file std::fstream navMixFile ; //<! Output file stream for RINEX Mixed navigation data file
/*! /*!
@ -110,6 +113,21 @@ public:
*/ */
void rinex_nav_header(std::fstream & out, const Gps_Iono & gps_iono, const Gps_Utc_Model & gps_utc_model, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & galileo_utc_model, const Galileo_Almanac & galileo_almanac); void rinex_nav_header(std::fstream & out, const Gps_Iono & gps_iono, const Gps_Utc_Model & gps_utc_model, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & galileo_utc_model, const Galileo_Almanac & galileo_almanac);
/*!
* \brief Generates the GLONASS L1, L2 C/A Navigation Data header
*/
void rinex_nav_header(std::fstream & out, const Glonass_Gnav_Utc_Model & utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
/*!
* \brief Generates the Mixed (Galileo/GLONASS) Navigation Data header
*/
void rinex_nav_header(std::fstream & out, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & galileo_utc_model, const Galileo_Almanac & galileo_almanac, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
/*!
* \brief Generates the Mixed (GPS L1 C/A/GLONASS L1, L2) Navigation Data header
*/
void rinex_nav_header(std::fstream & out, const Gps_Iono & gps_iono, const Gps_Utc_Model & gps_utc_model, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
/*! /*!
* \brief Generates the GPS Observation data header * \brief Generates the GPS Observation data header
*/ */
@ -135,6 +153,21 @@ public:
*/ */
void rinex_obs_header(std::fstream & out, const Gps_Ephemeris & gps_eph, const Galileo_Ephemeris & galileo_eph, const double d_TOW_first_observation, const std::string galileo_bands = "1B"); void rinex_obs_header(std::fstream & out, const Gps_Ephemeris & gps_eph, const Galileo_Ephemeris & galileo_eph, const double d_TOW_first_observation, const std::string galileo_bands = "1B");
/*!
* \brief Generates the GLONASS GNAV Observation data header. Example: bands("1C"), bands("1C 2C"), bands("2C"), ... Default: "1C".
*/
void rinex_obs_header(std::fstream & out, const Glonass_Gnav_Ephemeris & eph, const double d_TOW_first_observation, const std::string bands = "1C");
/*!
* \brief Generates the Mixed (GPS L1 C/A /GLONASS) Observation data header. Example: galileo_bands("1C"), galileo_bands("1B 5X"), galileo_bands("5X"), ... Default: "1B".
*/
void rinex_obs_header(std::fstream & out, const Gps_Ephemeris & gps_eph, const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const double d_TOW_first_observation, const std::string glo_bands = "1C");
/*!
* \brief Generates the Mixed (Galileo/GLONASS) Observation data header. Example: galileo_bands("1C"), galileo_bands("1B 5X"), galileo_bands("5X"), ... Default: "1B".
*/
void rinex_obs_header(std::fstream & out, const Galileo_Ephemeris & galileo_eph, const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const double d_TOW_first_observation, const std::string galileo_bands = "1B", const std::string glo_bands = "1C");
/*! /*!
* \brief Generates the SBAS raw data header * \brief Generates the SBAS raw data header
*/ */
@ -160,6 +193,11 @@ public:
*/ */
boost::posix_time::ptime compute_Galileo_time(const Galileo_Ephemeris & eph, const double obs_time); boost::posix_time::ptime compute_Galileo_time(const Galileo_Ephemeris & eph, const double obs_time);
/*!
* \brief Computes the GLONASS System Time and returns a boost::posix_time::ptime object
*/
boost::posix_time::ptime compute_GLONASS_time(const Glonass_Gnav_Ephemeris & eph, const double obs_time);
/*! /*!
* \brief Writes data from the GPS L1 C/A navigation message into the RINEX file * \brief Writes data from the GPS L1 C/A navigation message into the RINEX file
*/ */
@ -180,6 +218,21 @@ public:
*/ */
void log_rinex_nav(std::fstream & out, const std::map<int, Gps_Ephemeris> & gps_eph_map, const std::map<int, Galileo_Ephemeris> & galileo_eph_map); void log_rinex_nav(std::fstream & out, const std::map<int, Gps_Ephemeris> & gps_eph_map, const std::map<int, Galileo_Ephemeris> & galileo_eph_map);
/*!
* \brief Writes data from the GLONASS GNAV navigation message into the RINEX file
*/
void log_rinex_nav(std::fstream & out, const std::map<int, Glonass_Gnav_Ephemeris> & eph_map);
/*!
* \brief Writes data from the Mixed (GPS/GLONASS GNAV) navigation message into the RINEX file
*/
void log_rinex_nav(std::fstream & out, const std::map<int, Gps_Ephemeris> & gps_eph_map, const std::map<int, Glonass_Gnav_Ephemeris> & glonass_gnav_eph_map);
/*!
* \brief Writes data from the Mixed (Galileo/ GLONASS GNAV) navigation message into the RINEX file
*/
void log_rinex_nav(std::fstream & out, const std::map<int, Galileo_Ephemeris> & galileo_eph_map, const std::map<int, Glonass_Gnav_Ephemeris> & glonass_gnav_eph_map);
/*! /*!
* \brief Writes GPS L1 observables into the RINEX file * \brief Writes GPS L1 observables into the RINEX file
*/ */
@ -205,6 +258,21 @@ public:
*/ */
void log_rinex_obs(std::fstream & out, const Gps_Ephemeris & gps_eph, const Galileo_Ephemeris & galileo_eph, const double gps_obs_time, const std::map<int, Gnss_Synchro> & observables); void log_rinex_obs(std::fstream & out, const Gps_Ephemeris & gps_eph, const Galileo_Ephemeris & galileo_eph, const double gps_obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Writes GLONASS GNAV observables into the RINEX file. Example: glonass_bands("1C"), galileo_bands("1B 5X"), galileo_bands("5X"), ... Default: "1B".
*/
void log_rinex_obs(std::fstream & out, const Glonass_Gnav_Ephemeris & eph, double obs_time, const std::map<int, Gnss_Synchro> & observables, const std::string glonass_bands = "1C");
/*!
* \brief Writes Mixed GPS L1 C/A - GLONASS observables into the RINEX file
*/
void log_rinex_obs(std::fstream & out, const Gps_Ephemeris & gps_eph, const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const double gps_obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Writes Mixed Galileo/GLONASS observables into the RINEX file
*/
void log_rinex_obs(std::fstream & out, const Galileo_Ephemeris & galileo_eph, const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const double gps_obs_time, const std::map<int, Gnss_Synchro> & observables);
/*! /*!
* \brief Represents GPS time in the date time format. Leap years are considered, but leap seconds are not. * \brief Represents GPS time in the date time format. Leap years are considered, but leap seconds are not.
*/ */
@ -223,12 +291,20 @@ public:
void update_nav_header(std::fstream & out, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & utc_model, const Galileo_Almanac & galileo_almanac); void update_nav_header(std::fstream & out, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & utc_model, const Galileo_Almanac & galileo_almanac);
void update_nav_header(std::fstream & out, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
void update_nav_header(std::fstream & out, const Gps_Iono & gps_iono, const Gps_Utc_Model & gps_utc, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
void update_nav_header(std::fstream & out, const Galileo_Iono & galileo_iono, const Galileo_Utc_Model & galileo_utc_model, const Galileo_Almanac& galileo_almanac, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model, const Glonass_Gnav_Almanac & glonass_gnav_almanac);
void update_obs_header(std::fstream & out, const Gps_Utc_Model & utc_model); void update_obs_header(std::fstream & out, const Gps_Utc_Model & utc_model);
void update_obs_header(std::fstream & out, const Gps_CNAV_Utc_Model & utc_model); void update_obs_header(std::fstream & out, const Gps_CNAV_Utc_Model & utc_model);
void update_obs_header(std::fstream & out, const Galileo_Utc_Model & galileo_utc_model); void update_obs_header(std::fstream & out, const Galileo_Utc_Model & galileo_utc_model);
void update_obs_header(std::fstream & out, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
std::map<std::string,std::string> satelliteSystem; //<! GPS, GLONASS, SBAS payload, Galileo or Compass std::map<std::string,std::string> satelliteSystem; //<! GPS, GLONASS, SBAS payload, Galileo or Compass
std::map<std::string,std::string> observationType; //<! PSEUDORANGE, CARRIER_PHASE, DOPPLER, SIGNAL_STRENGTH std::map<std::string,std::string> observationType; //<! PSEUDORANGE, CARRIER_PHASE, DOPPLER, SIGNAL_STRENGTH
std::map<std::string,std::string> observationCode; //<! GNSS observation descriptors std::map<std::string,std::string> observationCode; //<! GNSS observation descriptors
@ -238,6 +314,7 @@ public:
std::string obsfilename; std::string obsfilename;
std::string sbsfilename; std::string sbsfilename;
std::string navGalfilename; std::string navGalfilename;
std::string navGlofilename;
std::string navMixfilename; std::string navMixfilename;
private: private:

View File

@ -186,6 +186,38 @@ bool Rtcm_Printer::Print_Rtcm_MT1004(const Gps_Ephemeris& gps_eph, const Gps_CNA
} }
bool Rtcm_Printer::Print_Rtcm_MT1009(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables)
{
std::string m1009 = rtcm->print_MT1009(glonass_gnav_eph, obs_time, observables, station_id);
Rtcm_Printer::Print_Message(m1009);
return true;
}
bool Rtcm_Printer::Print_Rtcm_MT1010(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables)
{
std::string m1010 = rtcm->print_MT1010(glonass_gnav_eph, obs_time, observables, station_id);
Rtcm_Printer::Print_Message(m1010);
return true;
}
bool Rtcm_Printer::Print_Rtcm_MT1011(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables)
{
std::string m1011 = rtcm->print_MT1011(glonass_gnav_ephL1, glonass_gnav_ephL2, obs_time, observables, station_id);
Rtcm_Printer::Print_Message(m1011);
return true;
}
bool Rtcm_Printer::Print_Rtcm_MT1012(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables)
{
std::string m1012 = rtcm->print_MT1012(glonass_gnav_ephL1, glonass_gnav_ephL2, obs_time, observables, station_id);
Rtcm_Printer::Print_Message(m1012);
return true;
}
bool Rtcm_Printer::Print_Rtcm_MT1019(const Gps_Ephemeris & gps_eph) bool Rtcm_Printer::Print_Rtcm_MT1019(const Gps_Ephemeris & gps_eph)
{ {
std::string m1019 = rtcm->print_MT1019(gps_eph); std::string m1019 = rtcm->print_MT1019(gps_eph);
@ -194,6 +226,14 @@ bool Rtcm_Printer::Print_Rtcm_MT1019(const Gps_Ephemeris & gps_eph)
} }
bool Rtcm_Printer::Print_Rtcm_MT1020(const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model)
{
std::string m1020 = rtcm->print_MT1020(glonass_gnav_eph, glonass_gnav_utc_model);
Rtcm_Printer::Print_Message(m1020);
return true;
}
bool Rtcm_Printer::Print_Rtcm_MT1045(const Galileo_Ephemeris & gal_eph) bool Rtcm_Printer::Print_Rtcm_MT1045(const Galileo_Ephemeris & gal_eph)
{ {
std::string m1045 = rtcm->print_MT1045(gal_eph); std::string m1045 = rtcm->print_MT1045(gal_eph);
@ -205,6 +245,7 @@ bool Rtcm_Printer::Print_Rtcm_MT1045(const Galileo_Ephemeris & gal_eph)
bool Rtcm_Printer::Print_Rtcm_MSM(unsigned int msm_number, const Gps_Ephemeris & gps_eph, bool Rtcm_Printer::Print_Rtcm_MSM(unsigned int msm_number, const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int clock_steering_indicator, unsigned int clock_steering_indicator,
@ -216,31 +257,31 @@ bool Rtcm_Printer::Print_Rtcm_MSM(unsigned int msm_number, const Gps_Ephemeris &
std::string msm; std::string msm;
if(msm_number == 1) if(msm_number == 1)
{ {
msm = rtcm->print_MSM_1(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_1(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 2) else if(msm_number == 2)
{ {
msm = rtcm->print_MSM_2(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_2(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 3) else if(msm_number == 3)
{ {
msm = rtcm->print_MSM_3(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_3(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 4) else if(msm_number == 4)
{ {
msm = rtcm->print_MSM_4(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_4(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 5) else if(msm_number == 5)
{ {
msm = rtcm->print_MSM_5(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_5(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 6) else if(msm_number == 6)
{ {
msm = rtcm->print_MSM_6(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_6(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else if(msm_number == 7) else if(msm_number == 7)
{ {
msm = rtcm->print_MSM_7(gps_eph, gps_cnav_eph, gal_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages); msm = rtcm->print_MSM_7(gps_eph, gps_cnav_eph, gal_eph, glo_gnav_eph, obs_time, observables, station_id, clock_steering_indicator, external_clock_indicator, smooth_int, divergence_free, more_messages);
} }
else else
{ {
@ -348,3 +389,9 @@ unsigned int Rtcm_Printer::lock_time(const Galileo_Ephemeris& eph, double obs_ti
{ {
return rtcm->lock_time(eph, obs_time, gnss_synchro); return rtcm->lock_time(eph, obs_time, gnss_synchro);
} }
unsigned int Rtcm_Printer::lock_time(const Glonass_Gnav_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro)
{
return rtcm->lock_time(eph, obs_time, gnss_synchro);
}

View File

@ -59,12 +59,66 @@ public:
bool Print_Rtcm_MT1002(const Gps_Ephemeris& gps_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables); bool Print_Rtcm_MT1002(const Gps_Ephemeris& gps_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables);
bool Print_Rtcm_MT1003(const Gps_Ephemeris& gps_eph, const Gps_CNAV_Ephemeris& cnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables); bool Print_Rtcm_MT1003(const Gps_Ephemeris& gps_eph, const Gps_CNAV_Ephemeris& cnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables);
bool Print_Rtcm_MT1004(const Gps_Ephemeris& gps_eph, const Gps_CNAV_Ephemeris& cnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables); bool Print_Rtcm_MT1004(const Gps_Ephemeris& gps_eph, const Gps_CNAV_Ephemeris& cnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Prints L1-Only GLONASS RTK Observables
* \details This GLONASS message type is not generally used or supported; type 1012 is to be preferred.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return true or false upon operation success
*/
bool Print_Rtcm_MT1009(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Prints Extended L1-Only GLONASS RTK Observables
* \details This GLONASS message type is used when only L1 data is present and bandwidth is very tight, often 1012 is used in such cases.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return true or false upon operation success
*/
bool Print_Rtcm_MT1010(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Prints L1&L2 GLONASS RTK Observables
* \details This GLONASS message type is not generally used or supported; type 1012 is to be preferred
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_ephL1 GLONASS L1 GNAV Broadcast Ephemeris for satellite
* \param glonass_gnav_ephL2 GLONASS L2 GNAV Broadcast Ephemeris for satellite
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return true or false upon operation success
*/
bool Print_Rtcm_MT1011(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables);
/*!
* \brief Prints Extended L1&L2 GLONASS RTK Observables
* \details This GLONASS message type is the most common observational message type, with L1/L2/SNR content. This is one of the most common messages found.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_ephL1 GLONASS L1 GNAV Broadcast Ephemeris for satellite
* \param glonass_gnav_ephL2 GLONASS L2 GNAV Broadcast Ephemeris for satellite
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return true or false upon operation success
*/
bool Print_Rtcm_MT1012(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables);
bool Print_Rtcm_MT1019(const Gps_Ephemeris & gps_eph); //<! GPS Ephemeris, should be broadcast in the event that the IODC does not match the IODE, and every 2 minutes. bool Print_Rtcm_MT1019(const Gps_Ephemeris & gps_eph); //<! GPS Ephemeris, should be broadcast in the event that the IODC does not match the IODE, and every 2 minutes.
bool Print_Rtcm_MT1045(const Galileo_Ephemeris & gal_eph); //<! Galileo Ephemeris, should be broadcast every 2 minutes bool Print_Rtcm_MT1045(const Galileo_Ephemeris & gal_eph); //<! Galileo Ephemeris, should be broadcast every 2 minutes
/*!
* \brief Prints GLONASS GNAV Ephemeris
* \details This GLONASS message should be broadcast every 2 minutes
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param utc_model GLONASS GNAV Clock Information broadcast in string 5
* \return true or false upon operation success
*/
bool Print_Rtcm_MT1020(const Glonass_Gnav_Ephemeris & glo_gnav_eph, const Glonass_Gnav_Utc_Model & utc_model);
bool Print_Rtcm_MSM(unsigned int msm_number, const Gps_Ephemeris & gps_eph, bool Print_Rtcm_MSM(unsigned int msm_number,
const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int clock_steering_indicator, unsigned int clock_steering_indicator,
@ -77,6 +131,15 @@ public:
unsigned int lock_time(const Gps_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro); unsigned int lock_time(const Gps_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro);
unsigned int lock_time(const Gps_CNAV_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro); unsigned int lock_time(const Gps_CNAV_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro);
unsigned int lock_time(const Galileo_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro); unsigned int lock_time(const Galileo_Ephemeris& eph, double obs_time, const Gnss_Synchro & gnss_synchro);
/*!
* \brief Locks time for logging given GLONASS GNAV Broadcast Ephemeris
* \note Code added as part of GSoC 2017 program
* \params glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \params obs_time Time of observation at the moment of printing
* \params observables Set of observables as defined by the platform
* \return locked time during logging process
*/
unsigned int 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

View File

@ -56,6 +56,7 @@
#include "rtklib_conversions.h" #include "rtklib_conversions.h"
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#include "Galileo_E1.h" #include "Galileo_E1.h"
#include "GLONASS_L1_CA.h"
using google::LogMessage; using google::LogMessage;
@ -114,6 +115,7 @@ bool rtklib_solver::get_PVT(const std::map<int,Gnss_Synchro> & gnss_observables_
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;
this->set_averaging_flag(flag_averaging); this->set_averaging_flag(flag_averaging);
@ -124,6 +126,7 @@ bool rtklib_solver::get_PVT(const std::map<int,Gnss_Synchro> & gnss_observables_
obsd_t obs_data[MAXOBS]; obsd_t obs_data[MAXOBS];
eph_t eph_data[MAXOBS]; eph_t eph_data[MAXOBS];
geph_t geph_data[MAXOBS];
for(gnss_observables_iter = gnss_observables_map.cbegin(); for(gnss_observables_iter = gnss_observables_map.cbegin();
gnss_observables_iter != gnss_observables_map.cend(); gnss_observables_iter != gnss_observables_map.cend();
@ -133,70 +136,75 @@ bool rtklib_solver::get_PVT(const std::map<int,Gnss_Synchro> & gnss_observables_
{ {
case 'E': case 'E':
{ {
std::string sig_(gnss_observables_iter->second.Signal); // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key
// Galileo E1 galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN);
if(sig_.compare("1B") == 0) if (galileo_ephemeris_iter != galileo_ephemeris_map.end())
{ {
// 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key std::string sig_(gnss_observables_iter->second.Signal);
galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); // Galileo E1
if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) if(sig_.compare("1B") == 0)
{ {
//convert ephemeris from GNSS-SDR class to RTKLIB structure // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key
eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second); galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN);
//convert observation from GNSS-SDR class to RTKLIB structure if (galileo_ephemeris_iter != galileo_ephemeris_map.cend())
obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}}; {
obs_data[valid_obs] = insert_obs_to_rtklib(newobs, //convert ephemeris from GNSS-SDR class to RTKLIB structure
gnss_observables_iter->second, eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second);
galileo_ephemeris_iter->second.WN_5, //convert observation from GNSS-SDR class to RTKLIB structure
0); obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}};
valid_obs++; obs_data[valid_obs] = insert_obs_to_rtklib(newobs,
} gnss_observables_iter->second,
else // the ephemeris are not available for this SV galileo_ephemeris_iter->second.WN_5,
{ 0);
DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; valid_obs++;
} }
else // the ephemeris are not available for this SV
{
DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN;
}
} }
// Galileo E5 // Galileo E5
if(sig_.compare("5X") == 0) if(sig_.compare("5X") == 0)
{ {
// 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key // 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key
galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN); galileo_ephemeris_iter = galileo_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (galileo_ephemeris_iter != galileo_ephemeris_map.cend()) if (galileo_ephemeris_iter != galileo_ephemeris_map.cend())
{ {
bool found_E1_obs=false; bool found_E1_obs=false;
for (int i = 0; i < valid_obs; i++) for (int i = 0; i < valid_obs; i++)
{ {
if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO))) if (eph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN + NSATGPS + NSATGLO)))
{ {
obs_data[i] = insert_obs_to_rtklib(obs_data[i], obs_data[i] = insert_obs_to_rtklib(obs_data[i],
gnss_observables_iter->second, gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5, galileo_ephemeris_iter->second.WN_5,
2);//Band 3 (L5/E5) 2);//Band 3 (L5/E5)
found_E1_obs=true; found_E1_obs=true;
break; break;
} }
} }
if (!found_E1_obs) if (!found_E1_obs)
{ {
//insert Galileo E5 obs as new obs and also insert its ephemeris //insert Galileo E5 obs as new obs and also insert its ephemeris
//convert ephemeris from GNSS-SDR class to RTKLIB structure //convert ephemeris from GNSS-SDR class to RTKLIB structure
eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second); eph_data[valid_obs] = eph_to_rtklib(galileo_ephemeris_iter->second);
//convert observation from GNSS-SDR class to RTKLIB structure //convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}}; obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}};
obs_data[valid_obs] = insert_obs_to_rtklib(newobs, obs_data[valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second, gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5, galileo_ephemeris_iter->second.WN_5,
2); //Band 3 (L5/E5) 2); //Band 3 (L5/E5)
valid_obs++; valid_obs++;
} }
} }
else // the ephemeris are not available for this SV else // the ephemeris are not available for this SV
{ {
DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN; DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN;
} }
} }
}
break; break;
} }
case 'G': case 'G':
@ -270,6 +278,76 @@ bool rtklib_solver::get_PVT(const std::map<int,Gnss_Synchro> & gnss_observables_
} }
break; break;
} }
case 'R': //TODO This should be using rtk lib nomenclature
{
std::string sig_(gnss_observables_iter->second.Signal);
// GLONASS GNAV L1
if(sig_.compare("1C") == 0)
{
// 1 Glo - find the ephemeris for the current GLONASS SV observation. The SV Slot Number (PRN ID) is the map key
glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.end())
{
//convert ephemeris from GNSS-SDR class to RTKLIB structure
geph_data[valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second);
//convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}};
obs_data[valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
glonass_gnav_ephemeris_iter->second.d_WN,
0);//TODO are THESE VALUES OK
valid_obs++;
}
else // the ephemeris are not available for this SV
{
DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN;
}
}
// GLONASS GNAV L2
if(sig_.compare("2C") == 0)
{
// 1 Gal - find the ephemeris for the current GALILEO SV observation. The SV PRN ID is the map key
glonass_gnav_ephemeris_iter = glonass_gnav_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (glonass_gnav_ephemeris_iter != glonass_gnav_ephemeris_map.end())
{
bool found_L1_obs=false;
for (int i = 0; i < valid_obs; i++)
{
// TODO what is this?
if (geph_data[i].sat == (static_cast<int>(gnss_observables_iter->second.PRN+NSATGPS+NSATGLO)))
{
obs_data[i] = insert_obs_to_rtklib(obs_data[i],
gnss_observables_iter->second,
glonass_gnav_ephemeris_iter->second.d_WN,
2);//Band 3 (L5/E5)
found_L1_obs=true;
break;
}
}
if (!found_L1_obs)
{
//insert GLONASS GNAV L2 obs as new obs and also insert its ephemeris
//convert ephemeris from GNSS-SDR class to RTKLIB structure
geph_data[valid_obs] = eph_to_rtklib(glonass_gnav_ephemeris_iter->second);
//convert observation from GNSS-SDR class to RTKLIB structure
obsd_t newobs = {{0,0}, '0', '0', {}, {}, {}, {}, {}, {}};
obs_data[valid_obs] = insert_obs_to_rtklib(newobs,
gnss_observables_iter->second,
galileo_ephemeris_iter->second.WN_5,
2); //Band 3 (L5/E5)
valid_obs++;
}
}
else // the ephemeris are not available for this SV
{
DLOG(INFO) << "No ephemeris data for SV " << gnss_observables_iter->second.PRN;
}
}
break;
}
default : default :
DLOG(INFO) << "Hybrid observables: Unknown GNSS"; DLOG(INFO) << "Hybrid observables: Unknown GNSS";
break; break;
@ -364,7 +442,7 @@ bool rtklib_solver::get_PVT(const std::map<int,Gnss_Synchro> & gnss_observables_
LOG(WARNING) << "Exception writing PVT LS dump file " << e.what(); LOG(WARNING) << "Exception writing PVT LS dump file " << e.what();
} }
} }
} }
} }
return this->is_valid_position(); return this->is_valid_position();
} }

View File

@ -62,6 +62,7 @@
#include "galileo_navigation_message.h" #include "galileo_navigation_message.h"
#include "gps_navigation_message.h" #include "gps_navigation_message.h"
#include "gps_cnav_navigation_message.h" #include "gps_cnav_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "pvt_solution.h" #include "pvt_solution.h"
@ -86,6 +87,7 @@ public:
std::map<int,Galileo_Ephemeris> galileo_ephemeris_map; //!< Map storing new Galileo_Ephemeris std::map<int,Galileo_Ephemeris> galileo_ephemeris_map; //!< Map storing new Galileo_Ephemeris
std::map<int,Gps_Ephemeris> gps_ephemeris_map; //!< Map storing new GPS_Ephemeris std::map<int,Gps_Ephemeris> gps_ephemeris_map; //!< Map storing new GPS_Ephemeris
std::map<int,Gps_CNAV_Ephemeris> gps_cnav_ephemeris_map; //!< Map storing new GPS_CNAV_Ephemeris std::map<int,Gps_CNAV_Ephemeris> gps_cnav_ephemeris_map; //!< Map storing new GPS_CNAV_Ephemeris
std::map<int,Glonass_Gnav_Ephemeris> glonass_gnav_ephemeris_map; //!< Map storing new GLONASS GNAV Ephmeris
Galileo_Utc_Model galileo_utc_model; Galileo_Utc_Model galileo_utc_model;
Galileo_Iono galileo_iono; Galileo_Iono galileo_iono;
@ -97,6 +99,9 @@ public:
Gps_CNAV_Iono gps_cnav_iono; Gps_CNAV_Iono gps_cnav_iono;
Gps_CNAV_Utc_Model gps_cnav_utc_model; Gps_CNAV_Utc_Model gps_cnav_utc_model;
Glonass_Gnav_Utc_Model glonass_gnav_utc_model; //!< Map storing GLONASS GNAV UTC Model
Glonass_Gnav_Almanac glonass_gnav_almanac; //!< Map storing GLONASS GNAV Almanac Model
int count_valid_position; int count_valid_position;
}; };

View File

@ -2,7 +2,7 @@
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include "glonass_l1_signal_processing.h" #include "glonass_l1_signal_processing.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "configuration_interface.h" #include "configuration_interface.h"
@ -358,4 +358,3 @@ gr::basic_block_sptr GlonassL1CaPcpsAcquisition::get_right_block()
return acquisition_cc_; return acquisition_cc_;
} }
} }

View File

@ -42,7 +42,7 @@
#include <volk_gnsssdr/volk_gnsssdr.h> #include <volk_gnsssdr/volk_gnsssdr.h>
#include "control_message_factory.h" #include "control_message_factory.h"
#include "GPS_L1_CA.h" //GPS_TWO_PI #include "GPS_L1_CA.h" //GPS_TWO_PI
#include "Glonass_L1_CA.h" //GLONASS_TWO_PI #include "GLONASS_L1_CA.h" //GLONASS_TWO_PI
using google::LogMessage; using google::LogMessage;
@ -195,7 +195,7 @@ bool pcps_acquisition_cc::is_fdma()
if( strcmp(d_gnss_synchro->Signal,"1G") == 0 ) if( strcmp(d_gnss_synchro->Signal,"1G") == 0 )
{ {
d_freq += DFRQ1_GLO * GLONASS_PRN.at(d_gnss_synchro->PRN); d_freq += DFRQ1_GLO * GLONASS_PRN.at(d_gnss_synchro->PRN);
LOG(INFO) << "Trying to acquire SV PRN " << d_gnss_synchro->PRN << " with freq " << DFRQ1_GLO * GLONASS_PRN.at(d_gnss_synchro->PRN) << " in Glonass Channel " << GLONASS_PRN.at(d_gnss_synchro->PRN) << std::endl; LOG(INFO) << "Trying to acquire SV PRN " << d_gnss_synchro->PRN << " with freq " << d_freq << " in Glonass Channel " << GLONASS_PRN.at(d_gnss_synchro->PRN) << std::endl;
return true; return true;
} }
else else

View File

@ -56,7 +56,7 @@
#include <gnuradio/gr_complex.h> #include <gnuradio/gr_complex.h>
#include <gnuradio/fft/fft.h> #include <gnuradio/fft/fft.h>
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "Glonass_L1_CA.h" //GLONASS_TWO_PI #include "GLONASS_L1_CA.h" //GLONASS_TWO_PI
class pcps_acquisition_cc; class pcps_acquisition_cc;

View File

@ -41,7 +41,7 @@
#include <volk_gnsssdr/volk_gnsssdr.h> #include <volk_gnsssdr/volk_gnsssdr.h>
#include "control_message_factory.h" #include "control_message_factory.h"
#include "GPS_L1_CA.h" //GPS_TWO_PI #include "GPS_L1_CA.h" //GPS_TWO_PI
#include "Glonass_L1_CA.h" //GLONASS_TWO_PI #include "GLONASS_L1_CA.h" //GLONASS_TWO_PI
using google::LogMessage; using google::LogMessage;

View File

@ -51,6 +51,10 @@ obsd_t insert_obs_to_rtklib(obsd_t & rtklib_obs, const Gnss_Synchro & gnss_synch
case 'E': case 'E':
rtklib_obs.sat = gnss_synchro.PRN+NSATGPS+NSATGLO; rtklib_obs.sat = gnss_synchro.PRN+NSATGPS+NSATGLO;
break; break;
case 'R':
rtklib_obs.sat = gnss_synchro.PRN;
break;
default: default:
rtklib_obs.sat = gnss_synchro.PRN; rtklib_obs.sat = gnss_synchro.PRN;
} }
@ -60,6 +64,56 @@ obsd_t insert_obs_to_rtklib(obsd_t & rtklib_obs, const Gnss_Synchro & gnss_synch
return rtklib_obs; return rtklib_obs;
} }
geph_t eph_to_rtklib(const Glonass_Gnav_Ephemeris & glonass_gnav_eph)
{
geph_t rtklib_sat = {0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0.0, 0.0, 0.0}, {0.0, 0.0,
0.0}, {0.0, 0.0, 0.0}, 0.0, 0.0, 0.0};
gtime_t t_utc;
struct tm utcinfo;
rtklib_sat.sat = glonass_gnav_eph.i_satellite_slot_number; /* satellite number */
rtklib_sat.iode = glonass_gnav_eph.d_iode; /* IODE (0-6 bit of tb field) */
rtklib_sat.frq = glonass_gnav_eph.i_satellite_freq_channel; /* satellite frequency number */
rtklib_sat.svh = glonass_gnav_eph.d_l3rd_n; /* satellite health*/
rtklib_sat.sva = glonass_gnav_eph.d_F_T; /* satellite accuracy*/
rtklib_sat.age = glonass_gnav_eph.d_E_n; /* satellite age*/
rtklib_sat.pos[0] = glonass_gnav_eph.d_Xn*1000; /* satellite position (ecef) (m) */
rtklib_sat.pos[1] = glonass_gnav_eph.d_Yn*1000; /* satellite position (ecef) (m) */
rtklib_sat.pos[2] = glonass_gnav_eph.d_Zn*1000; /* satellite position (ecef) (m) */
rtklib_sat.vel[0] = glonass_gnav_eph.d_VXn*1000; /* satellite velocity (ecef) (m/s) */
rtklib_sat.vel[1] = glonass_gnav_eph.d_VYn*1000; /* satellite velocity (ecef) (m/s) */
rtklib_sat.vel[2] = glonass_gnav_eph.d_VZn*1000; /* satellite velocity (ecef) (m/s) */
rtklib_sat.acc[0] = glonass_gnav_eph.d_AXn*1000; /* satellite acceleration (ecef) (m/s^2) */
rtklib_sat.acc[1] = glonass_gnav_eph.d_AYn*1000; /* satellite acceleration (ecef) (m/s^2) */
rtklib_sat.acc[2] = glonass_gnav_eph.d_AZn*1000; /* satellite acceleration (ecef) (m/s^2) */
rtklib_sat.taun = glonass_gnav_eph.d_tau_n; /* SV clock bias (s) */
rtklib_sat.gamn = glonass_gnav_eph.d_gamma_n; /* SV relative freq bias */
rtklib_sat.age = glonass_gnav_eph.d_Delta_tau_n; /* delay between L1 and L2 (s) */
utcinfo.tm_mon = 0;
utcinfo.tm_mday = glonass_gnav_eph.d_N_T;
utcinfo.tm_year = glonass_gnav_eph.d_yr - 1900;
utcinfo.tm_hour = 6; // Diff between utc and (utc(su) + 3.00h)
utcinfo.tm_min = 0;
utcinfo.tm_sec = glonass_gnav_eph.d_t_b;
t_utc.time = mktime(&utcinfo);
t_utc.sec = glonass_gnav_eph.d_tau_c;
rtklib_sat.toe = utc2gpst(t_utc); /* epoch of epherides (gpst) */
utcinfo.tm_mon = 0;
utcinfo.tm_mday = glonass_gnav_eph.d_N_T;
utcinfo.tm_year = glonass_gnav_eph.d_yr - 1900;
utcinfo.tm_hour = 6;
utcinfo.tm_min = 0;
utcinfo.tm_sec = glonass_gnav_eph.d_t_k;
t_utc.time = mktime(&utcinfo);
t_utc.sec = glonass_gnav_eph.d_tau_c;
rtklib_sat.tof = utc2gpst(t_utc); /* message frame time (gpst) */
return rtklib_sat;
}
eph_t eph_to_rtklib(const Galileo_Ephemeris & gal_eph) eph_t eph_to_rtklib(const Galileo_Ephemeris & gal_eph)
{ {
eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0, eph_t rtklib_sat = {0, 0, 0, 0, 0, 0, 0, 0, {0, 0}, {0, 0}, {0, 0}, 0.0, 0.0, 0.0, 0.0, 0.0,

View File

@ -36,10 +36,17 @@
#include "galileo_ephemeris.h" #include "galileo_ephemeris.h"
#include "gps_ephemeris.h" #include "gps_ephemeris.h"
#include "gps_cnav_ephemeris.h" #include "gps_cnav_ephemeris.h"
#include "glonass_gnav_ephemeris.h"
eph_t eph_to_rtklib(const Galileo_Ephemeris & gal_eph); eph_t eph_to_rtklib(const Galileo_Ephemeris & gal_eph);
eph_t eph_to_rtklib(const Gps_Ephemeris & gps_eph); eph_t eph_to_rtklib(const Gps_Ephemeris & gps_eph);
eph_t eph_to_rtklib(const Gps_CNAV_Ephemeris & gps_cnav_eph); eph_t eph_to_rtklib(const Gps_CNAV_Ephemeris & gps_cnav_eph);
/*!
* \brief Transforms a Glonass_Gnav_Ephemeris to its RTKLIB counterpart
* \param glonass_gnav_eph GLONASS GNAV Ephemeris structure
* \return Ephemeris structure for RTKLIB parsing
*/
geph_t eph_to_rtklib(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
obsd_t insert_obs_to_rtklib(obsd_t & rtklib_obs, const Gnss_Synchro & gnss_synchro, int week, int band); obsd_t insert_obs_to_rtklib(obsd_t & rtklib_obs, const Gnss_Synchro & gnss_synchro, int week, int band);

View File

@ -36,7 +36,7 @@
#include "Galileo_E1.h" #include "Galileo_E1.h"
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#include "Galileo_E5a.h" #include "Galileo_E5a.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
using google::LogMessage; using google::LogMessage;

View File

@ -40,7 +40,7 @@
#include "Galileo_E1.h" #include "Galileo_E1.h"
#include "Galileo_E5a.h" #include "Galileo_E5a.h"
#include "GPS_L1_CA.h" #include "GPS_L1_CA.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
/* /*
* Create a new instance of signal_generator_c and return * Create a new instance of signal_generator_c and return
@ -115,7 +115,7 @@ void signal_generator_c::init()
/ (GLONASS_L1_CA_CODE_RATE_HZ / GLONASS_L1_CA_CODE_LENGTH_CHIPS))); / (GLONASS_L1_CA_CODE_RATE_HZ / GLONASS_L1_CA_CODE_LENGTH_CHIPS)));
num_of_codes_per_vector_.push_back(galileo_signal ? 4 * static_cast<int>(Galileo_E1_C_SECONDARY_CODE_LENGTH) : 1); num_of_codes_per_vector_.push_back(galileo_signal ? 4 * static_cast<int>(Galileo_E1_C_SECONDARY_CODE_LENGTH) : 1);
data_bit_duration_ms_.push_back(1e3 / GLONASS_CA_TELEMETRY_RATE_BITS_SECOND); data_bit_duration_ms_.push_back(1e3 / GLONASS_GNAV_TELEMETRY_RATE_BITS_SECOND);
} }
else if (system_[sat] == "E") else if (system_[sat] == "E")
{ {

View File

@ -22,6 +22,7 @@ set(TELEMETRY_DECODER_ADAPTER_SOURCES
galileo_e1b_telemetry_decoder.cc galileo_e1b_telemetry_decoder.cc
sbas_l1_telemetry_decoder.cc sbas_l1_telemetry_decoder.cc
galileo_e5a_telemetry_decoder.cc galileo_e5a_telemetry_decoder.cc
glonass_l1_ca_telemetry_decoder.cc
) )
include_directories( include_directories(

View File

@ -0,0 +1,102 @@
/*!
* \file glonass_l1_ca_telemetry_decoder.cc
* \brief Implementation of an adapter of a GLONASS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_l1_ca_telemetry_decoder.h"
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "concurrent_queue.h"
#include "glonass_gnav_ephemeris.h"
#include "glonass_gnav_almanac.h"
#include "glonass_gnav_utc_model.h"
#include "configuration_interface.h"
using google::LogMessage;
GlonassL1CaTelemetryDecoder::GlonassL1CaTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams) :
role_(role),
in_streams_(in_streams),
out_streams_(out_streams)
{
std::string default_dump_filename = "./navigation.dat";
DLOG(INFO) << "role " << role;
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
// make telemetry decoder object
telemetry_decoder_ = glonass_l1_ca_make_telemetry_decoder_cc(satellite_, dump_);
DLOG(INFO) << "telemetry_decoder(" << telemetry_decoder_->unique_id() << ")";
DLOG(INFO) << "global navigation message queue assigned to telemetry_decoder ("<< telemetry_decoder_->unique_id() << ")";
channel_ = 0;
}
GlonassL1CaTelemetryDecoder::~GlonassL1CaTelemetryDecoder()
{}
void GlonassL1CaTelemetryDecoder::set_satellite(Gnss_Satellite satellite)
{
satellite_ = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
telemetry_decoder_->set_satellite(satellite_);
DLOG(INFO) << "TELEMETRY DECODER: satellite set to " << satellite_;
}
void GlonassL1CaTelemetryDecoder::connect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
// Nothing to connect internally
DLOG(INFO) << "nothing to connect internally";
}
void GlonassL1CaTelemetryDecoder::disconnect(gr::top_block_sptr top_block)
{
if(top_block) { /* top_block is not null */};
// Nothing to disconnect
}
gr::basic_block_sptr GlonassL1CaTelemetryDecoder::get_left_block()
{
return telemetry_decoder_;
}
gr::basic_block_sptr GlonassL1CaTelemetryDecoder::get_right_block()
{
return telemetry_decoder_;
}

View File

@ -0,0 +1,92 @@
/*!
* \file glonass_l1_ca_telemetry_decoder.h
* \brief Interface of an adapter of a GLONASS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_L1_CA_TELEMETRY_DECODER_H_
#define GNSS_SDR_GLONASS_L1_CA_TELEMETRY_DECODER_H_
#include <string>
#include "telemetry_decoder_interface.h"
#include "glonass_l1_ca_telemetry_decoder_cc.h"
class ConfigurationInterface;
/*!
* \brief This class implements a NAV data decoder for GLONASS L1 C/A
*/
class GlonassL1CaTelemetryDecoder : public TelemetryDecoderInterface
{
public:
GlonassL1CaTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams);
virtual ~GlonassL1CaTelemetryDecoder();
std::string role()
{
return role_;
}
//! Returns "GLONASS_L1_CA_Telemetry_Decoder"
std::string implementation()
{
return "GLONASS_L1_CA_Telemetry_Decoder";
}
void connect(gr::top_block_sptr top_block);
void disconnect(gr::top_block_sptr top_block);
gr::basic_block_sptr get_left_block();
gr::basic_block_sptr get_right_block();
void set_satellite(Gnss_Satellite satellite);
void set_channel(int channel){telemetry_decoder_->set_channel(channel);}
void reset()
{
return;
}
size_t item_size()
{
return 0;
}
private:
glonass_l1_ca_telemetry_decoder_cc_sptr telemetry_decoder_;
Gnss_Satellite satellite_;
int channel_;
bool dump_;
std::string dump_filename_;
std::string role_;
unsigned int in_streams_;
unsigned int out_streams_;
};
#endif

View File

@ -22,6 +22,7 @@ set(TELEMETRY_DECODER_GR_BLOCKS_SOURCES
galileo_e1b_telemetry_decoder_cc.cc galileo_e1b_telemetry_decoder_cc.cc
sbas_l1_telemetry_decoder_cc.cc sbas_l1_telemetry_decoder_cc.cc
galileo_e5a_telemetry_decoder_cc.cc galileo_e5a_telemetry_decoder_cc.cc
glonass_l1_ca_telemetry_decoder_cc.cc
) )
include_directories( include_directories(

View File

@ -0,0 +1,431 @@
/*!
* \file glonass_l1_ca_telemetry_decoder_cc.cc
* \brief Implementation of an adapter of a GLONASS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_l1_ca_telemetry_decoder_cc.h"
#include <cstdio>
#include <cstdlib>
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "gnss_synchro.h"
#include "convolutional.h"
#define CRC_ERROR_LIMIT 6
using google::LogMessage;
glonass_l1_ca_telemetry_decoder_cc_sptr
glonass_l1_ca_make_telemetry_decoder_cc(Gnss_Satellite satellite, bool dump)
{
return glonass_l1_ca_telemetry_decoder_cc_sptr(new glonass_l1_ca_telemetry_decoder_cc(satellite, dump));
}
glonass_l1_ca_telemetry_decoder_cc::glonass_l1_ca_telemetry_decoder_cc(
Gnss_Satellite satellite,
bool dump) :
gr::block("glonass_l1_ca_telemetry_decoder_cc", gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// Telemetry Bit transition synchronization port out
this->message_port_register_out(pmt::mp("preamble_timestamp_s"));
// Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry"));
// initialize internal vars
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
LOG(INFO) << "Initializing GLONASS L1 CA TELEMETRY DECODING";
// Define the number of sampes per symbol. Notice that GLONASS has 2 rates,
//one for the navigation data and the other for the preamble information
d_samples_per_symbol = ( GLONASS_L1_CA_CODE_RATE_HZ / GLONASS_L1_CA_CODE_LENGTH_CHIPS ) / GLONASS_L1_CA_SYMBOL_RATE_BPS;
// Set the preamble information
unsigned short int preambles_bits[GLONASS_GNAV_PREAMBLE_LENGTH_BITS] = GLONASS_GNAV_PREAMBLE;
// Since preamble rate is different than navigation data rate we use a constant
d_symbols_per_preamble = GLONASS_GNAV_PREAMBLE_LENGTH_SYMBOLS;
memcpy((unsigned short int*)this->d_preambles_bits, (unsigned short int*)preambles_bits, GLONASS_GNAV_PREAMBLE_LENGTH_BITS*sizeof(unsigned short int));
// preamble bits to sampled symbols
d_preambles_symbols = (signed int*)malloc(sizeof(signed int) * d_symbols_per_preamble);
int n = 0;
for (int i = 0; i < GLONASS_GNAV_PREAMBLE_LENGTH_BITS; i++)
{
for (unsigned int j = 0; j < GLONASS_GNAV_TELEMETRY_SYMBOLS_PER_PREAMBLE_BIT; j++)
{
if (d_preambles_bits[i] == 1)
{
d_preambles_symbols[n] = 1;
}
else
{
d_preambles_symbols[n] = -1;
}
n++;
}
}
d_sample_counter = 0;
d_stat = 0;
d_preamble_index = 0;
d_flag_frame_sync = false;
d_flag_parity = false;
d_TOW_at_current_symbol = 0;
delta_t = 0;
d_CRC_error_counter = 0;
d_flag_preamble = false;
d_channel = 0;
flag_TOW_set = false;
}
glonass_l1_ca_telemetry_decoder_cc::~glonass_l1_ca_telemetry_decoder_cc()
{
delete d_preambles_symbols;
if(d_dump_file.is_open() == true)
{
try
{
d_dump_file.close();
}
catch(const std::exception & ex)
{
LOG(WARNING) << "Exception in destructor closing the dump file " << ex.what();
}
}
}
void glonass_l1_ca_telemetry_decoder_cc::decode_string(double *frame_symbols,int frame_length)
{
double chip_acc = 0.0;
int chip_acc_counter = 0;
// 1. Transform from symbols to bits
std::string bi_binary_code;
std::string relative_code;
// Group samples into bi-binary code
for(int i = 0; i < (frame_length); i++)
{
chip_acc += frame_symbols[i];
chip_acc_counter += 1;
if(chip_acc_counter == (GLONASS_GNAV_TELEMETRY_SYMBOLS_PER_BIT))
{
if (chip_acc > 0)
{
bi_binary_code.push_back('1');
chip_acc_counter = 0;
chip_acc = 0;
}
else
{
bi_binary_code.push_back('0');
chip_acc_counter = 0;
chip_acc = 0;
}
}
}
// Convert from bi-binary code to relative code
for(int i = 0; i < (GLONASS_GNAV_STRING_BITS); i++)
{
if(bi_binary_code[2*i] == '1' && bi_binary_code[2*i + 1] == '0')
{
relative_code.push_back('1');
}
else
{
relative_code.push_back('0');
}
}
// 2. Call the GLONASS GNAV string decoder
d_nav.string_decoder(relative_code);
// 3. Check operation executed correctly
if(d_nav.flag_CRC_test == true)
{
LOG(INFO) << "GLONASS GNAV CRC correct on channel " << d_channel << " from satellite "<< d_satellite;
}
else
{
LOG(INFO) << "GLONASS GNAV CRC error on channel " << d_channel << " from satellite " << d_satellite;
}
// 4. Push the new navigation data to the queues
if (d_nav.have_new_ephemeris() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Glonass_Gnav_Ephemeris> tmp_obj = std::make_shared<Glonass_Gnav_Ephemeris>(d_nav.get_ephemeris());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_utc_model() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Glonass_Gnav_Utc_Model> tmp_obj = std::make_shared<Glonass_Gnav_Utc_Model>(d_nav.get_utc_model());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
if (d_nav.have_new_almanac() == true)
{
unsigned int slot_nbr = d_nav.get_ephemeris().i_satellite_slot_number;
std::shared_ptr<Glonass_Gnav_Almanac> tmp_obj= std::make_shared<Glonass_Gnav_Almanac>(d_nav.get_almanac(slot_nbr));
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
}
}
int glonass_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute__((unused)), gr_vector_int &ninput_items __attribute__((unused)),
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items)
{
int corr_value = 0;
int preamble_diff = 0;
Gnss_Synchro **out = (Gnss_Synchro **) &output_items[0];
const Gnss_Synchro **in = (const Gnss_Synchro **) &input_items[0]; //Get the input samples pointer
Gnss_Synchro current_symbol; //structure to save the synchronization information and send the output object to the next block
//1. Copy the current tracking output
current_symbol = in[0][0];
d_symbol_history.push_back(current_symbol); //add new symbol to the symbol queue
d_sample_counter++; //count for the processed samples
consume_each(1);
d_flag_preamble = false;
unsigned int required_symbols=GLONASS_GNAV_STRING_SYMBOLS;
if (d_symbol_history.size()>required_symbols)
{
//******* preamble correlation ********
for (int i = 0; i < d_symbols_per_preamble; i++)
{
if (d_symbol_history.at(i).Prompt_I < 0) // symbols clipping
{
corr_value -= d_preambles_symbols[i];
}
else
{
corr_value += d_preambles_symbols[i];
}
}
}
//******* frame sync ******************
if (d_stat == 0) //no preamble information
{
if (abs(corr_value) >= d_symbols_per_preamble)
{
// Record the preamble sample stamp
d_preamble_index = d_sample_counter;
LOG(INFO) << "Preamble detection for GLONASS L1 C/A SAT " << this->d_satellite;
// Enter into frame pre-detection status
d_stat = 1;
}
}
else if (d_stat == 1) // posible preamble lock
{
if (abs(corr_value) >= d_symbols_per_preamble)
{
//check preamble separation
preamble_diff = d_sample_counter - d_preamble_index;
if (abs(preamble_diff - GLONASS_GNAV_PREAMBLE_PERIOD_SYMBOLS) == 0)
{
//try to decode frame
LOG(INFO) << "Starting string decoder for GLONASS L1 C/A SAT " << this->d_satellite;
d_preamble_index = d_sample_counter; //record the preamble sample stamp
d_stat = 2;
}
else
{
if (preamble_diff > GLONASS_GNAV_PREAMBLE_PERIOD_SYMBOLS)
{
d_stat = 0; // start again
}
DLOG(INFO) << "Failed string decoder for GLONASS L1 C/A SAT " << this->d_satellite;
}
}
}
else if (d_stat == 2)
{
// FIXME: The preamble index marks the first symbol of the string count. Here I just wait for another full string to be received before processing
if (d_sample_counter == d_preamble_index + GLONASS_GNAV_STRING_SYMBOLS)
{
// NEW GLONASS string received
// 0. fetch the symbols into an array
int string_length = GLONASS_GNAV_STRING_SYMBOLS - d_symbols_per_preamble;
double string_symbols[GLONASS_GNAV_DATA_SYMBOLS] = {0};
//******* SYMBOL TO BIT *******
for (int i = 0; i < string_length; i++)
{
if (corr_value > 0)
{
string_symbols[i] = d_symbol_history.at(i + d_symbols_per_preamble).Prompt_I; // because last symbol of the preamble is just received now!
}
else
{
string_symbols[i] = -d_symbol_history.at(i + d_symbols_per_preamble).Prompt_I; // because last symbol of the preamble is just received now!
}
}
//call the decoder
decode_string(string_symbols, string_length);
if (d_nav.flag_CRC_test == true)
{
d_CRC_error_counter = 0;
d_flag_preamble = true; //valid preamble indicator (initialized to false every work())
d_preamble_index = d_sample_counter; //record the preamble sample stamp (t_P)
if (!d_flag_frame_sync)
{
d_flag_frame_sync = true;
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at "
<< d_symbol_history.at(0).Tracking_sample_counter << " [samples]";
}
}
else
{
d_CRC_error_counter++;
d_preamble_index = d_sample_counter; //record the preamble sample stamp
if (d_CRC_error_counter > CRC_ERROR_LIMIT)
{
LOG(INFO) << "Lost of frame sync SAT " << this->d_satellite;
d_flag_frame_sync = false;
d_stat = 0;
}
}
}
}
// UPDATE GNSS SYNCHRO DATA
//2. Add the telemetry decoder information
if (this->d_flag_preamble == true and d_nav.flag_TOW_set == true)
//update TOW at the preamble instant
{
d_TOW_at_current_symbol = floor((d_nav.d_TOW + 2*GLONASS_L1_CA_CODE_PERIOD + GLONASS_GNAV_PREAMBLE_DURATION_S)*1000.0)/1000.0;
}
else //if there is not a new preamble, we define the TOW of the current symbol
{
d_TOW_at_current_symbol = d_TOW_at_current_symbol + GLONASS_L1_CA_CODE_PERIOD;
}
//if (d_flag_frame_sync == true and d_nav.flag_TOW_set==true and d_nav.flag_CRC_test == true)
// if(d_nav.flag_GGTO_1 == true and d_nav.flag_GGTO_2 == true and d_nav.flag_GGTO_3 == true and d_nav.flag_GGTO_4 == true) //all GGTO parameters arrived
// {
// delta_t = d_nav.A_0G_10 + d_nav.A_1G_10 * (d_TOW_at_current_symbol - d_nav.t_0G_10 + 604800.0 * (fmod((d_nav.WN_0 - d_nav.WN_0G_10), 64)));
// }
if (d_flag_frame_sync == true and d_nav.flag_TOW_set == true)
{
current_symbol.Flag_valid_word = true;
}
else
{
current_symbol.Flag_valid_word = false;
}
current_symbol.TOW_at_current_symbol_s = floor(d_TOW_at_current_symbol*1000.0)/1000.0;
current_symbol.TOW_at_current_symbol_s -=delta_t; //Galileo to GPS TOW
if(d_dump == true)
{
// MULTIPLEXED FILE RECORDING - Record results to file
try
{
double tmp_double;
unsigned long int tmp_ulong_int;
tmp_double = d_TOW_at_current_symbol;
d_dump_file.write((char*)&tmp_double, sizeof(double));
tmp_ulong_int = current_symbol.Tracking_sample_counter;
d_dump_file.write((char*)&tmp_ulong_int, sizeof(unsigned long int));
tmp_double = 0;
d_dump_file.write((char*)&tmp_double, sizeof(double));
}
catch (const std::ifstream::failure & e)
{
LOG(WARNING) << "Exception writing observables dump file " << e.what();
}
}
// remove used symbols from history
if (d_symbol_history.size()>required_symbols)
{
d_symbol_history.pop_front();
}
//3. Make the output (copy the object contents to the GNURadio reserved memory)
*out[0] = current_symbol;
return 1;
}
void glonass_l1_ca_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite "<< d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
void glonass_l1_ca_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
try
{
d_dump_filename = "telemetry";
d_dump_filename.append(boost::lexical_cast<std::string>(d_channel));
d_dump_filename.append(".dat");
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
LOG(INFO) << "Telemetry decoder dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (const std::ifstream::failure& e)
{
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}
}

View File

@ -0,0 +1,118 @@
/*!
* \file glonass_l1_ca_telemetry_decoder_cc.h
* \brief Implementation of an adapter of a GLONASS L1 C/A NAV data decoder block
* to a TelemetryDecoderInterface
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_L1_CA_TELEMETRY_DECODER_CC_H
#define GNSS_SDR_GLONASS_L1_CA_TELEMETRY_DECODER_CC_H
#include <fstream>
#include <string>
#include <gnuradio/block.h>
#include "GLONASS_L1_CA.h"
#include "concurrent_queue.h"
#include "gnss_satellite.h"
#include "glonass_gnav_navigation_message.h"
#include "glonass_gnav_ephemeris.h"
#include "glonass_gnav_almanac.h"
#include "glonass_gnav_utc_model.h"
#include "gnss_synchro.h"
class glonass_l1_ca_telemetry_decoder_cc;
typedef boost::shared_ptr<glonass_l1_ca_telemetry_decoder_cc> glonass_l1_ca_telemetry_decoder_cc_sptr;
glonass_l1_ca_telemetry_decoder_cc_sptr glonass_l1_ca_make_telemetry_decoder_cc(Gnss_Satellite satellite, bool dump);
/*!
* \brief This class implements a block that decodes the GNAV data defined in GLONASS ICD v5.1
* \note Code added as part of GSoC 2017 program
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
*/
class glonass_l1_ca_telemetry_decoder_cc : public gr::block
{
public:
~glonass_l1_ca_telemetry_decoder_cc(); //!< Class destructor
void set_satellite(Gnss_Satellite satellite); //!< Set satellite PRN
void set_channel(int channel); //!< Set receiver's channel
/*!
* \brief This is where all signal processing takes place
*/
int general_work (int noutput_items, gr_vector_int &ninput_items,
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
private:
friend glonass_l1_ca_telemetry_decoder_cc_sptr
glonass_l1_ca_make_telemetry_decoder_cc(Gnss_Satellite satellite, bool dump);
glonass_l1_ca_telemetry_decoder_cc(Gnss_Satellite satellite, bool dump);
void decode_string(double *symbols, int frame_length);
//!< Preamble decoding
unsigned short int d_preambles_bits[GLONASS_GNAV_PREAMBLE_LENGTH_BITS];
int *d_preambles_symbols;
unsigned int d_samples_per_symbol;
unsigned int d_samples_per_preamble_symbol;
int d_symbols_per_preamble;
//!< Storage for incoming data
std::deque<Gnss_Synchro> d_symbol_history;
//!< Variables for internal functionality
long unsigned int d_sample_counter; //!< Sample counter as an index (1,2,3,..etc) indicating number of samples processed
long unsigned int d_preamble_index; //!< Index of sample number where preamble was found
unsigned int d_stat; //!< Status of decoder
bool d_flag_frame_sync; //!< Indicate when a frame sync is achieved
bool d_flag_parity; //!< Flag indicating when parity check was achieved (crc check)
bool d_flag_preamble; //!< Flag indicating when preamble was found
int d_CRC_error_counter; //!< Number of failed CRC operations
bool flag_TOW_set; //!< Indicates when time of week is set
double delta_t; //!< GPS-GLONASS time offset
//!< Navigation Message variable
Glonass_Gnav_Navigation_Message d_nav;
//!< Values to populate gnss synchronization structure
double d_TOW_at_current_symbol;
bool Flag_valid_word;
//!< Satellite Information and logging capacity
Gnss_Satellite d_satellite;
int d_channel;
bool d_dump;
std::string d_dump_filename;
std::ofstream d_dump_file;
};
#endif

View File

@ -1,6 +1,6 @@
#include "glonass_l1_ca_dll_pll_c_aid_tracking.h" #include "glonass_l1_ca_dll_pll_c_aid_tracking.h"
#include <glog/logging.h> #include <glog/logging.h>
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "configuration_interface.h" #include "configuration_interface.h"

View File

@ -38,7 +38,7 @@
#include "glonass_l1_ca_dll_pll_tracking.h" #include "glonass_l1_ca_dll_pll_tracking.h"
#include <glog/logging.h> #include <glog/logging.h>
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "configuration_interface.h" #include "configuration_interface.h"

View File

@ -12,7 +12,7 @@
#include "glonass_l1_signal_processing.h" #include "glonass_l1_signal_processing.h"
#include "tracking_discriminators.h" #include "tracking_discriminators.h"
#include "lock_detectors.h" #include "lock_detectors.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "control_message_factory.h" #include "control_message_factory.h"
@ -196,7 +196,7 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking()
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
// Fd=(C/(C+Vr))*F // Fd=(C/(C+Vr))*F
d_glonass_freq_ch = GLONASS_L1_FREQ_HZ + (GLONASS_L1_FREQ_HZ * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN)); d_glonass_freq_ch = GLONASS_L1_CA_FREQ_HZ + (DFRQ1_GLO * static_cast<double>(GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN)));
double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch; double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch;
// new chip and prn sequence periods based on acq Doppler // new chip and prn sequence periods based on acq Doppler
double T_chip_mod_seconds; double T_chip_mod_seconds;
@ -224,7 +224,8 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking()
d_acq_code_phase_samples = corrected_acq_phase_samples; d_acq_code_phase_samples = corrected_acq_phase_samples;
d_carrier_doppler_hz = d_acq_carrier_doppler_hz; d_carrier_doppler_hz = d_acq_carrier_doppler_hz + d_if_freq + (DFRQ1_GLO * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN));
// d_carrier_doppler_hz = d_acq_carrier_doppler_hz;
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
@ -575,7 +576,8 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work (int noutput_items __a
d_dump_file.write(reinterpret_cast<char*>(&d_acc_carrier_phase_cycles), sizeof(double)); d_dump_file.write(reinterpret_cast<char*>(&d_acc_carrier_phase_cycles), sizeof(double));
// carrier and code frequency // carrier and code frequency
d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double)); double if_freq_carrier = d_carrier_doppler_hz + d_if_freq + (DFRQ1_GLO * static_cast<double>(GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN)));
d_dump_file.write(reinterpret_cast<char*>(&if_freq_carrier), sizeof(double));
d_dump_file.write(reinterpret_cast<char*>(&d_code_freq_chips), sizeof(double)); d_dump_file.write(reinterpret_cast<char*>(&d_code_freq_chips), sizeof(double));
//PLL commands //PLL commands

View File

@ -85,7 +85,7 @@ private:
long d_if_freq; long d_if_freq;
long d_fs_in; long d_fs_in;
long d_glonass_freq_ch; double d_glonass_freq_ch;
double d_early_late_spc_chips; double d_early_late_spc_chips;
int d_n_correlator_taps; int d_n_correlator_taps;

View File

@ -13,7 +13,7 @@
#include "glonass_l1_signal_processing.h" #include "glonass_l1_signal_processing.h"
#include "tracking_discriminators.h" #include "tracking_discriminators.h"
#include "lock_detectors.h" #include "lock_detectors.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "control_message_factory.h" #include "control_message_factory.h"
@ -197,7 +197,7 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking()
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
// Fd=(C/(C+Vr))*F // Fd=(C/(C+Vr))*F
d_glonass_freq_ch = GLONASS_L1_FREQ_HZ + (GLONASS_L1_FREQ_HZ * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN)); d_glonass_freq_ch = GLONASS_L1_CA_FREQ_HZ + (GLONASS_L1_CA_FREQ_HZ * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN));
double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch; double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch;
// new chip and prn sequence periods based on acq Doppler // new chip and prn sequence periods based on acq Doppler
double T_chip_mod_seconds; double T_chip_mod_seconds;
@ -225,7 +225,8 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking()
d_acq_code_phase_samples = corrected_acq_phase_samples; d_acq_code_phase_samples = corrected_acq_phase_samples;
d_carrier_doppler_hz = d_acq_carrier_doppler_hz; d_carrier_doppler_hz = d_acq_carrier_doppler_hz + d_if_freq + (DFRQ1_GLO * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN));
// d_carrier_doppler_hz = d_acq_carrier_doppler_hz;
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);

View File

@ -10,7 +10,7 @@
#include "glonass_l1_signal_processing.h" #include "glonass_l1_signal_processing.h"
#include "tracking_discriminators.h" #include "tracking_discriminators.h"
#include "lock_detectors.h" #include "lock_detectors.h"
#include "Glonass_L1_CA.h" #include "GLONASS_L1_CA.h"
#include "control_message_factory.h" #include "control_message_factory.h"
@ -161,7 +161,7 @@ void Glonass_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in); acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in);
// Doppler effect // Doppler effect
// Fd=(C/(C+Vr))*F // Fd=(C/(C+Vr))*F
d_glonass_freq_ch = GLONASS_L1_FREQ_HZ + (GLONASS_L1_FREQ_HZ * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN)); d_glonass_freq_ch = GLONASS_L1_CA_FREQ_HZ + (DFRQ1_GLO * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN));
double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch; double radial_velocity = (d_glonass_freq_ch + d_acq_carrier_doppler_hz) / d_glonass_freq_ch;
// new chip and prn sequence periods based on acq Doppler // new chip and prn sequence periods based on acq Doppler
double T_chip_mod_seconds; double T_chip_mod_seconds;
@ -189,7 +189,8 @@ void Glonass_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
d_acq_code_phase_samples = corrected_acq_phase_samples; d_acq_code_phase_samples = corrected_acq_phase_samples;
d_carrier_doppler_hz = d_acq_carrier_doppler_hz; d_carrier_doppler_hz = d_acq_carrier_doppler_hz + d_if_freq + (DFRQ1_GLO * GLONASS_PRN.at(d_acquisition_gnss_synchro->PRN));
// d_carrier_doppler_hz = d_acq_carrier_doppler_hz;
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
// DLL/PLL filter initialization // DLL/PLL filter initialization

View File

@ -92,6 +92,7 @@
#include "gps_l2c_telemetry_decoder.h" #include "gps_l2c_telemetry_decoder.h"
#include "galileo_e1b_telemetry_decoder.h" #include "galileo_e1b_telemetry_decoder.h"
#include "galileo_e5a_telemetry_decoder.h" #include "galileo_e5a_telemetry_decoder.h"
#include "glonass_l1_ca_telemetry_decoder.h"
#include "sbas_l1_telemetry_decoder.h" #include "sbas_l1_telemetry_decoder.h"
#include "hybrid_observables.h" #include "hybrid_observables.h"
#include "rtklib_pvt.h" #include "rtklib_pvt.h"
@ -528,7 +529,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_1G(
stream << channel; stream << channel;
std::string id = stream.str(); std::string id = stream.str();
LOG(INFO) << "Instantiating Channel " << channel << " with Acquisition Implementation: " LOG(INFO) << "Instantiating Channel " << channel << " with Acquisition Implementation: "
<< acq << ", Tracking Implementation: " << trk << ", Telemetry Decoder implementation: " << tlm; << acq << ", Tracking Implementation: " << trk << ", Telemetry Decoder Implementation: " << tlm;
std::string aux = configuration->property("Acquisition_1G" + boost::lexical_cast<std::string>(channel) + ".implementation", std::string("W")); std::string aux = configuration->property("Acquisition_1G" + boost::lexical_cast<std::string>(channel) + ".implementation", std::string("W"));
std::string appendix1; std::string appendix1;
@ -1203,6 +1204,12 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
out_streams)); out_streams));
block = std::move(block_); block = std::move(block_);
} }
else if (implementation.compare("GLONASS_L1_CA_Telemetry_Decoder") == 0)
{
std::unique_ptr<GNSSBlockInterface> block_(new GlonassL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
// OBSERVABLES ----------------------------------------------------------------- // OBSERVABLES -----------------------------------------------------------------
else if ((implementation.compare("Hybrid_Observables") == 0) || (implementation.compare("GPS_L1_CA_Observables") == 0) || (implementation.compare("GPS_L2C_Observables") == 0) || else if ((implementation.compare("Hybrid_Observables") == 0) || (implementation.compare("GPS_L1_CA_Observables") == 0) || (implementation.compare("GPS_L2C_Observables") == 0) ||
@ -1483,6 +1490,12 @@ std::unique_ptr<TelemetryDecoderInterface> GNSSBlockFactory::GetTlmBlock(
out_streams)); out_streams));
block = std::move(block_); block = std::move(block_);
} }
else if (implementation.compare("GLONASS_L1_CA_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new GlonassL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else else
{ {
// Log fatal. This causes execution to stop. // Log fatal. This causes execution to stop.

View File

@ -597,8 +597,8 @@ void GNSSFlowgraph::set_signals_list()
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28,
29, 30, 31, 32, 33, 34, 35, 36}; 29, 30, 31, 32, 33, 34, 35, 36};
std::set<unsigned int> available_glonass_prn = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, // Removing satellites sharing same frequency number(1 and 5, 2 and 6, 3 and 7, 4 and 6, 11 and 15, 12 and 16, 14 and 18, 17 and 21
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24}; std::set<unsigned int> available_glonass_prn = { 1, 2, 3, 4, 9, 10, 11, 12, 18, 19, 20, 21 };
std::string sv_list = configuration_->property("Galileo.prns", std::string("") ); std::string sv_list = configuration_->property("Galileo.prns", std::string("") );
@ -735,19 +735,19 @@ void GNSSFlowgraph::set_signals_list()
} }
} }
if (configuration_->property("Channels_1G.count", 0) > 0 ) if (configuration_->property("Channels_1G.count", 0) > 0 )
{ {
/* /*
* Loop to create the list of GLONASS L1 C/A signals * Loop to create the list of GLONASS L1 C/A signals
*/ */
for (available_gnss_prn_iter = available_glonass_prn.begin(); for (available_gnss_prn_iter = available_glonass_prn.begin();
available_gnss_prn_iter != available_glonass_prn.end(); available_gnss_prn_iter != available_glonass_prn.end();
available_gnss_prn_iter++) available_gnss_prn_iter++)
{ {
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("Glonass"), available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("Glonass"),
*available_gnss_prn_iter), std::string("1G"))); *available_gnss_prn_iter), std::string("1G")));
} }
} }
/* /*
* Ordering the list of signals from configuration file * Ordering the list of signals from configuration file
*/ */

View File

@ -39,6 +39,10 @@ set(SYSTEM_PARAMETERS_SOURCES
gps_cnav_iono.cc gps_cnav_iono.cc
gps_cnav_utc_model.cc gps_cnav_utc_model.cc
rtcm.cc rtcm.cc
glonass_gnav_ephemeris.cc
glonass_gnav_almanac.cc
glonass_gnav_utc_model.cc
glonass_gnav_navigation_message.cc
) )
@ -59,4 +63,3 @@ add_library(gnss_system_parameters ${SYSTEM_PARAMETERS_SOURCES} ${SYSTEM_PARAMET
source_group(Headers FILES ${SYSTEM_PARAMETERS_HEADERS}) source_group(Headers FILES ${SYSTEM_PARAMETERS_HEADERS})
add_dependencies(gnss_system_parameters rtklib_lib glog-${glog_RELEASE}) add_dependencies(gnss_system_parameters rtklib_lib glog-${glog_RELEASE})
target_link_libraries(gnss_system_parameters rtklib_lib ${Boost_LIBRARIES}) target_link_libraries(gnss_system_parameters rtklib_lib ${Boost_LIBRARIES})

View File

@ -0,0 +1,244 @@
/*!
* \file GLONASS_L1_CA.h
* \brief Defines system parameters for GLONASS L1 C/A signal and NAV data
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_L1_CA_H_
#define GNSS_SDR_GLONASS_L1_CA_H_
#include <vector>
#include <utility> // std::pair
#include "MATH_CONSTANTS.h"
#include "gnss_frequencies.h"
// Physical constants
const double GLONASS_C_m_s = SPEED_OF_LIGHT; //!< The speed of light, [m/s]
const double GLONASS_C_m_ms = 299792.4580; //!< The speed of light, [m/ms]
const double GLONASS_PI = 3.1415926535898; //!< Pi as defined in IS-GPS-200E
const double GLONASS_TWO_PI = 6.283185307179586; //!< 2Pi as defined in IS-GPS-200E
const double GLONASS_OMEGA_EARTH_DOT = 7.292115e-5; //!< Earth rotation rate, [rad/s]
const double GLONASS_GM = 398600.4418e9; //!< Universal gravitational constant times the mass of the Earth, [m^3/s^2]
const double GLONASS_fM_a = 0.35e9; //!< Gravitational constant of atmosphere [m^3/s^2]
const double GLONASS_SEMI_MAJOR_AXIS = 6378136; //!< Semi-major axis of Earth [m]
const double GLONASS_FLATTENING = 1/29825784; //!< Flattening parameter
const double GLONASS_GRAVITY = 97803284; //!< Equatorial acceleration of gravity [mGal]
const double GLONASS_GRAVITY_CORRECTION = 0.87; //!< Correction to acceleration of gravity at sea-level due to Atmosphere[мGal]
const double GLONASS_J2 = 1082625.75e-9; //!< Second zonal harmonic of the geopotential
const double GLONASS_J4 = -2370.89e-9; //!<Fourth zonal harmonic of the geopotential
const double GLONASS_J6 = 6.08e-9; //!< Sixth zonal harmonic of the geopotential
const double GLONASS_J8 = 1.40e-11; //!< Eighth zonal harmonic of the geopotential
const double GLONASS_U0 = 62636861.4; //!< Normal potential at surface of common terrestrial ellipsoid [m^2/s^2]
const double GLONASS_C20 = -1082.63e-6; //!< Second zonal coefficient of spherical harmonic expansion
const double GLONASS_EARTH_RADIUS = 6378.136; //!< Equatorial radius of Earth [km]
const double GLONASS_EARTH_INCLINATION = 0.000409148809899e3; //!< Mean inclination of ecliptic to equator (23 deg 26 min 33 sec) [rad]
const double GLONASS_TAU_0 = -0.005835151531174e3; //!< (-334 deg 19 min 46.40 sec) [rad];
const double GLONASS_TAU_1 = 0.071018041257371e3; //!< (4069 deg 02 min 02.52 sec) [rad];
const double GLONASS_MOON_Q0 = -0.001115184961435e3; //!< (-63 deg 53 min 43.41 sec) [rad]
const double GLONASS_MOON_Q1 = 8.328691103668023e3; //!< (477198 deg 50 min 56.79 sec) [rad]
const double GLONASS_MOON_OMEGA_0 = 0.004523601514852e3; //!< (259 deg 10 min 59.79 sec) [rad]
const double GLONASS_MOON_OMEGA_1 = -0.033757146246552e3; //!< (-1934 deg 08 min 31.23 sec) [rad]
const double GLONASS_MOON_GM = 4902.835; //!< Lunar gravitational constant [km^3/s^2]
const double GLONASS_MOON_SEMI_MAJOR_AXIS = 3.84385243e5; //!< Semi-major axis of lunar orbit [km];
const double GLONASS_MOON_ECCENTRICITY = 0.054900489; //!< Eccentricity of lunar orbit
const double GLONASS_MOON_INCLINATION = 0.000089803977407e3; //!< Inclination of lunar orbit to ecliptic plane (5 deg 08 min 43.4 sec) [rad]
const double GLONASS_SUN_OMEGA = 0.004908229466869e3; //!< TODO What is this operation in the seconds with T?(281 deg 13 min 15.0 + 6189.03*Т sec) [rad]
const double GLONASS_SUN_Q0 = 0.006256583774423e3; //!< (358 deg 28 min 33.04 sec) [rad]
const double GLONASS_SUN_Q1 = 0e3; //!< TODO Why is the value greater than 60?(129596579.10 sec) [rad]
const double GLONASS_SUN_GM = 0.1325263e12; //!< Solar gravitational constant [km^3/s^2]
const double GLONASS_SUN_SEMI_MAJOR_AXIS = 1.49598e8; //!< Semi-major axis of solar orbit [km];
const double GLONASS_SUN_ECCENTRICITY = 0.016719; //!< Eccentricity of solar orbit
// carrier and code frequencies
const double GLONASS_L2_FREQ_HZ = FREQ2_GLO; //!< L1 [Hz]
const double GLONASS_L1_CA_FREQ_HZ = FREQ1_GLO; //!< L1 [Hz]
const double GLONASS_L1_CA_DFREQ_HZ = DFRQ1_GLO; //!< Freq Bias for GLONASS L1 [Hz]
const double GLONASS_L1_CA_CODE_RATE_HZ = 0.511e6; //!< GLONASS L1 C/A code rate [chips/s]
const double GLONASS_L1_CA_CODE_LENGTH_CHIPS = 511.0; //!< GLONASS L1 C/A code length [chips]
const double GLONASS_L1_CA_CODE_PERIOD = 0.001; //!< GLONASS L1 C/A code period [seconds]
const double GLONASS_L1_CA_CHIP_PERIOD = 1.9569e-06; //!< GLONASS L1 C/A chip period [seconds]
const double GLONASS_L1_CA_SYMBOL_RATE_BPS = 1000;
//FIXME Probably should use leap seconds definitions of rtklib
const double GLONASS_LEAP_SECONDS[21][7] = { /* leap seconds (y,m,d,h,m,s,utc-gpst) */
{2019, 1, 1, 0, 0, 0, -20},
{2018, 1, 1, 0, 0, 0, -19},
{2017, 1, 1, 0, 0, 0, -18},
{2015, 7, 1, 0, 0, 0, -17},
{2012, 7, 1, 0, 0, 0, -16},
{2009, 1, 1, 0, 0, 0, -15},
{2006, 1, 1, 0, 0, 0, -14},
{1999, 1, 1, 0, 0, 0, -13},
{1997, 7, 1, 0, 0, 0, -12},
{1996, 1, 1, 0, 0, 0, -11},
{1994, 7, 1, 0, 0, 0, -10},
{1993, 7, 1, 0, 0, 0, -9},
{1992, 7, 1, 0, 0, 0, -8},
{1991, 1, 1, 0, 0, 0, -7},
{1990, 1, 1, 0, 0, 0, -6},
{1988, 1, 1, 0, 0, 0, -5},
{1985, 7, 1, 0, 0, 0, -4},
{1983, 7, 1, 0, 0, 0, -3},
{1982, 7, 1, 0, 0, 0, -2},
{1981, 7, 1, 0, 0, 0, -1},
{}
};
// GLONASS SV's orbital slots PRN = (orbital_slot - 1)
const std::map<unsigned int, int> GLONASS_PRN =
{{ 0, 8,}, //For test
{ 1, 1,}, //Plane 1
{ 2,-4,}, //Plane 1
{ 3, 5,}, //Plane 1
{ 4, 6,}, //Plane 1
{ 5, 1,}, //Plane 1
{ 6,-4,}, //Plane 1
{ 7, 5,}, //Plane 1
{ 8, 6,}, //Plane 1
{ 9,-2,}, //Plane 2
{10,-7,}, //Plane 2
{11, 0,}, //Plane 2
{12,-1,}, //Plane 2
{13,-2,}, //Plane 2
{14,-7,}, //Plane 2
{15, 0,}, //Plane 2
{16,-1,}, //Plane 2
{17, 4,}, //Plane 3
{18,-3,}, //Plane 3
{19, 3,}, //Plane 3
{20, 2,}, //Plane 3
{21, 4,}, //Plane 3
{22,-3,}, //Plane 3
{23, 3,}, //Plane 3
{24, 2}}; //Plane 3
const double GLONASS_STARTOFFSET_ms = 68.802; //[ms] Initial sign. travel time (this cannot go here)
// OBSERVABLE HISTORY DEEP FOR INTERPOLATION
const int GLONASS_L1_CA_HISTORY_DEEP = 100;
// NAVIGATION MESSAGE DEMODULATION AND DECODING
#define GLONASS_GNAV_PREAMBLE {1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 0, 1, 1, 1, 0, 1, 0, 1, 0, 0, 0, 0, 1, 0, 0, 1, 0, 1, 1, 0}
const double GLONASS_GNAV_PREAMBLE_DURATION_S = 0.3;
const int GLONASS_GNAV_PREAMBLE_LENGTH_BITS = 30;
const int GLONASS_GNAV_PREAMBLE_LENGTH_SYMBOLS = 300;
const int GLONASS_GNAV_PREAMBLE_PERIOD_SYMBOLS = 2000;
const int GLONASS_GNAV_TELEMETRY_RATE_BITS_SECOND = 50; //!< NAV message bit rate [bits/s]
const int GLONASS_GNAV_TELEMETRY_SYMBOLS_PER_BIT = 10;
const int GLONASS_GNAV_TELEMETRY_SYMBOLS_PER_PREAMBLE_BIT = 10;
const int GLONASS_GNAV_TELEMETRY_RATE_SYMBOLS_SECOND = GLONASS_GNAV_TELEMETRY_RATE_BITS_SECOND*GLONASS_GNAV_TELEMETRY_SYMBOLS_PER_BIT; //!< NAV message bit rate [symbols/s]
const int GLONASS_GNAV_STRING_SYMBOLS = 2000; //!< Number of bits per string in the GNAV message (85 data bits + 30 time mark bits) [bits]
const int GLONASS_GNAV_STRING_BITS = 85; //!< Number of bits per string in the GNAV message (85 data bits + 30 time mark bits) [bits]
const int GLONASS_GNAV_HAMMING_CODE_BITS = 8; //!< Number of bits in hamming code sequence of GNAV message
const int GLONASS_GNAV_DATA_SYMBOLS = 1700; // STRING DATA WITHOUT PREAMBLE
const std::vector<int> GLONASS_GNAV_CRC_I_INDEX {9, 10, 12, 13, 15, 17, 19, 20, 22, 24, 26, 28, 30, 32, 34, 35, 37, 39, 41, 43, 45, 47, 49, 51, 53, 55, 57, 59, 61, 63, 65, 66, 68, 70, 72, 74, 76, 78, 80, 82, 84};
const std::vector<int> GLONASS_GNAV_CRC_J_INDEX {9, 11, 12, 14, 15, 18, 19, 21, 22, 25, 26, 29, 30, 33, 34, 36, 37, 40, 41, 44, 45, 48, 49, 52, 53, 56, 57, 60, 61, 64, 65, 67, 68, 71, 72, 75, 76, 79, 80, 83, 84};
const std::vector<int> GLONASS_GNAV_CRC_K_INDEX {10, 11, 12, 16, 17, 18, 19, 23, 24, 25, 26, 31, 32, 33, 34, 38, 39, 40, 41, 46, 47, 48, 49, 54, 55, 56, 57, 62, 63, 64, 65, 69, 70, 71, 72, 77, 78, 79, 80, 85};
const std::vector<int> GLONASS_GNAV_CRC_L_INDEX {9, 11, 12, 14, 15, 18, 19, 21, 22, 25, 26, 29, 30, 33, 34, 36, 37, 40, 41, 44, 45, 48, 49, 52, 53, 56, 57, 60, 61, 64, 65, 67, 68, 71, 72, 75, 76, 79, 80, 83, 84};
const std::vector<int> GLONASS_GNAV_CRC_M_INDEX {20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 81, 82, 83, 84, 85};
const std::vector<int> GLONASS_GNAV_CRC_N_INDEX {35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85};
const std::vector<int> GLONASS_GNAV_CRC_P_INDEX {66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85};
const std::vector<int> GLONASS_GNAV_CRC_Q_INDEX {9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85};
// GLONASS GNAV NAVIGATION MESSAGE STRUCTURE
// NAVIGATION MESSAGE FIELDS POSITIONS (from IS-GPS-200E Appendix II)
// FRAME 1-4
// COMMON FIELDS
const std::vector<std::pair<int,int>> STRING_ID({{2,4}});
const std::vector<std::pair<int,int>> KX({{78,8}});
//STRING 1
const std::vector<std::pair<int,int>> P1({{8,2}});
const std::vector<std::pair<int,int>> T_K_HR({{10,5}});
const std::vector<std::pair<int,int>> T_K_MIN({{15,6}});
const std::vector<std::pair<int,int>> T_K_SEC({{21,1}});
const std::vector<std::pair<int,int>> X_N_DOT ({{22,24}});
const std::vector<std::pair<int,int>> X_N_DOT_DOT ({{46,5}});
const std::vector<std::pair<int,int>> X_N({{51,27}});
//STRING 2
const std::vector<std::pair<int,int>> B_N({{6,3}});
const std::vector<std::pair<int,int>> P2({{9,1}});
const std::vector<std::pair<int,int>> T_B({{10,7}});
const std::vector<std::pair<int,int>> Y_N_DOT ({{22,24}});
const std::vector<std::pair<int,int>> Y_N_DOT_DOT ({{46,5}});
const std::vector<std::pair<int,int>> Y_N({{51,27}});
//STRING 3
const std::vector<std::pair<int,int>> P3({{6,1}});
const std::vector<std::pair<int,int>> GAMMA_N({{7,11}});
const std::vector<std::pair<int,int>> P({{19,2}});
const std::vector<std::pair<int,int>> EPH_L_N({{21,1}});
const std::vector<std::pair<int,int>> Z_N_DOT ({{22,24}});
const std::vector<std::pair<int,int>> Z_N_DOT_DOT ({{46,5}});
const std::vector<std::pair<int,int>> Z_N({{51,27}});
// STRING 4
const std::vector<std::pair<int,int>> TAU_N({{6,22}});
const std::vector<std::pair<int,int>> DELTA_TAU_N({{28,5}});
const std::vector<std::pair<int,int>> E_N({{33,5}});
const std::vector<std::pair<int,int>> P4 ({{52,1}});
const std::vector<std::pair<int,int>> F_T ({{53,4}});
const std::vector<std::pair<int,int>> N_T({{60,11}});
const std::vector<std::pair<int,int>> N({{71,5}});
const std::vector<std::pair<int,int>> M({{76,2}});
// STRING 5
const std::vector<std::pair<int,int>> N_A({{6,11}});
const std::vector<std::pair<int,int>> TAU_C({{17,32}});
const std::vector<std::pair<int,int>> N_4({{50,5}});
const std::vector<std::pair<int,int>> TAU_GPS({{55,22}});
const std::vector<std::pair<int,int>> ALM_L_N({{77,1}});
// STRING 6, 8, 10, 12, 14
const std::vector<std::pair<int,int>> C_N({{6,1}});
const std::vector<std::pair<int,int>> M_N_A({{7,2}});
const std::vector<std::pair<int,int>> n_A({{9,5}});
const std::vector<std::pair<int,int>> TAU_N_A({{14,10}});
const std::vector<std::pair<int,int>> LAMBDA_N_A({{24,21}});
const std::vector<std::pair<int,int>> DELTA_I_N_A({{45,18}});
const std::vector<std::pair<int,int>> EPSILON_N_A({{63,15}});
//STRING 7, 9, 11, 13, 15
const std::vector<std::pair<int,int>> OMEGA_N_A({{6,16}});
const std::vector<std::pair<int,int>> T_LAMBDA_N_A({{22,21}});
const std::vector<std::pair<int,int>> DELTA_T_N_A({{43,22}});
const std::vector<std::pair<int,int>> DELTA_T_DOT_N_A({{65,7}});
const std::vector<std::pair<int,int>> H_N_A({{72,5}});
// STRING 14 FRAME 5
const std::vector<std::pair<int,int>> B1({{6,11}});
const std::vector<std::pair<int,int>> B2({{17,10}});
#endif /* GNSS_SDR_GLONASS_L1_CA_H_ */

View File

@ -1,69 +0,0 @@
#ifndef GNSS_SDR_GLONASS_L1_CA_H_
#define GNSS_SDR_GLONASS_L1_CA_H_
#include <vector>
#include <map> // std::map
#include "MATH_CONSTANTS.h"
#include "gnss_frequencies.h"
// Physical constants
const double GLONASS_C_m_s = 299792458.0; //!< The speed of light, [m/s]
const double GLONASS_C_m_ms = 299792.4580; //!< The speed of light, [m/ms]
const double GLONASS_PI = 3.1415926535898; //!< Pi as (NOT) defined in ICD-GLONASS-2008
const double GLONASS_TWO_PI = 6.283185307179586;//!< 2Pi as (NOT) defined in ICD-GLONASS-2008
const double GLONASS_OMEGA_EARTH_DOT = 7.292115e-5; //!< Earth rotation rate, [rad/s]
const double GLONASS_GM = 3.986004418e14; //!< Universal gravitational constant times the mass of the Earth, [m^3/s^2]
// const double F = -4.442807633e-10; //!< Constant, [s/(m)^(1/2)]
// Geodesic constants and parameters
const double fMa = 0.35e9; //!< The Gravitational constant of atmosphere, [m^3/s^2]
const double SEMI_MAJOR_AXIS = 6378136; //!< The Semi-major axis, [m]
const double FLATTENING = 1/298.25784; //!< The Orbital Flattening
const double EQUATORIAL_GRAVITY = 978032.84; //!< The Equatorial acceleration of gravity, [mGal]
const double GRAVITY_CORRECTION = 0.87; //!< The Correction to acceleration of gravity at sea-level due to Atmosphere, [mGal]
const double SECOND_HARMONIC = 1082625.75e-9; //!< Second zonal harmonic of the geopotential (J_2^0)
const double FOURTH_HARMONIC = -2370.89e-9; //!< Fourth zonal harmonic of the geopotential (J_4^0)
const double SIXTH_HARMONIC = 6.08e-9; //!< Sixth zonal harmonic of the geopotential (J_6^0)
const double EIGHTH_HARMONIC = 1.40e-11; //!< Eighth zonal harmonic of the geopotential (J_8^0)
const double NORMAL_POTENCIAL = 62636861.4; //!< The Normal potential at surface of common terrestrial ellipsoid (U_0), [m^2/s^2]
// carrier and code frequencies
const double GLONASS_L1_FREQ_HZ = FREQ1_GLO; //!< L1 [Hz]
const double GLONASS_L1_CA_CODE_RATE_HZ = 0.511e6; //!< GLONASS L1 C/A code rate [chips/s]
const double GLONASS_L1_CA_CODE_LENGTH_CHIPS = 511.0; //!< GLONASS L1 C/A code length [chips]
const double GLONASS_L1_CA_CODE_PERIOD = 0.001; //!< GLONASS L1 C/A code period [seconds]
const double GLONASS_L1_CA_CHIP_PERIOD = 1.9569e-06; //!< GLONASS L1 C/A chip period [seconds]
// GLONASS SV's orbital slots PRN = (orbital_slot - 1)
const std::map<unsigned int, int> GLONASS_PRN =
{{ 0, 8,}, //For test
{ 1, 1,}, //Plane 1
{ 2,-4,}, //Plane 1
{ 3, 5,}, //Plane 1
{ 4, 6,}, //Plane 1
{ 5, 1,}, //Plane 1
{ 6,-4,}, //Plane 1
{ 7, 5,}, //Plane 1
{ 8, 6,}, //Plane 1
{ 9,-2,}, //Plane 2
{10,-7,}, //Plane 2
{11, 0,}, //Plane 2
{12,-1,}, //Plane 2
{13,-2,}, //Plane 2
{14,-7,}, //Plane 2
{15, 0,}, //Plane 2
{16,-1,}, //Plane 2
{17, 4,}, //Plane 3
{18,-3,}, //Plane 3
{19, 3,}, //Plane 3
{20, 2,}, //Plane 3
{21, 4,}, //Plane 3
{22,-3,}, //Plane 3
{23, 3,}, //Plane 3
{24, 2}}; //Plane 3
const int GLONASS_CA_TELEMETRY_RATE_BITS_SECOND = 50; //!< NAV message bit rate [bits/s]
#endif /* GNSS_SDR_GLONASS_L1_CA_H_ */

View File

@ -65,6 +65,7 @@ const double TWO_N14 = (0.00006103515625); //!< 2^-14
const double TWO_N15 = (0.00003051757813); //!< 2^-15 const double TWO_N15 = (0.00003051757813); //!< 2^-15
const double TWO_N16 = (0.0000152587890625); //!< 2^-16 const double TWO_N16 = (0.0000152587890625); //!< 2^-16
const double TWO_N17 = (7.629394531250000e-006); //!< 2^-17 const double TWO_N17 = (7.629394531250000e-006); //!< 2^-17
const double TWO_N18 = (3.814697265625000e-006); //!< 2^-18
const double TWO_N19 = (1.907348632812500e-006); //!< 2^-19 const double TWO_N19 = (1.907348632812500e-006); //!< 2^-19
const double TWO_N20 = (9.536743164062500e-007); //!< 2^-20 const double TWO_N20 = (9.536743164062500e-007); //!< 2^-20
const double TWO_N21 = (4.768371582031250e-007); //!< 2^-21 const double TWO_N21 = (4.768371582031250e-007); //!< 2^-21

View File

@ -0,0 +1,177 @@
/*!
* \file glonass_gnav_almanac.cc
* \brief Interface of a GLONASS GNAV ALMANAC storage as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_gnav_almanac.h"
#include <cmath>
#include "GLONASS_L1_CA.h"
#include "gnss_satellite.h"
Glonass_Gnav_Almanac::Glonass_Gnav_Almanac()
{
i_satellite_freq_channel = 0;
i_satellite_PRN = 0;
i_satellite_slot_number = 0;
d_n_A = 0.0;
d_H_n_A = 0.0;
d_lambda_n_A = 0.0;
d_t_lambda_n_A = 0.0;
d_Delta_i_n_A = 0.0;
d_Delta_T_n_A = 0.0;
d_Delta_T_n_A_dot = 0.0;
d_epsilon_n_A = 0.0;
d_omega_n_A = 0.0;
d_M_n_A = 0.0;
d_KP = 0.0;
d_tau_n_A = 0.0;
d_C_n = false;
d_l_n = false;
}
void Glonass_Gnav_Almanac::satellite_position(double N_A, double N_i, double t_i)
{
double T_nom = 43200; // [seconds]
double i_nom = D2R*63.0; // [rad]
double Delta_t = 0.0;
double i = 0.0;
double T = 0.0;
double n = 0.0;
double a = 0.0;
double lambda_dot = 0.0;
double omega_dot = 0.0;
double lambda = 0.0;
double omega = 0.0;
double E_P = 0.0;
double Delta_T = 0.0;
double M = 0.0;
double E = 0.0;
double E_old = 0.0;
double dE = 0.0;
double e1_x = 0.0;
double e1_y = 0.0;
double e1_z = 0.0;
double e2_x = 0.0;
double e2_y = 0.0;
double e2_z = 0.0;
// Compute time difference to reference time
Delta_t = (N_i - N_A) * 86400 + (t_i + d_t_lambda_n_A);
// Compute the actual inclination
i = i_nom + d_Delta_i_n_A;
// Compute the actual orbital period:
T = T_nom + d_Delta_T_n_A;
// Compute the mean motion
n = 2*GLONASS_PI/T;
// Compute the semi-major axis:
a = cbrt(GLONASS_GM/(n*n));
// Compute correction to longitude of ascending node
lambda_dot = -10*pow(GLONASS_SEMI_MAJOR_AXIS / a, 7/2)*D2R*cos(i)/86400;
// Compute correction to argument of perigee
omega_dot = 5*pow(GLONASS_SEMI_MAJOR_AXIS / a, 7/2)*D2R*(5*cos(i)*cos(i) - 1)/86400;
// Compute corrected longitude of ascending node:
lambda = d_lambda_n_A + (lambda_dot - GLONASS_OMEGA_EARTH_DOT)*Delta_t;
// Compute corrected argument of perigee:
omega = d_omega_n_A + omega_dot*Delta_t;
// Compute eccentric anomaly at point P: Note: P is that point of the orbit the true anomaly of which is identical to the argument of perigee.
E_P = 2*atan(tan((omega/2)*(sqrt((1 - d_epsilon_n_A)*(1 + d_epsilon_n_A)))));
// Compute time difference to perigee passing
if (omega < GLONASS_PI)
{
Delta_T = (E_P - d_epsilon_n_A*sin(E_P))/n;
}
else
{
Delta_T = (E_P - d_epsilon_n_A*sin(E_P))/n + T;
}
// Compute mean anomaly at epoch t_i:
M = n * (Delta_t - Delta_T);
// Compute eccentric anomaly at epoch t_i. Note: Keplers equation has to be solved iteratively
// Initial guess of eccentric anomaly
E = M;
// --- Iteratively compute eccentric anomaly ----------------------------
for (int ii = 1; ii < 20; ii++)
{
E_old = E;
E = M + d_epsilon_n_A * sin(E);
dE = fmod(E - E_old, 2.0 * GLONASS_PI);
if (fabs(dE) < 1e-12)
{
//Necessary precision is reached, exit from the loop
break;
}
}
// Compute position in orbital coordinate system
d_satpos_Xo = a*cos(E) - d_epsilon_n_A;
d_satpos_Yo = a*sqrt(1 - d_epsilon_n_A*d_epsilon_n_A)*sin(E);
d_satpos_Zo = a*0;
// Compute velocity in orbital coordinate system
d_satvel_Xo = a/(1-d_epsilon_n_A*cos(E))*(-n*sin(E));
d_satvel_Yo = a/(1-d_epsilon_n_A*cos(E))*(n*sqrt(1 - d_epsilon_n_A*d_epsilon_n_A)*cos(E));
d_satvel_Zo = a/(1-d_epsilon_n_A*cos(E))*(0);
// Determine orientation vectors of orbital coordinate system in ECEF system
e1_x = cos(omega)*cos(lambda) - sin(omega)*sin(lambda);
e1_y = cos(omega)*sin(lambda) + sin(omega)*cos(lambda)*cos(i);
e1_z = sin(omega)*sin(i);
e2_x = -sin(omega)*cos(lambda) - sin(omega)*sin(lambda)*cos(i);
e2_y = -sin(omega)*sin(lambda) + cos(omega)*cos(lambda)*cos(i);
e2_z = cos(omega)*sin(i);
// Convert position from orbital to ECEF system
d_satpos_X = d_satpos_Xo*e1_x + d_satpos_Xo*e2_x;
d_satpos_Y = d_satpos_Yo*e1_z + d_satpos_Yo*e2_y;
d_satpos_Z = d_satpos_Zo*e1_z + d_satpos_Zo*e2_z;
// Convert position from orbital to ECEF system
d_satvel_X = d_satvel_Xo*e1_x + d_satvel_Xo*e2_x + GLONASS_OMEGA_EARTH_DOT*d_satpos_Y;
d_satvel_Y = d_satvel_Yo*e1_z + d_satvel_Yo*e2_y - GLONASS_OMEGA_EARTH_DOT*d_satpos_X;
d_satvel_Z = d_satvel_Zo*e1_z + d_satvel_Zo*e2_z;
}

View File

@ -0,0 +1,123 @@
/*!
* \file glonass_gnav_almanac.h
* \brief Interface of a GLONASS GNAV ALMANAC storage
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_ALMANAC_H_
#define GNSS_SDR_GLONASS_ALMANAC_H_
#include <map>
#include <string>
#include "boost/assign.hpp"
#include <boost/serialization/nvp.hpp>
/*!
* \brief This class is a storage for the GLONASS SV ALMANAC data as described GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*/
class Glonass_Gnav_Almanac
{
public:
double d_n_A; //!< Conventional number of satellite within GLONASS space segment [dimensionless]
double d_H_n_A; //!< Carrier frequency number of navigation RF signal transmitted by d_nA satellite as table 4.10 (0-31) [dimensionless]
double d_lambda_n_A; //!< Longitude of the first (within the d_NA day) ascending node of d_nA [semi-circles]
double d_t_lambda_n_A; //!< Time of first ascending node passage [s]
double d_Delta_i_n_A; //!< Correction of the mean value of inclination of d_n_A satellite at instant t_lambda_n_A [semi-circles]
double d_Delta_T_n_A; //!< Correction to the mean value of Draconian period of d_n_A satellite at instant t_lambda_n_A[s / orbital period]
double d_Delta_T_n_A_dot; //!< Rate of change of Draconian period of d_n_A satellite at instant t_lambda_n_A [s / orbital period^2]
double d_epsilon_n_A; //!< Eccentricity of d_n_A satellite at instant t_lambda_n_A [dimensionless]
double d_omega_n_A; //!< Argument of preigree of d_n_A satellite at instant t_lambdan_A [semi-circles]
double d_M_n_A; //!< Type of satellite n_A [dimensionless]
double d_KP; //!< Notification on forthcoming leap second correction of UTC [dimensionless]
double d_tau_n_A; //!< Coarse value of d_n_A satellite time correction to GLONASS time at instant t_lambdan_A[s]
bool d_C_n; //!< Generalized “unhealthy flag” of n_A satellite at instant of almanac upload [dimensionless]
bool d_l_n; //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
// Satellite Identification Information
int i_satellite_freq_channel; //!< SV Frequency Channel Number
unsigned int i_satellite_PRN; //!< SV PRN Number, equivalent to slot number for compatibility with GPS
unsigned int i_satellite_slot_number; //!< SV Slot Number
// satellite positions
double d_satpos_Xo; //!< Earth-fixed coordinate x of the satellite in PZ-90.02 coordinate system [km].
double d_satpos_Yo; //!< Earth-fixed coordinate y of the satellite in PZ-90.02 coordinate system [km]
double d_satpos_Zo; //!< Earth-fixed coordinate z of the satellite in PZ-90.02 coordinate system [km]
// Satellite velocity
double d_satvel_Xo; //!< Earth-fixed velocity coordinate x of the satellite in PZ-90.02 coordinate system [km/s]
double d_satvel_Yo; //!< Earth-fixed velocity coordinate y of the satellite in PZ-90.02 coordinate system [km/s]
double d_satvel_Zo; //!< Earth-fixed velocity coordinate z of the satellite in PZ-90.02 coordinate system [km/s]
// satellite positions
double d_satpos_X; //!< Earth-fixed coordinate x of the satellite in PZ-90.02 coordinate system [km].
double d_satpos_Y; //!< Earth-fixed coordinate y of the satellite in PZ-90.02 coordinate system [km]
double d_satpos_Z; //!< Earth-fixed coordinate z of the satellite in PZ-90.02 coordinate system [km]
// Satellite velocity
double d_satvel_X; //!< Earth-fixed velocity coordinate x of the satellite in PZ-90.02 coordinate system [km/s]
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite in PZ-90.02 coordinate system [km/s]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite in PZ-90.02 coordinate system [km/s]
template<class Archive>
/*!
* \brief Serialize is a boost standard method to be called by the boost XML serialization. Here is used to save the almanac data on disk file.
*/
void serialize(Archive& archive, const unsigned int version)
{
using boost::serialization::make_nvp;
if(version){};
archive & make_nvp("i_satellite_freq_channel", i_satellite_freq_channel);
archive & make_nvp("i_satellite_PRN", i_satellite_PRN);
archive & make_nvp("i_satellite_slot_number", i_satellite_slot_number);
archive & make_nvp("d_n_A", d_n_A);
archive & make_nvp("d_H_n_A", d_H_n_A);
archive & make_nvp("d_lambda_n_A", d_lambda_n_A);
archive & make_nvp("d_t_lambda_n_A", d_t_lambda_n_A);
archive & make_nvp("d_Delta_i_n_A", d_Delta_i_n_A);
archive & make_nvp("d_Delta_T_n_A", d_Delta_T_n_A);
archive & make_nvp("d_Delta_T_n_A_dot", d_Delta_T_n_A_dot);
archive & make_nvp("d_epsilon_n_A", d_epsilon_n_A);
archive & make_nvp("d_omega_n_A", d_omega_n_A);
archive & make_nvp("d_M_n_A", d_M_n_A);
archive & make_nvp("d_KP", d_KP);
archive & make_nvp("d_tau_n_A", d_tau_n_A);
archive & make_nvp("d_C_n", d_C_n);
archive & make_nvp("d_l_n", d_l_n);
}
void satellite_position(double N_A, double N_i, double t_i);
/*!
* Default constructor
*/
Glonass_Gnav_Almanac();
};
#endif

View File

@ -0,0 +1,123 @@
/*!
* \file glonass_gnav_ephemeris.cc
* \brief Interface of a GLONASS GNAV EPHEMERIS storage and orbital model functions
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_gnav_ephemeris.h"
#include <cmath>
#include <boost/date_time/posix_time/posix_time.hpp>
#include "GLONASS_L1_CA.h"
#include "gnss_satellite.h"
Glonass_Gnav_Ephemeris::Glonass_Gnav_Ephemeris()
{
d_m = 0.0; //!< String number within frame [dimensionless]
d_t_k = 0.0; //!< GLONASS Time (UTC(SU) + 3 h) referenced to the beginning of the frame within the current day [s]
d_t_b = 0.0; //!< Reference ephemeris relative time in GLONASS Time (UTC(SU) + 3 h). Index of a time interval within current day according to UTC(SU) + 03 hours 00 min. [s]
d_M = 0.0; //!< Type of satellite transmitting navigation signal [dimensionless]
d_gamma_n = 0.0; //!< Relative deviation of predicted carrier frequency value of n- satellite from nominal value at the instant tb [dimensionless]
d_tau_n = 0.0; //!< Correction to the nth satellite time (tn) relative to GLONASS time (te),
d_Xn = 0.0; //!< Earth-fixed coordinate x of the satellite in PZ-90.02 coordinate system [km].
d_Yn = 0.0; //!< Earth-fixed coordinate y of the satellite in PZ-90.02 coordinate system [km]
d_Zn = 0.0; //!< Earth-fixed coordinate z of the satellite in PZ-90.02 coordinate system [km]
d_VXn = 0.0; //!< Earth-fixed velocity coordinate x of the satellite in PZ-90.02 coordinate system [km/s]
d_VYn = 0.0; //!< Earth-fixed velocity coordinate y of the satellite in PZ-90.02 coordinate system [km/s]
d_VZn = 0.0; //!< Earth-fixed velocity coordinate z of the satellite in PZ-90.02 coordinate system [km/s]
d_AXn = 0.0; //!< Earth-fixed acceleration coordinate x of the satellite in PZ-90.02 coordinate system [km/s^2]
d_AYn = 0.0; //!< Earth-fixed acceleration coordinate y of the satellite in PZ-90.02 coordinate system [km/s^2]
d_AZn = 0.0; //!< Earth-fixed acceleration coordinate z of the satellite in PZ-90.02 coordinate system [km/s^2]
d_B_n = 0.0; //!< Health flag [dimensionless]
d_P = 0.0; //!< Technological parameter of control segment, indication the satellite operation mode in respect of time parameters [dimensionless]
d_N_T = 0.0; //!< Current date, calendar number of day within four-year interval starting from the 1-st of January in a leap year [days]
d_F_T = 0.0; //!< Parameter that provides the predicted satellite user range accuracy at time tb [dimensionless]
d_n = 0.0; //!< Index of the satellite transmitting given navigation signal. It corresponds to a slot number within GLONASS constellation
d_Delta_tau_n = 0.0; //!< Time difference between navigation RF signal transmitted in L2 sub- band and aviation RF signal transmitted in L1 sub-band by nth satellite. [dimensionless]
d_E_n = 0.0; //!< Characterises "age" of a current information [days]
d_P_1 = 0.0; //!< Flag of the immediate data updating [minutes]
d_P_2 = false; //!< Flag of oddness ("1") or evenness ("0") of the value of (tb) [dimensionless]
d_P_3 = false; //!< Flag indicating a number of satellites for which almanac is transmitted within given frame: "1" corresponds to 5 satellites and "0" corresponds to 4 satellites [dimensionless]
d_P_4 = false; //!< Flag to show that ephemeris parameters are present. "1" indicates that updated ephemeris or frequency/time parameters have been uploaded by the control segment [dimensionless]
d_l3rd_n = false; //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
d_l5th_n = false; //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
// Satellite Identification Information
i_satellite_freq_channel = 0; //!< SV Frequency Channel Number
i_satellite_PRN = 0; //!< SV PRN Number, equivalent to slot number for compatibility with GPS
i_satellite_slot_number = 0; //!< SV Slot Number
d_yr = 1972; //!< Current year, defaults to 1972 (UTC Epoch with leap seconds)
d_satClkDrift = 0.0; //!< GLONASS clock error
d_dtr = 0.0; //!< relativistic clock correction term
d_iode = 0.0; //!< Issue of data, ephemeris (Bit 0-6 of tb)
d_tau_c = 0.0;
d_TOW = 0.0; // tow of the start of frame
d_WN = 0.0; // week number of the start of frame
}
boost::posix_time::ptime Glonass_Gnav_Ephemeris::compute_GLONASS_time(const double offset_time) const
{
boost::posix_time::time_duration t(0, 0, offset_time + d_tau_c);
boost::gregorian::date d1(d_yr, 1, 1);
boost::gregorian::days d2(d_N_T);
boost::posix_time::ptime glonass_time(d1+d2, t);
return glonass_time;
}
double Glonass_Gnav_Ephemeris::check_t(double time)
{
double corrTime;
double half_day = 43200.0; // seconds
corrTime = time;
if (time > half_day)
{
corrTime = time - 2.0 * half_day;
}
else if (time < -half_day)
{
corrTime = time + 2.0 * half_day;
}
return corrTime;
}
// FIXME Fix reference here
// 20.3.3.3.3.1 User Algorithm for SV Clock Correction.
double Glonass_Gnav_Ephemeris::sv_clock_drift(double transmitTime, double timeCorrUTC)
{
double dt;
dt = check_t(transmitTime - d_t_b);
d_satClkDrift = -(d_tau_n + timeCorrUTC - d_gamma_n * dt);
//Correct satellite group delay and missing relativistic term here
//d_satClkDrift-=d_TGD;
return d_satClkDrift;
}

View File

@ -0,0 +1,167 @@
/*!
* \file glonass_gnav_ephemeris.h
* \brief Interface of a GLONASS EPHEMERIS storage
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_GNAV_EPHEMERIS_H_
#define GNSS_SDR_GLONASS_GNAV_EPHEMERIS_H_
#include <map>
#include <string>
#include "boost/assign.hpp"
#include <boost/serialization/nvp.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
/*!
* \brief This class is a storage and orbital model functions for the GLONASS SV ephemeris data as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*/
class Glonass_Gnav_Ephemeris
{
private:
/*
* Accounts for the beginning or end of week crossover
*
* See paragraph 20.3.3.3.3.1 (IS-GPS-200E)
* \param[in] - time in seconds
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public:
double d_m; //!< String number within frame [dimensionless]
double d_t_k; //!< GLONASS Time (UTC(SU) + 3 h) referenced to the beginning of the frame within the current day [s]
double d_t_b; //!< Reference ephemeris relative time in GLONASS Time (UTC(SU) + 3 h). Index of a time interval within current day according to UTC(SU) + 03 hours 00 min. [s]
double d_M; //!< Type of satellite transmitting navigation signal [dimensionless]
double d_gamma_n; //!< Relative deviation of predicted carrier frequency value of n- satellite from nominal value at the instant tb [dimensionless]
double d_tau_n; //!< Correction to the nth satellite time (tn) relative to GLONASS time (te),
double d_Xn; //!< Earth-fixed coordinate x of the satellite in PZ-90.02 coordinate system [km].
double d_Yn; //!< Earth-fixed coordinate y of the satellite in PZ-90.02 coordinate system [km]
double d_Zn; //!< Earth-fixed coordinate z of the satellite in PZ-90.02 coordinate system [km]
double d_VXn; //!< Earth-fixed velocity coordinate x of the satellite in PZ-90.02 coordinate system [km/s]
double d_VYn; //!< Earth-fixed velocity coordinate y of the satellite in PZ-90.02 coordinate system [km/s]
double d_VZn; //!< Earth-fixed velocity coordinate z of the satellite in PZ-90.02 coordinate system [km/s]
double d_AXn; //!< Earth-fixed acceleration coordinate x of the satellite in PZ-90.02 coordinate system [km/s^2]
double d_AYn; //!< Earth-fixed acceleration coordinate y of the satellite in PZ-90.02 coordinate system [km/s^2]
double d_AZn; //!< Earth-fixed acceleration coordinate z of the satellite in PZ-90.02 coordinate system [km/s^2]
double d_B_n; //!< Health flag [dimensionless]
double d_P; //!< Technological parameter of control segment, indication the satellite operation mode in respect of time parameters [dimensionless]
double d_N_T; //!< Current date, calendar number of day within four-year interval starting from the 1-st of January in a leap year [days]
double d_F_T; //!< Parameter that provides the predicted satellite user range accuracy at time tb [dimensionless]
double d_n; //!< Index of the satellite transmitting given navigation signal. It corresponds to a slot number within GLONASS constellation
double d_Delta_tau_n; //!< Time difference between navigation RF signal transmitted in L2 sub- band and aviation RF signal transmitted in L1 sub-band by nth satellite. [dimensionless]
double d_E_n; //!< Characterises "age" of a current information [days]
double d_P_1; //!< Flag of the immediate data updating [minutes]
bool d_P_2; //!< Flag of oddness ("1") or evenness ("0") of the value of (tb) [dimensionless]
bool d_P_3; //!< Flag indicating a number of satellites for which almanac is transmitted within given frame: "1" corresponds to 5 satellites and "0" corresponds to 4 satellites [dimensionless]
bool d_P_4; //!< Flag to show that ephemeris parameters are present. "1" indicates that updated ephemeris or frequency/time parameters have been uploaded by the control segment [dimensionless]
bool d_l3rd_n; //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
bool d_l5th_n; //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
// Inmediate deliverables of ephemeris information
// Satellite Identification Information
int i_satellite_freq_channel; //!< SV Frequency Channel Number
unsigned int i_satellite_PRN; //!< SV PRN Number, equivalent to slot number for compatibility with GPS
unsigned int i_satellite_slot_number; //!< SV Slot Number
double d_yr; //!< Current year
double d_satClkDrift; //!< GLONASS clock error
double d_dtr; //!< relativistic clock correction term
double d_iode; //!< Issue of data, ephemeris (Bit 0-6 of tb)
double d_tau_c;
double d_TOW; // tow of the start of frame
double d_WN; // week number of the start of frame
template<class Archive>
/*!
* \brief Serialize is a boost standard method to be called by the boost XML serialization. Here is used to save the ephemeris data on disk file.
*/
void serialize(Archive& archive, const unsigned int version)
{
using boost::serialization::make_nvp;
if(version){};
archive & make_nvp("i_satellite_freq_channel", i_satellite_freq_channel); //!< SV PRN frequency channel number
archive & make_nvp("i_satellite_PRN", i_satellite_PRN);
archive & make_nvp("i_satellite_slot_number", i_satellite_slot_number);
archive & make_nvp("d_m", d_m); //!< String number within frame [dimensionless]
archive & make_nvp("d_t_k", d_t_k); //!< Time referenced to the beginning of the frame within the current day [hours, minutes, seconds]
archive & make_nvp("d_t_b", d_t_b); //!< Index of a time interval within current day according to UTC(SU) + 03 hours 00 min. [minutes]
archive & make_nvp("d_M", d_M); //!< Type of satellite transmitting navigation signal [dimensionless]
archive & make_nvp("d_gamma_n", d_gamma_n); //!< Relative deviation of predicted carrier frequency value of n- satellite from nominal value at the instant tb [dimensionless]
archive & make_nvp("d_tau_n", d_tau_n); //!< Correction to the nth satellite time (tn) relative to GLONASS time (te)
archive & make_nvp("d_Xn", d_Xn); //!< Earth-fixed coordinate x of the satellite in PZ-90.02 coordinate system [km].
archive & make_nvp("d_Yn", d_Yn); //!< Earth-fixed coordinate y of the satellite in PZ-90.02 coordinate system [km]
archive & make_nvp("d_Zn", d_Zn); //!< Earth-fixed coordinate z of the satellite in PZ-90.02 coordinate system [km]
archive & make_nvp("d_VXn", d_VXn); //!< Earth-fixed velocity coordinate x of the satellite in PZ-90.02 coordinate system [km/s]
archive & make_nvp("d_VYn", d_VYn); //!< Earth-fixed velocity coordinate y of the satellite in PZ-90.02 coordinate system [km/s]
archive & make_nvp("d_VZn", d_VZn); //!< Earth-fixed velocity coordinate z of the satellite in PZ-90.02 coordinate system [km/s]
archive & make_nvp("d_AXn", d_AXn); //!< Earth-fixed acceleration coordinate x of the satellite in PZ-90.02 coordinate system [km/s^2]
archive & make_nvp("d_AYn", d_AYn); //!< Earth-fixed acceleration coordinate y of the satellite in PZ-90.02 coordinate system [km/s^2]
archive & make_nvp("d_AZn", d_AZn); //!< Earth-fixed acceleration coordinate z of the satellite in PZ-90.02 coordinate system [km/s^2]
archive & make_nvp("d_B_n", d_B_n); //!< Health flag [dimensionless]
archive & make_nvp("d_P", d_P); //!< Technological parameter of control segment, indication the satellite operation mode in respect of time parameters [dimensionless]
archive & make_nvp("d_N_T", d_N_T); //!< Current date, calendar number of day within four-year interval starting from the 1-st of January in a leap year [days]
archive & make_nvp("d_F_T", d_F_T); //!< Parameter that provides the predicted satellite user range accuracy at time tb [dimensionless]
archive & make_nvp("d_n", d_n); //!< Index of the satellite transmitting given navigation signal. It corresponds to a slot number within GLONASS constellation
archive & make_nvp("d_Delta_tau_n", d_Delta_tau_n);//!< Time difference between navigation RF signal transmitted in L2 sub- band and aviation RF signal transmitted in L1 sub-band by nth satellite. [dimensionless]
archive & make_nvp("d_E_n", d_E_n); //!< Characterises "age" of a current information [days]
archive & make_nvp("d_P_1", d_P_1); //!< Flag of the immediate data updating.
archive & make_nvp("d_P_2", d_P_2); //!< Flag of oddness ("1") or evenness ("0") of the value of (tb) [dimensionless]
archive & make_nvp("d_P_3", d_P_3); //!< Flag indicating a number of satellites for which almanac is transmitted within given frame: "1" corresponds to 5 satellites and "0" corresponds to 4 satellites [dimensionless]
archive & make_nvp("d_P_4", d_P_4); //!< Flag to show that ephemeris parameters are present. "1" indicates that updated ephemeris or frequency/time parameters have been uploaded by the control segment [dimensionless]
archive & make_nvp("d_l3rd_n", d_l3rd_n); //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
archive & make_nvp("d_l5th_n", d_l5th_n); //!< Health flag for nth satellite; ln = 0 indicates the n-th satellite is helthy, ln = 1 indicates malfunction of this nth satellite [dimensionless]
}
/*!
* \brief Sets (\a d_satClkDrift)and returns the clock drift in seconds according to the User Algorithm for SV Clock Correction
* (IS-GPS-200E, 20.3.3.3.3.1)
*/
double sv_clock_drift(double transmitTime, double timeCorrUTC);
/*!
* \brief Computes the GLONASS System Time and returns a boost::posix_time::ptime object
* \ param offset_time Is the start of day offset to compute the time
*/
boost::posix_time::ptime compute_GLONASS_time(const double offset_time) const;
/*!
* Default constructor
*/
Glonass_Gnav_Ephemeris();
};
#endif

View File

@ -0,0 +1,769 @@
/*!
* \file glonass_gnav_navigation_message.cc
* \brief Implementation of a GLONASS GNAV Data message decoder as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_gnav_navigation_message.h"
#include <boost/crc.hpp>
#include <boost/dynamic_bitset.hpp>
#include <cmath>
#include <iostream>
#include <sstream>
#include <gnss_satellite.h>
#include <glog/logging.h>
void Glonass_Gnav_Navigation_Message::reset()
{
//!< Satellite Identification
i_channel_ID = 0; //!< Channel ID assigned by the receiver
i_satellite_freq_channel = 0; //!< SV Frequency Slot Number
i_satellite_slot_number = 0; //!< SV Orbit Slot Number
//!< Ephmeris Flags
flag_all_ephemeris = false;
flag_ephemeris_str_1 = false;
flag_ephemeris_str_2 = false;
flag_ephemeris_str_3 = false;
flag_ephemeris_str_4 = false;
//!< Almanac Flags
flag_all_almanac = false;
flag_almanac_str_6 = false;
flag_almanac_str_7 = false;
flag_almanac_str_8 = false;
flag_almanac_str_9 = false;
flag_almanac_str_10 = false;
flag_almanac_str_11 = false;
flag_almanac_str_12 = false;
flag_almanac_str_13 = false;
flag_almanac_str_14 = false;
flag_almanac_str_15 = false;
//!< UTC and System Clocks Flags
flag_utc_model_valid = false; //!< If set, it indicates that the UTC model parameters are filled
flag_utc_model_str_5 = false; //!< Clock info send in string 5 of navigation data
flag_utc_model_str_15 = false; //!< Clock info send in string 15 of frame 5 of navigation data
//broadcast orbit 1
flag_TOW_set = false;
d_TOW = 0.0; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
d_TOW_F1 = 0.0; //!< Time of GPS Week from HOW word of Subframe 1 [s]
d_TOW_F2 = 0.0; //!< Time of GPS Week from HOW word of Subframe 2 [s]
d_TOW_F3 = 0.0; //!< Time of GPS Week from HOW word of Subframe 3 [s]
d_TOW_F4 = 0.0; //!< Time of GPS Week from HOW word of Subframe 4 [s]
d_TOW_F5 = 0.0; //!< Time of GPS Week from HOW word of Subframe 5 [s]
flag_CRC_test = false;
d_frame_ID = 0;
d_string_ID = 0;
// Clock terms
d_satClkCorr = 0.0;
d_dtr = 0.0;
d_satClkDrift = 0.0;
std::map<int,std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
auto gnss_sat = Gnss_Satellite();
std::string _system ("GLONASS");
//TODO SHould number of channels be hardcoded?
for(unsigned int i = 1; i < 14; i++)
{
satelliteBlock[i] = gnss_sat.what_block(_system, i);
}
}
Glonass_Gnav_Navigation_Message::Glonass_Gnav_Navigation_Message()
{
reset();
}
bool Glonass_Gnav_Navigation_Message::CRC_test(std::bitset<GLONASS_GNAV_STRING_BITS> bits)
{
int sum_bits = 0;
int sum_hamming = 0;
int C1 = 0;
int C2 = 0;
int C3 = 0;
int C4 = 0;
int C5 = 0;
int C6 = 0;
int C7 = 0;
int C_Sigma = 0;
std::vector<int> string_bits(GLONASS_GNAV_STRING_BITS);
//!< Populate data and hamming code vectors
for(int i = 0; i < static_cast<int>(GLONASS_GNAV_STRING_BITS); i++)
{
string_bits[i] = static_cast<int>(bits[i]);
}
//!< Compute C1 term
sum_bits = 0;
for(int i = 0; i < static_cast<int>(GLONASS_GNAV_CRC_I_INDEX.size()); i++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_I_INDEX[i]];
}
C1 = string_bits[0]^(sum_bits%2);
//!< Compute C2 term
sum_bits = 0;
for(int j = 0; j < static_cast<int>(GLONASS_GNAV_CRC_J_INDEX.size()); j++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_J_INDEX[j]];
}
C2 = (string_bits[1])^(sum_bits%2);
//!< Compute C3 term
sum_bits = 0;
for(int k = 0; k < static_cast<int>(GLONASS_GNAV_CRC_K_INDEX.size()); k++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_K_INDEX[k]];
}
C3 = string_bits[2]^(sum_bits%2);
//!< Compute C4 term
sum_bits = 0;
for(int l = 0; l < static_cast<int>(GLONASS_GNAV_CRC_L_INDEX.size()); l++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_L_INDEX[l]];
}
C4 = string_bits[3]^(sum_bits%2);
//!< Compute C5 term
sum_bits = 0;
for(int m = 0; m < static_cast<int>(GLONASS_GNAV_CRC_M_INDEX.size()); m++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_M_INDEX[m]];
}
C5 = string_bits[4]^(sum_bits%2);
//!< Compute C6 term
sum_bits = 0;
for(int n = 0; n < static_cast<int>(GLONASS_GNAV_CRC_N_INDEX.size()); n++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_N_INDEX[n]];
}
C6 = string_bits[5]^(sum_bits%2);
//!< Compute C7 term
sum_bits = 0;
for(int p = 0; p < static_cast<int>(GLONASS_GNAV_CRC_P_INDEX.size()); p++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_P_INDEX[p]];
}
C7 = string_bits[6]^(sum_bits%2);
//!< Compute C_Sigma term
sum_bits = 0;
sum_hamming = 0;
for(int q = 0; q < static_cast<int>(GLONASS_GNAV_CRC_Q_INDEX.size()); q++)
{
sum_bits += string_bits[GLONASS_GNAV_CRC_Q_INDEX[q]];
}
for(int q = 0; q < 8; q++)
{
sum_hamming += string_bits[q];
}
C_Sigma = (sum_hamming%2)^(sum_bits%2);
//!< Verification of the data
// All of the checksums are equal to zero
if((C1 & C2 & C3 & C4 & C5 & C6 & C7 & C_Sigma) == 0 )
{
return true;
}
// only one of the checksums (C1,...,C7) is equal to zero but C_Sigma = 1
else if(C_Sigma == 1 && C1+C2+C3+C4+C5+C6+C7 == 6)
{
return true;
}
else
{
return false;
}
}
bool Glonass_Gnav_Navigation_Message::read_navigation_bool(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter)
{
bool value;
if (bits[GLONASS_GNAV_STRING_BITS - parameter[0].first] == 1)
{
value = true;
}
else
{
value = false;
}
return value;
}
unsigned long int Glonass_Gnav_Navigation_Message::read_navigation_unsigned(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter)
{
unsigned long int value = 0;
int num_of_slices = parameter.size();
for (int i = 0; i < num_of_slices; i++)
{
for (int j = 0; j < parameter[i].second; j++)
{
value <<= 1; //shift left
if (bits[GLONASS_GNAV_STRING_BITS - parameter[i].first - j] == 1)
{
value += 1; // insert the bit
}
}
}
return value;
}
signed long int Glonass_Gnav_Navigation_Message::read_navigation_signed(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter)
{
signed long int value = 0;
signed long int sign = 0;
int num_of_slices = parameter.size();
// read the MSB and perform the sign extension
if (bits[GLONASS_GNAV_STRING_BITS - parameter[0].first] == 1)
{
sign = -1;
}
else
{
sign = 1;
}
for (int i = 0; i < num_of_slices; i++)
{
for (int j = 1; j < parameter[i].second; j++)
{
value <<= 1; //shift left
if (bits[GLONASS_GNAV_STRING_BITS - parameter[i].first - j] == 1)
{
value += 1; // insert the bit
}
}
}
return (sign*value);
}
unsigned int Glonass_Gnav_Navigation_Message::get_frame_number(unsigned int satellite_slot_number)
{
unsigned int frame_ID = 0;
if(satellite_slot_number >= 1 and satellite_slot_number <= 5 )
{
frame_ID = 1;
}
else if(satellite_slot_number >= 6 and satellite_slot_number <= 10 )
{
frame_ID = 2;
}
else if(satellite_slot_number >= 11 and satellite_slot_number <= 15 )
{
frame_ID = 3;
}
else if(satellite_slot_number >= 16 and satellite_slot_number <= 20 )
{
frame_ID = 4;
}
else if(satellite_slot_number >= 21 and satellite_slot_number <= 24 )
{
frame_ID = 5;
}
else
{
//TODO Find print statement and make it an error
frame_ID = 0;
}
return frame_ID;
}
double Glonass_Gnav_Navigation_Message::get_TOW()
{
double TOW = 0.0;
double utcsu2utc = 3*3600;
double glot2utcsu = 3*3600;
int i = 0;
TOW = gnav_ephemeris.d_t_k + glot2utcsu + utcsu2utc + gnav_utc_model.d_tau_c + gnav_utc_model.d_tau_gps;
for (i = 0; GLONASS_LEAP_SECONDS[i][0]>0; i++)
{
if (GLONASS_LEAP_SECONDS[i][0] == gnav_ephemeris.d_yr)
{
TOW -= GLONASS_LEAP_SECONDS[i][6];
}
}
return TOW;
}
int Glonass_Gnav_Navigation_Message::string_decoder(std::string frame_string)
{
int J = 0;
d_string_ID = 0;
d_frame_ID = 0;
// UNPACK BYTES TO BITS AND REMOVE THE CRC REDUNDANCE
std::bitset<GLONASS_GNAV_STRING_BITS> string_bits = std::bitset<GLONASS_GNAV_STRING_BITS>((frame_string));
d_string_ID = static_cast<unsigned int>(read_navigation_unsigned(string_bits, STRING_ID));
flag_CRC_test = CRC_test(string_bits);
// Decode all 15 string messages
switch (d_string_ID)
{
case 1:
//--- It is string 1 -----------------------------------------------
gnav_ephemeris.d_P_1 = (static_cast<double>(read_navigation_unsigned(string_bits, P1)) + 1)*15;
gnav_ephemeris.d_t_k = static_cast<double>(read_navigation_unsigned(string_bits, T_K_HR)) * 3600 +
static_cast<double>(read_navigation_unsigned(string_bits, T_K_MIN)) * 60 +
static_cast<double>(read_navigation_unsigned(string_bits, T_K_SEC)) * 30;
gnav_ephemeris.d_VXn = static_cast<double>(read_navigation_signed(string_bits, X_N_DOT)) * TWO_N20;
gnav_ephemeris.d_AXn = static_cast<double>(read_navigation_signed(string_bits, X_N_DOT_DOT)) * TWO_N30;
gnav_ephemeris.d_Xn = static_cast<double>(read_navigation_signed(string_bits, X_N)) * TWO_N11;
flag_ephemeris_str_1 = true;
break;
case 2:
//--- It is string 2 -----------------------------------------------
if (flag_ephemeris_str_1 == true)
{
gnav_ephemeris.d_B_n = static_cast<double>(read_navigation_unsigned(string_bits, B_N));
gnav_ephemeris.d_P_2 = static_cast<bool>(read_navigation_bool(string_bits, P2));
gnav_ephemeris.d_t_b = static_cast<double>(read_navigation_unsigned(string_bits, T_B))*gnav_ephemeris.d_P_1*60;
gnav_ephemeris.d_VYn = static_cast<double>(read_navigation_signed(string_bits, Y_N_DOT))* TWO_N20;
gnav_ephemeris.d_AYn = static_cast<double>(read_navigation_signed(string_bits, Y_N_DOT_DOT)) * TWO_N30;
gnav_ephemeris.d_Yn = static_cast<double>(read_navigation_signed(string_bits, Y_N)) * TWO_N11;
gnav_ephemeris.d_iode = read_navigation_unsigned(string_bits, T_B);
flag_ephemeris_str_2 = true;
}
break;
case 3:
// --- It is string 3 ----------------------------------------------
gnav_ephemeris.d_P_3 = static_cast<bool>(read_navigation_bool(string_bits, P3));
gnav_ephemeris.d_gamma_n = static_cast<double>(read_navigation_signed(string_bits, GAMMA_N)) * TWO_N40;
gnav_ephemeris.d_P = static_cast<double>(read_navigation_unsigned(string_bits, P));
gnav_ephemeris.d_l3rd_n = static_cast<bool>(read_navigation_bool(string_bits, EPH_L_N));
gnav_ephemeris.d_VZn = static_cast<double>(read_navigation_signed(string_bits, Z_N_DOT)) * TWO_N20;
gnav_ephemeris.d_AZn = static_cast<double>(read_navigation_signed(string_bits, Z_N_DOT_DOT)) * TWO_N30;
gnav_ephemeris.d_Zn = static_cast<double>(read_navigation_signed(string_bits, Z_N)) * TWO_N11;
flag_ephemeris_str_3 = true;
break;
case 4:
// --- It is string 4 ----------------------------------------------
gnav_ephemeris.d_tau_n = static_cast<double>(read_navigation_signed(string_bits, TAU_N)) * TWO_N30;
gnav_ephemeris.d_Delta_tau_n = static_cast<double>(read_navigation_signed(string_bits, DELTA_TAU_N)) * TWO_N30;
gnav_ephemeris.d_E_n = static_cast<double>(read_navigation_unsigned(string_bits, E_N));
gnav_ephemeris.d_P_4 = static_cast<bool>(read_navigation_bool(string_bits, P4));
gnav_ephemeris.d_F_T = static_cast<double>(read_navigation_unsigned(string_bits, F_T));
gnav_ephemeris.d_N_T = static_cast<double>(read_navigation_unsigned(string_bits, N_T));
gnav_ephemeris.d_n = static_cast<double>(read_navigation_unsigned(string_bits, N));
gnav_ephemeris.d_M = static_cast<double>(read_navigation_unsigned(string_bits, M));
// Fill in ephemeris deliverables in the code
gnav_ephemeris.i_satellite_slot_number = gnav_ephemeris.d_n;
gnav_ephemeris.i_satellite_PRN = gnav_ephemeris.d_n;
flag_ephemeris_str_4 = true;
break;
case 5:
// --- It is string 5 ----------------------------------------------
gnav_utc_model.d_N_A = static_cast<double>(read_navigation_unsigned(string_bits, N_A));
gnav_utc_model.d_tau_c = static_cast<double>(read_navigation_signed(string_bits, TAU_C)) * TWO_N31;
gnav_utc_model.d_N_4 = static_cast<double>(read_navigation_unsigned(string_bits, N_4));
gnav_utc_model.d_tau_gps = static_cast<double>(read_navigation_signed(string_bits, TAU_GPS)) * TWO_N30;
gnav_ephemeris.d_l5th_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
flag_utc_model_str_5 = true;
// Compute Year and DoY based on Algorithm A3.11 of GLONASS ICD
if(flag_ephemeris_str_4 == true)
{
//Current year number J in the four-year interval is calculated:
if(gnav_ephemeris.d_N_T >= 1 && gnav_ephemeris.d_N_T <= 366)
{
J = 1;
}
else if ( gnav_ephemeris.d_N_T >= 367 && gnav_ephemeris.d_N_T <= 731)
{
J = 2;
}
else if (gnav_ephemeris.d_N_T >= 732 && gnav_ephemeris.d_N_T <= 1096)
{
J = 3;
}
else if (gnav_ephemeris.d_N_T >= 1097 && gnav_ephemeris.d_N_T <= 1461)
{
J = 4;
}
// 2). Current year in common form is calculated by the following formula:
gnav_ephemeris.d_yr = 1996 + 4.0*(gnav_utc_model.d_N_4 - 1.0) + (J - 1.0);
gnav_ephemeris.d_tau_c = gnav_utc_model.d_tau_c;
// 3). Set TOW once the year has been defined, it helps with leap second determination
if(flag_ephemeris_str_1 == true)
{
d_TOW = get_TOW();
flag_TOW_set = true;
}
}
break;
case 6:
// --- It is string 6 ----------------------------------------------
i_satellite_slot_number = static_cast<unsigned int>(read_navigation_unsigned(string_bits, n_A));
d_frame_ID = get_frame_number(i_satellite_slot_number);
gnav_almanac[i_satellite_slot_number - 1].d_C_n = static_cast<bool>(read_navigation_bool(string_bits, C_N));
gnav_almanac[i_satellite_slot_number - 1].d_M_n_A = static_cast<double>(read_navigation_unsigned(string_bits, M_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_n_A = static_cast<double>(read_navigation_unsigned(string_bits, n_A));
gnav_almanac[i_satellite_slot_number - 1].d_tau_n_A = static_cast<double>(read_navigation_unsigned(string_bits, TAU_N_A)) * TWO_N18;
gnav_almanac[i_satellite_slot_number - 1].d_lambda_n_A = static_cast<double>(read_navigation_signed(string_bits, LAMBDA_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_i_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_I_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_epsilon_n_A = static_cast<double>(read_navigation_unsigned(string_bits, EPSILON_N_A)) * TWO_N20;
flag_almanac_str_6 = true;
break;
case 7:
// --- It is string 7 ----------------------------------------------
if (flag_almanac_str_6 == true)
{
gnav_almanac[i_satellite_slot_number - 1].d_omega_n_A = static_cast<double>(read_navigation_signed(string_bits, OMEGA_N_A)) * TWO_N15;
gnav_almanac[i_satellite_slot_number - 1].d_t_lambda_n_A = static_cast<double>(read_navigation_unsigned(string_bits, T_LAMBDA_N_A)) * TWO_N5;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_N_A)) * TWO_N9;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A_dot = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_DOT_N_A)) * TWO_N14;
gnav_almanac[i_satellite_slot_number - 1].d_H_n_A = static_cast<double>(read_navigation_unsigned(string_bits, H_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_l_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
// Set satellite information for redundancy purposes
if(gnav_almanac[i_satellite_slot_number - 1].d_H_n_A > 24)
{
gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].d_H_n_A - 32.0;
}
gnav_almanac[i_satellite_slot_number - 1].i_satellite_slot_number = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
gnav_almanac[i_satellite_slot_number - 1].i_satellite_PRN = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
if(i_satellite_slot_number == gnav_ephemeris.i_satellite_slot_number)
{
gnav_ephemeris.i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel;
}
flag_almanac_str_7 = true;
}
break;
case 8:
// --- It is string 8 ----------------------------------------------
i_satellite_slot_number = static_cast<unsigned int>(read_navigation_unsigned(string_bits, n_A));
d_frame_ID = get_frame_number(i_satellite_slot_number);
gnav_almanac[i_satellite_slot_number - 1].d_C_n = static_cast<bool>(read_navigation_bool(string_bits, C_N));
gnav_almanac[i_satellite_slot_number - 1].d_M_n_A = static_cast<double>(read_navigation_unsigned(string_bits, M_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_n_A = static_cast<double>(read_navigation_unsigned(string_bits, n_A));
gnav_almanac[i_satellite_slot_number - 1].d_tau_n_A = static_cast<double>(read_navigation_unsigned(string_bits, TAU_N_A)) * TWO_N18;
gnav_almanac[i_satellite_slot_number - 1].d_lambda_n_A = static_cast<double>(read_navigation_signed(string_bits, LAMBDA_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_i_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_I_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_epsilon_n_A = static_cast<double>(read_navigation_unsigned(string_bits, EPSILON_N_A)) * TWO_N20;
flag_almanac_str_8 = true;
break;
case 9:
// --- It is string 9 ----------------------------------------------
if (flag_almanac_str_8 == true)
{
// TODO signed vs unsigned reading from datasheet
gnav_almanac[i_satellite_slot_number - 1].d_omega_n_A = static_cast<double>(read_navigation_signed(string_bits, OMEGA_N_A)) * TWO_N15;
gnav_almanac[i_satellite_slot_number - 1].d_t_lambda_n_A = static_cast<double>(read_navigation_unsigned(string_bits, T_LAMBDA_N_A)) * TWO_N5;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_N_A)) * TWO_N9;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A_dot = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_DOT_N_A)) * TWO_N14;
gnav_almanac[i_satellite_slot_number - 1].d_H_n_A = static_cast<double>(read_navigation_unsigned(string_bits, H_N_A)) -32.0;
gnav_almanac[i_satellite_slot_number - 1].d_l_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
// Set satellite information for redundancy purposes
if(gnav_almanac[i_satellite_slot_number - 1].d_H_n_A > 24)
{
gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].d_H_n_A - 32.0;
}
gnav_almanac[i_satellite_slot_number - 1].i_satellite_slot_number = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
gnav_almanac[i_satellite_slot_number - 1].i_satellite_PRN = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
flag_almanac_str_9 = true;
}
break;
case 10:
// --- It is string 10 ---------------------------------------------
i_satellite_slot_number = static_cast<unsigned int>(read_navigation_unsigned(string_bits, n_A));
d_frame_ID = get_frame_number(i_satellite_slot_number);
gnav_almanac[i_satellite_slot_number - 1].d_C_n = static_cast<bool>(read_navigation_bool(string_bits, C_N));
gnav_almanac[i_satellite_slot_number - 1].d_M_n_A = static_cast<double>(read_navigation_unsigned(string_bits, M_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_n_A = static_cast<double>(read_navigation_unsigned(string_bits, n_A));
gnav_almanac[i_satellite_slot_number - 1].d_tau_n_A = static_cast<double>(read_navigation_unsigned(string_bits, TAU_N_A)) * TWO_N18;
gnav_almanac[i_satellite_slot_number - 1].d_lambda_n_A = static_cast<double>(read_navigation_signed(string_bits, LAMBDA_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_i_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_I_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_epsilon_n_A = static_cast<double>(read_navigation_unsigned(string_bits, EPSILON_N_A)) * TWO_N20;
flag_almanac_str_10 = true;
break;
case 11:
// --- It is string 11 ---------------------------------------------
if (flag_almanac_str_10 == true)
{
gnav_almanac[i_satellite_slot_number - 1].d_omega_n_A = static_cast<double>(read_navigation_signed(string_bits, OMEGA_N_A)) * TWO_N15;
gnav_almanac[i_satellite_slot_number - 1].d_t_lambda_n_A = static_cast<double>(read_navigation_unsigned(string_bits, T_LAMBDA_N_A)) * TWO_N5;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_N_A)) * TWO_N9;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A_dot = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_DOT_N_A)) * TWO_N14;
gnav_almanac[i_satellite_slot_number - 1].d_H_n_A = static_cast<double>(read_navigation_unsigned(string_bits, H_N_A)) - 32.0;
gnav_almanac[i_satellite_slot_number - 1].d_l_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
// Set satellite information for redundancy purposes
if(gnav_almanac[i_satellite_slot_number - 1].d_H_n_A > 24)
{
gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].d_H_n_A - 32.0;
}
gnav_almanac[i_satellite_slot_number - 1].i_satellite_slot_number = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
gnav_almanac[i_satellite_slot_number - 1].i_satellite_PRN = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
flag_almanac_str_11 = true;
}
break;
case 12:
// --- It is string 12 ---------------------------------------------
i_satellite_slot_number = static_cast<unsigned int>(read_navigation_unsigned(string_bits, n_A));
d_frame_ID = get_frame_number(i_satellite_slot_number);
gnav_almanac[i_satellite_slot_number - 1].d_C_n = static_cast<bool>(read_navigation_bool(string_bits, C_N));
gnav_almanac[i_satellite_slot_number - 1].d_M_n_A = static_cast<double>(read_navigation_unsigned(string_bits, M_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_n_A = static_cast<double>(read_navigation_unsigned(string_bits, n_A));
gnav_almanac[i_satellite_slot_number - 1].d_tau_n_A = static_cast<double>(read_navigation_unsigned(string_bits, TAU_N_A)) * TWO_N18;
gnav_almanac[i_satellite_slot_number - 1].d_lambda_n_A = static_cast<double>(read_navigation_signed(string_bits, LAMBDA_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_i_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_I_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_epsilon_n_A = static_cast<double>(read_navigation_unsigned(string_bits, EPSILON_N_A)) * TWO_N20;
flag_almanac_str_12 = true;
break;
case 13:
// --- It is string 13 ---------------------------------------------
if (flag_almanac_str_12 == true)
{
gnav_almanac[i_satellite_slot_number - 1].d_omega_n_A = static_cast<double>(read_navigation_signed(string_bits, OMEGA_N_A)) * TWO_N15;
gnav_almanac[i_satellite_slot_number - 1].d_t_lambda_n_A = static_cast<double>(read_navigation_unsigned(string_bits, T_LAMBDA_N_A)) * TWO_N5;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_N_A)) * TWO_N9;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A_dot = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_DOT_N_A)) * TWO_N14;
gnav_almanac[i_satellite_slot_number - 1].d_H_n_A = static_cast<double>(read_navigation_unsigned(string_bits, H_N_A)) - 32.0;
gnav_almanac[i_satellite_slot_number - 1].d_l_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
// Set satellite information for redundancy purposes
if(gnav_almanac[i_satellite_slot_number - 1].d_H_n_A > 24)
{
gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].d_H_n_A - 32.0;
}
gnav_almanac[i_satellite_slot_number - 1].i_satellite_slot_number = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
gnav_almanac[i_satellite_slot_number - 1].i_satellite_PRN = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
flag_almanac_str_13 = true;
}
break;
case 14:
// --- It is string 14 ---------------------------------------------
if( d_frame_ID == 5)
{
gnav_utc_model.d_B1 = static_cast<double>(read_navigation_unsigned(string_bits, B1));
gnav_utc_model.d_B2 = static_cast<double>(read_navigation_unsigned(string_bits, B2));
}
else
{
i_satellite_slot_number = static_cast<unsigned int>(read_navigation_unsigned(string_bits, n_A));
d_frame_ID = get_frame_number(i_satellite_slot_number);
gnav_almanac[i_satellite_slot_number - 1].d_C_n = static_cast<bool>(read_navigation_bool(string_bits, C_N));
gnav_almanac[i_satellite_slot_number - 1].d_M_n_A = static_cast<double>(read_navigation_unsigned(string_bits, M_N_A));
gnav_almanac[i_satellite_slot_number - 1].d_n_A = static_cast<double>(read_navigation_unsigned(string_bits, n_A));
gnav_almanac[i_satellite_slot_number - 1].d_tau_n_A = static_cast<double>(read_navigation_unsigned(string_bits, TAU_N_A)) * TWO_N18;
gnav_almanac[i_satellite_slot_number - 1].d_lambda_n_A = static_cast<double>(read_navigation_signed(string_bits, LAMBDA_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_i_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_I_N_A)) * TWO_N20;
gnav_almanac[i_satellite_slot_number - 1].d_epsilon_n_A = static_cast<double>(read_navigation_unsigned(string_bits, EPSILON_N_A)) * TWO_N20;
flag_almanac_str_14 = true;
}
break;
case 15:
// --- It is string 9 ----------------------------------------------
if (d_frame_ID != 5 and flag_almanac_str_14 == true )
{
gnav_almanac[i_satellite_slot_number - 1].d_omega_n_A = static_cast<double>(read_navigation_signed(string_bits, OMEGA_N_A)) * TWO_N15;
gnav_almanac[i_satellite_slot_number - 1].d_t_lambda_n_A = static_cast<double>(read_navigation_unsigned(string_bits, T_LAMBDA_N_A)) * TWO_N5;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_N_A)) * TWO_N9;
gnav_almanac[i_satellite_slot_number - 1].d_Delta_T_n_A_dot = static_cast<double>(read_navigation_signed(string_bits, DELTA_T_DOT_N_A)) * TWO_N14;
gnav_almanac[i_satellite_slot_number - 1].d_H_n_A = static_cast<double>(read_navigation_unsigned(string_bits, H_N_A)) - 32.0;
gnav_almanac[i_satellite_slot_number - 1].d_l_n = static_cast<bool>(read_navigation_bool(string_bits, ALM_L_N));
// Set satellite information for redundancy purposes
if(gnav_almanac[i_satellite_slot_number - 1].d_H_n_A > 24)
{
gnav_almanac[i_satellite_slot_number - 1].i_satellite_freq_channel = gnav_almanac[i_satellite_slot_number - 1].d_H_n_A - 32.0;
}
gnav_almanac[i_satellite_slot_number - 1].i_satellite_slot_number = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
gnav_almanac[i_satellite_slot_number - 1].i_satellite_PRN = gnav_almanac[i_satellite_slot_number - 1].d_n_A;
flag_almanac_str_15 = true;
}
break;
default:
LOG(INFO) << "GLONASS GNAV: Invalid String ID of received. Received " << d_string_ID << ", but acceptable range is from 1-15";
break;
} // switch string ID ...
return d_string_ID;
}
double Glonass_Gnav_Navigation_Message::utc_time(const double glonass_time_corrected) const
{
double t_utc;
t_utc = glonass_time_corrected + 3*3600 + gnav_utc_model.d_tau_c;
return t_utc;
}
Glonass_Gnav_Ephemeris Glonass_Gnav_Navigation_Message::get_ephemeris()
{
return gnav_ephemeris;
}
Glonass_Gnav_Utc_Model Glonass_Gnav_Navigation_Message::get_utc_model()
{
return gnav_utc_model;
}
Glonass_Gnav_Almanac Glonass_Gnav_Navigation_Message::get_almanac(unsigned int satellite_slot_number)
{
return gnav_almanac[satellite_slot_number - 1];
}
bool Glonass_Gnav_Navigation_Message::have_new_ephemeris() //Check if we have a new ephemeris stored in the galileo navigation class
{
if ((flag_ephemeris_str_1 == true) and (flag_ephemeris_str_2 == true) and (flag_ephemeris_str_3 == true) and (flag_ephemeris_str_4 == true))
{
if ((gnav_ephemeris.d_P_4 == 1) )
{
flag_ephemeris_str_1 = false;// clear the flag
flag_ephemeris_str_2 = false;// clear the flag
flag_ephemeris_str_3 = false;// clear the flag
flag_ephemeris_str_4 = false;// clear the flag
flag_all_ephemeris = true;
DLOG(INFO) << "Ephemeris (1, 2, 3, 4) have been received and belong to the same batch" << std::endl;
return true;
}
else
{
return false;
}
}
else
return false;
}
bool Glonass_Gnav_Navigation_Message::have_new_utc_model() // Check if we have a new utc data set stored in the galileo navigation class
{
if (flag_utc_model_valid == true)
{
flag_utc_model_valid = false; // clear the flag
return true;
}
else
return false;
}
bool Glonass_Gnav_Navigation_Message::have_new_almanac() //Check if we have a new almanac data set stored in the galileo navigation class
{
if ((flag_almanac_str_6 == true) and (flag_almanac_str_7 == true) and
(flag_almanac_str_8 == true) and (flag_almanac_str_9 == true) and
(flag_almanac_str_10 == true) and (flag_almanac_str_11 == true) and
(flag_almanac_str_12 == true) and (flag_almanac_str_13 == true) and
(flag_almanac_str_14 == true) and (flag_almanac_str_15 == true))
{
//All almanac have been received
flag_almanac_str_6 = false;
flag_almanac_str_7 = false;
flag_almanac_str_8 = false;
flag_almanac_str_9 = false;
flag_almanac_str_10 = false;
flag_almanac_str_11 = false;
flag_almanac_str_12 = false;
flag_almanac_str_13 = false;
flag_almanac_str_14 = false;
flag_almanac_str_15 = false;
flag_all_almanac = true;
return true;
}
else
return false;
}

View File

@ -0,0 +1,176 @@
/*!
* \file glonass_gnav_navigation_message.h
* \brief Interface of a GLONASS GNAV Data message decoder as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_GNAV_NAVIGATION_MESSAGE_H_
#define GNSS_SDR_GLONASS_GNAV_NAVIGATION_MESSAGE_H_
#include <bitset>
#include <map>
#include <string>
#include <utility>
#include <vector>
#include "GLONASS_L1_CA.h"
#include "glonass_gnav_ephemeris.h"
#include "glonass_gnav_almanac.h"
#include "glonass_gnav_utc_model.h"
/*!
* \brief This class decodes a GLONASS GNAV Data message as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*/
class Glonass_Gnav_Navigation_Message
{
private:
unsigned long int read_navigation_unsigned(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter);
signed long int read_navigation_signed(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter);
bool read_navigation_bool(std::bitset<GLONASS_GNAV_STRING_BITS> bits, const std::vector<std::pair<int,int>> parameter);
public:
bool flag_CRC_test;
unsigned int d_frame_ID;
unsigned int d_string_ID;
Glonass_Gnav_Ephemeris gnav_ephemeris; //!< Ephemeris information decoded
Glonass_Gnav_Utc_Model gnav_utc_model; //!< UTC model information
Glonass_Gnav_Almanac gnav_almanac[24]; //!< Almanac information for all 24 satellites
//!< Satellite Identification
int i_channel_ID; //!< Channel ID assigned by the receiver
unsigned int i_satellite_freq_channel; //!< SV Frequency Slot Number
unsigned int i_satellite_slot_number; //!< SV Orbit Slot Number
//!< Ephmeris Flags
bool flag_all_ephemeris; //!< Flag indicating that all strings containing ephemeris have been received
bool flag_ephemeris_str_1; //!< Flag indicating that ephemeris 1/4 (string 1) have been received
bool flag_ephemeris_str_2; //!< Flag indicating that ephemeris 2/4 (string 2) have been received
bool flag_ephemeris_str_3; //!< Flag indicating that ephemeris 3/4 (string 3) have been received
bool flag_ephemeris_str_4; //!< Flag indicating that ephemeris 4/4 (string 4) have been received
//!< Almanac Flags
bool flag_all_almanac; //!< Flag indicating that all almanac have been received
bool flag_almanac_str_6; //!< Flag indicating that almanac of string 6 have been received
bool flag_almanac_str_7; //!< Flag indicating that almanac of string 7 have been received
bool flag_almanac_str_8; //!< Flag indicating that almanac of string 8 have been received
bool flag_almanac_str_9; //!< Flag indicating that almanac of string 9 have been received
bool flag_almanac_str_10; //!< Flag indicating that almanac of string 10 have been received
bool flag_almanac_str_11; //!< Flag indicating that almanac of string 11 have been received
bool flag_almanac_str_12; //!< Flag indicating that almanac of string 12 have been received
bool flag_almanac_str_13; //!< Flag indicating that almanac of string 13 have been received
bool flag_almanac_str_14; //!< Flag indicating that almanac of string 14 have been received
bool flag_almanac_str_15; //!< Flag indicating that almanac of string 15 have been received
//!< UTC and System Clocks Flags
bool flag_utc_model_valid; //!< If set, it indicates that the UTC model parameters are filled
bool flag_utc_model_str_5; //!< Clock info send in string 5 of navigation data
bool flag_utc_model_str_15; //!< Clock info send in string 15 of frame 5 of navigation data
bool flag_TOW_set;
double d_TOW; //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
double d_TOW_F1; //!< Time of GPS Week from HOW word of Subframe 1 [s]
double d_TOW_F2; //!< Time of GPS Week from HOW word of Subframe 2 [s]
double d_TOW_F3; //!< Time of GPS Week from HOW word of Subframe 3 [s]
double d_TOW_F4; //!< Time of GPS Week from HOW word of Subframe 4 [s]
double d_TOW_F5; //!< Time of GPS Week from HOW word of Subframe 5 [s]
// Clock terms
double d_satClkCorr; // Satellite clock error
double d_dtr; // Relativistic clock correction term
double d_satClkDrift; // Satellite clock drift
bool CRC_test(std::bitset<GLONASS_GNAV_STRING_BITS> bits);
unsigned int get_frame_number(unsigned int satellite_slot_number);
/*!
* \brief Reset GLONASS GNAV Navigation Information
*/
void reset();
/*!
* \brief Obtain a GLONASS GNAV SV Ephemeris class filled with current SV data
*/
Glonass_Gnav_Ephemeris get_ephemeris();
/*!
* \brief Obtain a GLONASS GNAV UTC model parameters class filled with current SV data
*/
Glonass_Gnav_Utc_Model get_utc_model();
/*
* \brief Returns a Galileo_Almanac object filled with the latest navigation data received
*/
Glonass_Gnav_Almanac get_almanac(unsigned int satellite_slot_number);
/*
* \brief Returns true if new Ephemeris has arrived. The flag is set to false when the function is executed
*/
bool have_new_ephemeris();
/*
* \brief Returns true if new UTC model has arrived. The flag is set to false when the function is executed
*/
bool have_new_utc_model();
/*
* \brief Returns true if new UTC model has arrived. The flag is set to false when the function is executed
*/
bool have_new_almanac();
/*!
* \brief Decodes the GLONASS GNAV string
*/
int string_decoder(std::string frame_string);
/*!
* \brief Gets the time of week in GPS Time
* \details This converts from GLONASS Time to GPS Time of Week based on the
* start of frame
*/
double get_TOW();
/*!
* \brief Computes the Coordinated Universal Time (UTC) and returns it in [s]
*/
double utc_time(const double glonasstime_corrected) const;
/*!
* Default constructor
*/
Glonass_Gnav_Navigation_Message();
};
#endif

View File

@ -0,0 +1,55 @@
/*
* \file glonass_gnav_utc_model.h
* \brief Interface of a GLONASS GNAV UTC MODEL storage
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "glonass_gnav_utc_model.h"
#include <cmath>
Glonass_Gnav_Utc_Model::Glonass_Gnav_Utc_Model()
{
valid = false;
d_tau_c = 0.0;
d_tau_gps = 0.0;
d_N_4 = 0.0;
d_N_A = 0.0;
d_B1 = 0.0;
d_B2 = 0.0;
}
double Glonass_Gnav_Utc_Model::utc_time(double glonass_time_corrected)
{
double t_utc;
// GLONASS Time is relative to UTC Moscow, so we simply add its time difference
t_utc = glonass_time_corrected + 3*3600 + d_tau_c;
return t_utc;
}

View File

@ -0,0 +1,88 @@
/*!
* \file glonass_gnav_utc_model.h
* \brief Interface of a GLONASS GNAV UTC MODEL storage
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#ifndef GNSS_SDR_GLONASS_GNAV_UTC_MODEL_H_
#define GNSS_SDR_GLONASS_GNAV_UTC_MODEL_H_
#include "boost/assign.hpp"
#include <boost/serialization/nvp.hpp>
#include <iostream>
/*!
* \brief This class is a storage for the GLONASS GNAV UTC MODEL data as described in GLONASS ICD (Edition 5.1)
* \note Code added as part of GSoC 2017 program
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*/
class Glonass_Gnav_Utc_Model
{
public:
bool valid;
// Clock Parameters
double d_tau_c; //!< GLONASS time scale correction to UTC(SU) time. [s]
double d_tau_gps; //!< Correction to GPS time to GLONASS time [day]
double d_N_4; //!< Four year interval number starting from 1996 [4 year interval]
double d_N_A; //!< Calendar day number within the four-year period beginning since the leap year for Almanac data [days]
double d_B1; //!< Coefficient to determine DeltaUT1 [s]
double d_B2; //!< Coefficient to determine DeltaUT1 [s/msd]
template<class Archive>
/*!
* \brief Serialize is a boost standard method to be called by the boost XML serialization. Here is used to save the almanac data on disk file.
*/
void serialize(Archive& archive, const unsigned int version)
{
using boost::serialization::make_nvp;
if(version){};
archive & make_nvp("valid",valid);
archive & make_nvp("d_tau_c", d_tau_c);
archive & make_nvp("d_tau_gps", d_tau_gps);
archive & make_nvp("d_N_4", d_N_4);
archive & make_nvp("d_N_A", d_N_A);
archive & make_nvp("d_B1", d_B1);
archive & make_nvp("d_B2", d_B2);
}
/*!
* Default constructor
*/
Glonass_Gnav_Utc_Model();
/*!
* \brief Computes the Coordinated Universal Time (UTC) and
* returns it in [s] (GLONASS ICD (Edition 5.1) Section 3.3.3 GLONASS Time)
*/
double utc_time(double glonass_time_corrected);
};
#endif

View File

@ -557,6 +557,3 @@ void Gnss_Satellite::set_block(const std::string& system_, unsigned int PRN_)
{ {
block = what_block(system_, PRN_); block = what_block(system_, PRN_);
} }

View File

@ -37,6 +37,7 @@
#include <string> #include <string>
#include "boost/assign.hpp" #include "boost/assign.hpp"
#include <boost/serialization/nvp.hpp> #include <boost/serialization/nvp.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>

File diff suppressed because it is too large Load Diff

View File

@ -49,6 +49,7 @@
#include "galileo_fnav_message.h" #include "galileo_fnav_message.h"
#include "gps_navigation_message.h" #include "gps_navigation_message.h"
#include "gps_cnav_navigation_message.h" #include "gps_cnav_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
/*! /*!
@ -56,7 +57,7 @@
* defined in the RTCM 3.2 Standard, plus some utilities to handle messages. * defined in the RTCM 3.2 Standard, plus some utilities to handle messages.
* *
* Generation of the following Message Types: * Generation of the following Message Types:
* 1001, 1002, 1003, 1004, 1005, 1006, 1008, 1019, 1029, 1045 * 1001, 1002, 1003, 1004, 1005, 1006, 1008, 1019, 1020, 1029, 1045
* *
* Decoding of the following Message Types: * Decoding of the following Message Types:
* 1019, 1045 * 1019, 1045
@ -128,6 +129,47 @@ public:
*/ */
std::string print_MT1008(unsigned int ref_id, const std::string & antenna_descriptor, unsigned int antenna_setup_id, const std::string & antenna_serial_number); std::string print_MT1008(unsigned int ref_id, const std::string & antenna_descriptor, unsigned int antenna_setup_id, const std::string & antenna_serial_number);
/*!
* \brief Prints L1-Only GLONASS RTK Observables
* \details This GLONASS message type is not generally used or supported; type 1012 is to be preferred.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return string with message contents
*/
std::string print_MT1009(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables, unsigned short station_id);
/*!
* \brief Prints Extended L1-Only GLONASS RTK Observables
* \details This GLONASS message type is used when only L1 data is present and bandwidth is very tight, often 1012 is used in such cases.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return string with message contents
*/
std::string print_MT1010(const Glonass_Gnav_Ephemeris& glonass_gnav_eph, double obs_time, const std::map<int, Gnss_Synchro> & observables, unsigned short station_id);
/*!
* \brief Prints L1&L2 GLONASS RTK Observables
* \details This GLONASS message type is not generally used or supported; type 1012 is to be preferred
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return string with message contents
*/
std::string print_MT1011(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables, unsigned short station_id);
/*!
* \brief Prints Extended L1&L2 GLONASS RTK Observables
* \details This GLONASS message type is the most common observational message type, with L1/L2/SNR content. This is one of the most common messages found.
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return string with message contents
*/
std::string print_MT1012(const Glonass_Gnav_Ephemeris& glonass_gnav_ephL1, const Glonass_Gnav_Ephemeris& glonass_gnav_ephL2, double obs_time, const std::map<int, Gnss_Synchro> & observables, unsigned short station_id);
/*! /*!
* \brief Prints message type 1019 (GPS Ephemeris), should be broadcast in the event that * \brief Prints message type 1019 (GPS Ephemeris), should be broadcast in the event that
* the IODC does not match the IODE, and every 2 minutes. * the IODC does not match the IODE, and every 2 minutes.
@ -139,6 +181,25 @@ public:
*/ */
int read_MT1019(const std::string & message, Gps_Ephemeris & gps_eph); int read_MT1019(const std::string & message, Gps_Ephemeris & gps_eph);
/*!
* \brief Prints message type 1020 (GLONASS Ephemeris).
* \note Code added as part of GSoC 2017 program
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param glonass_gnav_utc_model GLONASS GNAV Clock Information
* \return Returns message type as a string type
*/
std::string print_MT1020(const Glonass_Gnav_Ephemeris & glonass_gnav_eph, const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
/*!
* \brief Verifies and reads messages of type 1020 (GLONASS Ephemeris).
* \note Code added as part of GSoC 2017 program
* \param message Message to read as a string type
* \param glonass_gnav_eph GLONASS GNAV Broadcast Ephemeris
* \param glonass_gnav_utc_model GLONASS GNAV Clock Information
* \return Returns 1 if anything goes wrong, 0 otherwise.
*/
int read_MT1020(const std::string & message, Glonass_Gnav_Ephemeris & glonass_gnav_eph, Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
/*! /*!
* \brief Prints message type 1029 (Unicode Text String) * \brief Prints message type 1029 (Unicode Text String)
*/ */
@ -160,6 +221,7 @@ public:
std::string print_MSM_1( const Gps_Ephemeris & gps_eph, std::string print_MSM_1( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -175,6 +237,7 @@ public:
std::string print_MSM_2( const Gps_Ephemeris & gps_eph, std::string print_MSM_2( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -190,6 +253,7 @@ public:
std::string print_MSM_3( const Gps_Ephemeris & gps_eph, std::string print_MSM_3( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -205,6 +269,7 @@ public:
std::string print_MSM_4( const Gps_Ephemeris & gps_eph, std::string print_MSM_4( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -220,6 +285,7 @@ public:
std::string print_MSM_5( const Gps_Ephemeris & gps_eph, std::string print_MSM_5( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -235,6 +301,7 @@ public:
std::string print_MSM_6( const Gps_Ephemeris & gps_eph, std::string print_MSM_6( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -250,6 +317,7 @@ public:
std::string print_MSM_7( const Gps_Ephemeris & gps_eph, std::string print_MSM_7( const Gps_Ephemeris & gps_eph,
const Gps_CNAV_Ephemeris & gps_cnav_eph, const Gps_CNAV_Ephemeris & gps_cnav_eph,
const Galileo_Ephemeris & gal_eph, const Galileo_Ephemeris & gal_eph,
const Glonass_Gnav_Ephemeris & glo_gnav_eph,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id, unsigned int ref_id,
@ -262,6 +330,15 @@ public:
unsigned int lock_time(const Gps_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which GPS L1 signals have been continually tracked. unsigned int lock_time(const Gps_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which GPS L1 signals have been continually tracked.
unsigned int lock_time(const Gps_CNAV_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which GPS L2 signals have been continually tracked. unsigned int lock_time(const Gps_CNAV_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which GPS L2 signals have been continually tracked.
unsigned int lock_time(const Galileo_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which Galileo signals have been continually tracked. unsigned int lock_time(const Galileo_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro); //<! Returns the time period in which Galileo signals have been continually tracked.
/*!
* \brief Locks time period in which GLONASS signals have been continually tracked.
* \note Code added as part of GSoC 2017 program
* \param eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return Returns the time period in which GLONASS signals have been continually tracked.
*/
unsigned int lock_time(const Glonass_Gnav_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro);
std::string bin_to_hex(const std::string & s) const; //<! Returns a string of hexadecimal symbols from a string of binary symbols std::string bin_to_hex(const std::string & s) const; //<! Returns a string of hexadecimal symbols from a string of binary symbols
std::string hex_to_bin(const std::string & s) const; //<! Returns a string of binary symbols from a string of hexadecimal symbols std::string hex_to_bin(const std::string & s) const; //<! Returns a string of binary symbols from a string of hexadecimal symbols
@ -270,9 +347,17 @@ public:
std::string binary_data_to_bin(const std::string& s) const; //<! Returns a string of binary symbols from a string of binary data std::string binary_data_to_bin(const std::string& s) const; //<! Returns a string of binary symbols from a string of binary data
unsigned long int bin_to_uint(const std::string & s) const; //<! Returns an unsigned long int from a string of binary symbols unsigned long int bin_to_uint(const std::string & s) const; //<! Returns an unsigned long int from a string of binary symbols
long int bin_to_int(const std::string & s) const; //<! Returns a long int from a string of binary symbols long int bin_to_int(const std::string & s) const;
double bin_to_double(const std::string & s) const; //<! Returns double from a string of binary symbols double bin_to_double(const std::string & s) const; //<! Returns double from a string of binary symbols
/*!
* \brief Locks time period in which GLONASS signals have been continually tracked.
* \note Code added as part of GSoC 2017 program
* \param eph GLONASS GNAV Broadcast Ephemeris
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \return //<! Returns a long int from a string of binary symbols
*/
long int bin_to_sint(const std::string & s) const;
unsigned long int hex_to_uint(const std::string & s) const; //<! Returns an unsigned long int from a string of hexadecimal symbols unsigned long int hex_to_uint(const std::string & s) const; //<! Returns an unsigned long int from a string of hexadecimal symbols
long int hex_to_int(const std::string & s) const; //<! Returns a long int from a string of hexadecimal symbols long int hex_to_int(const std::string & s) const; //<! Returns a long int from a string of hexadecimal symbols
@ -303,6 +388,70 @@ private:
std::bitset<152> get_MT1005_test(); std::bitset<152> get_MT1005_test();
/*!
* \brief Generates contents of message header for types 1009, 1010, 1011 and 1012. GLONASS RTK Message
* \note Code added as part of GSoC 2017 program
* \param msg_number Message type number, acceptable options include 1009 to 1012
* \param obs_time Time of observation at the moment of printing
* \param observables Set of observables as defined by the platform
* \param ref_id
* \param smooth_int
* \param divergence_free
* \return Returns the message header content as set of bits
*/
std::bitset<61> get_MT1009_12_header(unsigned int msg_number,
double obs_time,
const std::map<int, Gnss_Synchro> & observables,
unsigned int ref_id,
unsigned int smooth_int,
bool sync_flag,
bool divergence_free);
/*!
* \brief Get the contents of the satellite specific portion of a type 1009 Message (GLONASS Basic RTK, L1 Only)
* \details Contents generated for each satellite. See table 3.5-11
* \note Code added as part of GSoC 2017 program
* \param ephGNAV Ephemeris for GLONASS GNAV in L1 satellites
* \param obs_time Time of observation at the moment of printing
* \param gnss_synchro Information generated by channels while processing the satellite
* \return Returns the message content as set of bits
*/
std::bitset<64> get_MT1009_sat_content(const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const Gnss_Synchro & gnss_synchro);
/*!
* \brief Get the contents of the satellite specific portion of a type 1010 Message (GLONASS Extended RTK, L1 Only)
* \details Contents generated for each satellite. See table 3.5-12
* \note Code added as part of GSoC 2017 program
* \param ephGNAV Ephemeris for GLONASS GNAV in L1 satellites
* \param obs_time Time of observation at the moment of printing
* \param gnss_synchro Information generated by channels while processing the satellite
* \return Returns the message content as set of bits
*/
std::bitset<79> get_MT1010_sat_content(const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const Gnss_Synchro & gnss_synchro);
/*!
* \brief Get the contents of the satellite specific portion of a type 1011 Message (GLONASS Basic RTK, L1 & L2)
* \details Contents generated for each satellite. See table 3.5-13
* \note Code added as part of GSoC 2017 program
* \param ephGNAVL1 Ephemeris for GLONASS GNAV in L1 satellites
* \param ephGNAVL2 Ephemeris for GLONASS GNAV in L2 satellites
* \param obs_time Time of observation at the moment of printing
* \param gnss_synchroL1 Information generated by channels while processing the GLONASS GNAV L1 satellite
* \param gnss_synchroL2 Information generated by channels while processing the GLONASS GNAV L2 satellite
* \return Returns the message content as set of bits
*/
std::bitset<107> get_MT1011_sat_content(const Glonass_Gnav_Ephemeris & ephGNAVL1, const Glonass_Gnav_Ephemeris & ephGNAVL2, double obs_time, const Gnss_Synchro & gnss_synchroL1, const Gnss_Synchro & gnss_synchroL2);
/*!
* \brief Get the contents of the satellite specific portion of a type 1012 Message (GLONASS Extended RTK, L1 & L2)
* \details Contents generated for each satellite. See table 3.5-14
* \note Code added as part of GSoC 2017 program
* \param ephGNAVL1 Ephemeris for GLONASS GNAV in L1 satellites
* \param ephGNAVL2 Ephemeris for GLONASS GNAV in L2 satellites
* \param obs_time Time of observation at the moment of printing
* \param gnss_synchroL1 Information generated by channels while processing the GLONASS GNAV L1 satellite
* \param gnss_synchroL2 Information generated by channels while processing the GLONASS GNAV L2 satellite
* \return Returns the message content as set of bits
*/
std::bitset<130> get_MT1012_sat_content(const Glonass_Gnav_Ephemeris & ephGNAVL1, const Glonass_Gnav_Ephemeris & ephGNAVL2, double obs_time, const Gnss_Synchro & gnss_synchroL1, const Gnss_Synchro & gnss_synchroL2);
std::string get_MSM_header(unsigned int msg_number, std::string get_MSM_header(unsigned int msg_number,
double obs_time, double obs_time,
const std::map<int, Gnss_Synchro> & observables, const std::map<int, Gnss_Synchro> & observables,
@ -318,12 +467,12 @@ private:
std::string get_MSM_5_content_sat_data(const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_5_content_sat_data(const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_1_content_signal_data(const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_1_content_signal_data(const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_2_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_2_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_3_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_3_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_4_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_4_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_5_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_5_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_6_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_6_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
std::string get_MSM_7_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables); std::string get_MSM_7_content_signal_data(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const std::map<int, Gnss_Synchro> & observables);
// //
// Utilities // Utilities
@ -335,10 +484,13 @@ private:
boost::posix_time::ptime compute_GPS_time(const Gps_Ephemeris& eph, double obs_time) const; boost::posix_time::ptime compute_GPS_time(const Gps_Ephemeris& eph, double obs_time) const;
boost::posix_time::ptime compute_GPS_time(const Gps_CNAV_Ephemeris & eph, double obs_time) const; boost::posix_time::ptime compute_GPS_time(const Gps_CNAV_Ephemeris & eph, double obs_time) const;
boost::posix_time::ptime compute_Galileo_time(const Galileo_Ephemeris& eph, double obs_time) const; boost::posix_time::ptime compute_Galileo_time(const Galileo_Ephemeris& eph, double obs_time) const;
boost::posix_time::ptime compute_GLONASS_time(const Glonass_Gnav_Ephemeris& eph, double obs_time) const;
boost::posix_time::ptime gps_L1_last_lock_time[64]; boost::posix_time::ptime gps_L1_last_lock_time[64];
boost::posix_time::ptime gps_L2_last_lock_time[64]; boost::posix_time::ptime gps_L2_last_lock_time[64];
boost::posix_time::ptime gal_E1_last_lock_time[64]; boost::posix_time::ptime gal_E1_last_lock_time[64];
boost::posix_time::ptime gal_E5_last_lock_time[64]; boost::posix_time::ptime gal_E5_last_lock_time[64];
boost::posix_time::ptime glo_L1_last_lock_time[64];
boost::posix_time::ptime glo_L2_last_lock_time[64];
unsigned int lock_time_indicator(unsigned int lock_time_period_s); unsigned int lock_time_indicator(unsigned int lock_time_period_s);
unsigned int msm_lock_time_indicator(unsigned int lock_time_period_s); unsigned int msm_lock_time_indicator(unsigned int lock_time_period_s);
unsigned int msm_extended_lock_time_indicator(unsigned int lock_time_period_s); unsigned int msm_extended_lock_time_indicator(unsigned int lock_time_period_s);
@ -870,6 +1022,65 @@ private:
std::bitset<8> DF032; std::bitset<8> DF032;
/*!
* \brief Sets the Data Field value
* \note Code added as part of GSoC 2017 program
* \param obs_time Time of observation at the moment of printing
* \return returns 0 upon success
*/
int set_DF034(double obs_time);
std::bitset<27> DF034; //!< GLONASS Epoch Time (tk)
std::bitset<5> DF035; //!< No. of GLONASS Satellite Signals Processed
int set_DF035(const std::map<int, Gnss_Synchro> & observables);
std::bitset<1> DF036; //!< GLONASS Divergence-free Smoothing Indicator
int set_DF036(bool divergence_free_smoothing_indicator);
std::bitset<3> DF037; //!< GLONASS Smoothing Interval
int set_DF037(short int smoothing_interval);
std::bitset<6> DF038; //!< GLONASS Satellite ID (Satellite Slot Number)
int set_DF038(const Gnss_Synchro & gnss_synchro);
int set_DF038(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF039; //!< GLONASS L1 Code Indicator
int set_DF039(bool code_indicator);
std::bitset<5> DF040; //!< GLONASS Satellite Frequency Number
int set_DF040(int frequency_channel_number);
int set_DF040(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<25> DF041; //!< GLONASS L1 Pseudorange
int set_DF041(const Gnss_Synchro & gnss_synchro);
std::bitset<20> DF042; //!< GLONASS L1 PhaseRange - L1 Pseudorange
int set_DF042(const Gnss_Synchro & gnss_synchro);
std::bitset<7> DF043; //!< GLONASS L1 Lock Time Indicator
int set_DF043(const Glonass_Gnav_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro);
std::bitset<7> DF044; //!< GLONASS Integer L1 Pseudorange Modulus Ambiguity
int set_DF044(const Gnss_Synchro & gnss_synchro);
std::bitset<8> DF045; //!< GLONASS L1 CNR
int set_DF045(const Gnss_Synchro & gnss_synchro);
std::bitset<2> DF046; //!< GLONASS L2 code indicator
int set_DF046(unsigned short code_indicator);
std::bitset<14> DF047; //!< GLONASS L2 - L1 Pseudorange Difference
int set_DF047(const Gnss_Synchro & gnss_synchroL1, const Gnss_Synchro & gnss_synchroL2);
std::bitset<20> DF048; //!< GLONASS L2 PhaseRange - L1 Pseudorange
int set_DF048(const Gnss_Synchro & gnss_synchroL1, const Gnss_Synchro & gnss_synchroL2);
std::bitset<7> DF049; //!< GLONASS L2 Lock Time Indicator
int set_DF049(const Glonass_Gnav_Ephemeris & eph, double obs_time, const Gnss_Synchro & gnss_synchro);
std::bitset<8> DF050; //!< GLONASS L2 CNR
int set_DF050(const Gnss_Synchro & gnss_synchro);
std::bitset<16> DF051; std::bitset<16> DF051;
int set_DF051(const Gps_Ephemeris & gps_eph, double obs_time); int set_DF051(const Gps_Ephemeris & gps_eph, double obs_time);
@ -964,6 +1175,105 @@ private:
std::bitset<1> DF103; std::bitset<1> DF103;
int set_DF103(const Gps_Ephemeris & gps_eph); int set_DF103(const Gps_Ephemeris & gps_eph);
std::bitset<1> DF104; //!< GLONASS Almanac Health
int set_DF104(unsigned int glonass_gnav_alm_health);
std::bitset<1> DF105; //!< GLONASS Almanac Health Availability Indicator
int set_DF105(unsigned int glonass_gnav_alm_health_ind);
std::bitset<2> DF106; //!< GLONASS P1 Word
int set_DF106(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<12> DF107; //!< GLONASS Epoch (tk)
int set_DF107(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF108; //!< GLONASS MSB of Bn Word
int set_DF108(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF109; //!< GLONASS P2 Word
int set_DF109(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<7> DF110; //!< GLONASS Ephmeris Epoch (tb)
int set_DF110(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<24> DF111; //!< GLONASS Xn first derivative
int set_DF111(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<27> DF112; //!< GLONASS Xn
int set_DF112(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<5> DF113; //!< GLONASS Xn second derivative
int set_DF113(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<24> DF114; //!< GLONASS Yn first derivative
int set_DF114(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<27> DF115; //!< GLONASS Yn
int set_DF115(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<5> DF116; //!< GLONASS Yn second derivative
int set_DF116(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<24> DF117; //!< GLONASS Zn first derivative
int set_DF117(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<27> DF118; //!< GLONASS Zn
int set_DF118(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<5> DF119; //!< GLONASS Zn second derivative
int set_DF119(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF120; //!< GLONASS P3
int set_DF120(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<11> DF121; //!< GLONASS GAMMA_N
int set_DF121(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<2> DF122; //!< GLONASS P
int set_DF122(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF123; //!< GLONASS ln (third string)
int set_DF123(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<22> DF124; //!< GLONASS TAU_N
int set_DF124(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<5> DF125; //!< GLONASS DELTA_TAU_N
int set_DF125(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<5> DF126; //!< GLONASS Eccentricity
int set_DF126(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF127; //!< GLONASS P4
int set_DF127(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<4> DF128; //!< GLONASS F_T
int set_DF128(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<11> DF129; //!< GLONASS N_T
int set_DF129(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<2> DF130; //!< GLONASS M
int set_DF130(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF131; //!< GLONASS Availability of additional data
int set_DF131(unsigned int fifth_str_additional_data_ind);
std::bitset<11> DF132; //!< GLONASS N_A
int set_DF132(const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
std::bitset<32> DF133; //!< GLONASS TAU_C
int set_DF133(const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
std::bitset<5> DF134; //!< GLONASS N_4
int set_DF134(const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
std::bitset<22> DF135; //!< GLONASS TAU_GPS
int set_DF135(const Glonass_Gnav_Utc_Model & glonass_gnav_utc_model);
std::bitset<1> DF136; //!< GLONASS L_N (FIFTH STRING)
int set_DF136(const Glonass_Gnav_Ephemeris & glonass_gnav_eph);
std::bitset<1> DF137; std::bitset<1> DF137;
int set_DF137(const Gps_Ephemeris & gps_eph); int set_DF137(const Gps_Ephemeris & gps_eph);
@ -1092,7 +1402,7 @@ private:
int set_DF401(const Gnss_Synchro & gnss_synchro); int set_DF401(const Gnss_Synchro & gnss_synchro);
std::bitset<4> DF402; std::bitset<4> DF402;
int set_DF402(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const Gnss_Synchro & gnss_synchro); int set_DF402(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const Gnss_Synchro & gnss_synchro);
std::bitset<6> DF403; std::bitset<6> DF403;
int set_DF403(const Gnss_Synchro & gnss_synchro); int set_DF403(const Gnss_Synchro & gnss_synchro);
@ -1107,7 +1417,7 @@ private:
int set_DF406(const Gnss_Synchro & gnss_synchro); int set_DF406(const Gnss_Synchro & gnss_synchro);
std::bitset<10> DF407; std::bitset<10> DF407;
int set_DF407(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, double obs_time, const Gnss_Synchro & gnss_synchro); int set_DF407(const Gps_Ephemeris & ephNAV, const Gps_CNAV_Ephemeris & ephCNAV, const Galileo_Ephemeris & ephFNAV, const Glonass_Gnav_Ephemeris & ephGNAV, double obs_time, const Gnss_Synchro & gnss_synchro);
std::bitset<10> DF408; std::bitset<10> DF408;
int set_DF408(const Gnss_Synchro & gnss_synchro); int set_DF408(const Gnss_Synchro & gnss_synchro);

View File

@ -59,6 +59,10 @@
#include "sbas_ephemeris.h" #include "sbas_ephemeris.h"
#include "glonass_gnav_ephemeris.h"
#include "glonass_gnav_almanac.h"
#include "glonass_gnav_utc_model.h"
using google::LogMessage; using google::LogMessage;
DECLARE_string(log_dir); DECLARE_string(log_dir);
@ -139,7 +143,9 @@ DECLARE_string(log_dir);
#endif #endif
#endif #endif
#include "unit-tests/system-parameters/glonass_gnav_ephemeris_test.cc"
#include "unit-tests/system-parameters/glonass_gnav_almanac_test.cc"
#include "unit-tests/system-parameters/glonass_gnav_nav_message_test.cc"
// For GPS NAVIGATION (L1) // For GPS NAVIGATION (L1)
concurrent_queue<Gps_Acq_Assist> global_gps_acq_assist_queue; concurrent_queue<Gps_Acq_Assist> global_gps_acq_assist_queue;

View File

@ -87,6 +87,35 @@ TEST(RinexPrinterTest, GalileoObsHeader)
} }
TEST(RinexPrinterTest, GlonassObsHeader)
{
std::string line_aux;
std::string line_str;
bool no_more_finds = false;
const Glonass_Gnav_Ephemeris eph = Glonass_Gnav_Ephemeris();
std::shared_ptr<Rinex_Printer> rp1;
rp1 = std::make_shared<Rinex_Printer>();
rp1->rinex_obs_header(rp1->obsFile, eph, 0.0);
rp1->obsFile.seekp(0);
while(!rp1->obsFile.eof())
{
std::getline(rp1->obsFile, line_str);
if(!no_more_finds)
{
if (line_str.find("SYS / # / OBS TYPES", 59) != std::string::npos)
{
no_more_finds = true;
line_aux = std::string(line_str);
}
}
}
std::string expected_str("R 4 C1C L1C D1C S1C SYS / # / OBS TYPES ");
EXPECT_EQ(0, expected_str.compare(line_aux));
if(remove(rp1->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
line_aux.clear();
}
TEST(RinexPrinterTest, MixedObsHeader) TEST(RinexPrinterTest, MixedObsHeader)
@ -133,6 +162,50 @@ TEST(RinexPrinterTest, MixedObsHeader)
} }
TEST(RinexPrinterTest, MixedObsHeaderGpsGlo)
{
std::string line_aux;
std::string line_aux2;
std::string line_str;
bool no_more_finds = false;
const Glonass_Gnav_Ephemeris eph_glo = Glonass_Gnav_Ephemeris();
const Gps_Ephemeris eph_gps = Gps_Ephemeris();
std::shared_ptr<Rinex_Printer> rp1;
rp1 = std::make_shared<Rinex_Printer>();
rp1->rinex_obs_header(rp1->obsFile, eph_gps, eph_glo, 0.0, "1C");
rp1->obsFile.seekp(0);
int systems_found = 0;
while(!rp1->obsFile.eof())
{
std::getline(rp1->obsFile, line_str);
if(!no_more_finds)
{
if (line_str.find("SYS / # / OBS TYPES", 59) != std::string::npos)
{
systems_found++;
if(systems_found == 1)
{
line_aux = std::string(line_str);
}
if(systems_found == 2)
{
line_aux2 = std::string(line_str);
no_more_finds = true;
}
}
}
}
std::string expected_str("G 4 C1C L1C D1C S1C SYS / # / OBS TYPES ");
std::string expected_str2("R 8 C1C L1C D1C S1C SYS / # / OBS TYPES ");
EXPECT_EQ(0, expected_str.compare(line_aux));
EXPECT_EQ(0, expected_str2.compare(line_aux2));
if(remove(rp1->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}
TEST(RinexPrinterTest, GalileoObsLog) TEST(RinexPrinterTest, GalileoObsLog)
{ {
std::string line_aux; std::string line_aux;
@ -201,6 +274,74 @@ TEST(RinexPrinterTest, GalileoObsLog)
} }
TEST(RinexPrinterTest, GlonassObsLog)
{
std::string line_aux;
std::string line_str;
bool no_more_finds = false;
const Glonass_Gnav_Ephemeris eph = Glonass_Gnav_Ephemeris();
std::shared_ptr<Rinex_Printer> rp;
rp = std::make_shared<Rinex_Printer>();
rp->rinex_obs_header(rp->obsFile, eph, 0.0);
std::map<int,Gnss_Synchro> gnss_pseudoranges_map;
Gnss_Synchro gs1 = Gnss_Synchro();
Gnss_Synchro gs2 = Gnss_Synchro();
Gnss_Synchro gs3 = Gnss_Synchro();
Gnss_Synchro gs4 = Gnss_Synchro();
std::string sys = "R";
gs1.System = *sys.c_str();
gs2.System = *sys.c_str();
gs3.System = *sys.c_str();
gs4.System = *sys.c_str();
std::string sig = "1C";
std::memcpy((void*)gs1.Signal, sig.c_str(), 3);
std::memcpy((void*)gs2.Signal, sig.c_str(), 3);
std::memcpy((void*)gs3.Signal, sig.c_str(), 3);
std::memcpy((void*)gs4.Signal, sig.c_str(), 3);
gs1.PRN = 3;
gs2.PRN = 8;
gs3.PRN = 10;
gs4.PRN = 22;
gs4.Pseudorange_m = 22000000;
gs4.Carrier_phase_rads = 23.4;
gs4.Carrier_Doppler_hz = 1534;
gs4.CN0_dB_hz = 42;
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(1,gs1) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(2,gs2) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(3,gs3) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(4,gs4) );
rp->log_rinex_obs(rp->obsFile, eph, 0.0, gnss_pseudoranges_map);
rp->obsFile.seekp(0);
while(!rp->obsFile.eof())
{
std::getline(rp->obsFile, line_str);
if(!no_more_finds)
{
if (line_str.find("R22", 0) != std::string::npos)
{
no_more_finds = true;
line_aux = std::string(line_str);
}
}
}
std::string expected_str("R22 22000000.000 7 3.724 7 1534.000 7 42.000 ");
EXPECT_EQ(0, expected_str.compare(line_aux));
if(remove(rp->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}
TEST(RinexPrinterTest, GpsObsLogDualBand) TEST(RinexPrinterTest, GpsObsLogDualBand)
{ {
std::string line_aux; std::string line_aux;
@ -473,3 +614,111 @@ TEST(RinexPrinterTest, MixedObsLog)
if(remove(rp->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file"; if(remove(rp->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
} }
TEST(RinexPrinterTest, MixedObsLogGpsGlo)
{
std::string line_aux;
std::string line_str;
bool no_more_finds = false;
const Glonass_Gnav_Ephemeris eph_glo = Glonass_Gnav_Ephemeris();
const Gps_Ephemeris eph_gps = Gps_Ephemeris();
std::shared_ptr<Rinex_Printer> rp;
rp = std::make_shared<Rinex_Printer>();
rp->rinex_obs_header(rp->obsFile, eph_gps, eph_glo, 0.0, "1C");
std::map<int,Gnss_Synchro> gnss_pseudoranges_map;
Gnss_Synchro gs1 = Gnss_Synchro();
Gnss_Synchro gs2 = Gnss_Synchro();
Gnss_Synchro gs3 = Gnss_Synchro();
Gnss_Synchro gs4 = Gnss_Synchro();
Gnss_Synchro gs5 = Gnss_Synchro();
Gnss_Synchro gs6 = Gnss_Synchro();
Gnss_Synchro gs7 = Gnss_Synchro();
Gnss_Synchro gs8 = Gnss_Synchro();
std::string sys = "G";
gs1.System = *sys.c_str();
gs2.System = *sys.c_str();
gs3.System = *sys.c_str();
gs4.System = *sys.c_str();
sys = "R";
gs5.System = *sys.c_str();
gs6.System = *sys.c_str();
gs7.System = *sys.c_str();
gs8.System = *sys.c_str();
std::string sig = "1C";
std::memcpy((void*)gs1.Signal, sig.c_str(), 3);
std::memcpy((void*)gs2.Signal, sig.c_str(), 3);
std::memcpy((void*)gs3.Signal, sig.c_str(), 3);
std::memcpy((void*)gs4.Signal, sig.c_str(), 3);
sig = "1C";
std::memcpy((void*)gs5.Signal, sig.c_str(), 3);
std::memcpy((void*)gs6.Signal, sig.c_str(), 3);
std::memcpy((void*)gs7.Signal, sig.c_str(), 3);
std::memcpy((void*)gs8.Signal, sig.c_str(), 3);
gs1.PRN = 3;
gs2.PRN = 8;
gs3.PRN = 14;
gs4.PRN = 16;
gs5.PRN = 3;
gs6.PRN = 16;
gs7.PRN = 14;
gs8.PRN = 16;
gs2.Pseudorange_m = 22000002.1;
gs2.Carrier_phase_rads = 45.4;
gs2.Carrier_Doppler_hz = 321;
gs2.CN0_dB_hz = 39;
gs4.Pseudorange_m = 22000000;
gs4.Carrier_phase_rads = 23.4;
gs4.Carrier_Doppler_hz = -1534;
gs4.CN0_dB_hz = 40;
gs6.Pseudorange_m = 22000000;
gs6.Carrier_phase_rads = 52.1;
gs6.Carrier_Doppler_hz = 1534;
gs6.CN0_dB_hz = 41;
gs8.Pseudorange_m = 22000000;
gs8.Carrier_phase_rads = 0.8;
gs8.Carrier_Doppler_hz = -20;
gs8.CN0_dB_hz = 42;
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(1,gs1) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(2,gs2) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(3,gs3) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(4,gs4) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(5,gs5) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(6,gs6) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(7,gs7) );
gnss_pseudoranges_map.insert( std::pair<int, Gnss_Synchro>(8,gs8) );
rp->log_rinex_obs(rp->obsFile, eph_gps, eph_glo, 0.0, gnss_pseudoranges_map);
rp->obsFile.seekp(0);
while(!rp->obsFile.eof())
{
std::getline(rp->obsFile, line_str);
if(!no_more_finds)
{
if (line_str.find("R16", 0) != std::string::npos)
{
no_more_finds = true;
line_aux = std::string(line_str);
}
}
}
std::string expected_str("R16 22000000.000 7 0.127 7 -20.000 7 42.000 22000000.000 6 8.292 6 1534.000 6 41.000");
EXPECT_EQ(0, expected_str.compare(line_aux));
if(remove(rp->obsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}

View File

@ -253,6 +253,7 @@ TEST(RtcmTest, MT1005)
} }
TEST(RtcmTest, MT1019) TEST(RtcmTest, MT1019)
{ {
auto rtcm = std::make_shared<Rtcm>(); auto rtcm = std::make_shared<Rtcm>();
@ -276,6 +277,41 @@ TEST(RtcmTest, MT1019)
} }
TEST(RtcmTest, MT1020)
{
auto rtcm = std::make_shared<Rtcm>();
bool expected_true = true;
// Objects to populate the ephemeris and utc fields
Glonass_Gnav_Ephemeris gnav_ephemeris = Glonass_Gnav_Ephemeris();
Glonass_Gnav_Utc_Model gnav_utc_model = Glonass_Gnav_Utc_Model();
// Objects read, used for comparison
Glonass_Gnav_Ephemeris gnav_ephemeris_read = Glonass_Gnav_Ephemeris();
Glonass_Gnav_Utc_Model gnav_utc_model_read = Glonass_Gnav_Utc_Model();
// Perform data read and print of special values types
gnav_ephemeris.d_P_1 = 15;
// Bit distribution per fields
gnav_ephemeris.d_t_k = 7560;
// Glonass signed values
gnav_ephemeris.d_VXn = -0.490900039672852;
// Bit distribution per fields dependant on other factors
gnav_ephemeris.d_t_b = 8100;
// Binary flag representation
gnav_ephemeris.d_P_3 = 1;
std::string tx_msg = rtcm->print_MT1020(gnav_ephemeris, gnav_utc_model);
EXPECT_EQ(0, rtcm->read_MT1020(tx_msg, gnav_ephemeris_read, gnav_utc_model_read));
EXPECT_EQ(gnav_ephemeris.d_P_1, gnav_ephemeris_read.d_P_1);
EXPECT_TRUE(gnav_ephemeris.d_t_b - gnav_ephemeris_read.d_t_b < FLT_EPSILON);
EXPECT_TRUE( gnav_ephemeris.d_VXn - gnav_ephemeris_read.d_VXn < FLT_EPSILON);
EXPECT_TRUE( gnav_ephemeris.d_t_k - gnav_ephemeris.d_t_k < FLT_EPSILON);
EXPECT_EQ(gnav_ephemeris.d_P_3, gnav_ephemeris_read.d_P_3);
EXPECT_EQ(1, rtcm->read_MT1020(rtcm->bin_to_binary_data(rtcm->hex_to_bin("FFFFFFFFFFF")), gnav_ephemeris_read, gnav_utc_model_read));
}
TEST(RtcmTest, MT1029) TEST(RtcmTest, MT1029)
{ {
auto rtcm = std::make_shared<Rtcm>(); auto rtcm = std::make_shared<Rtcm>();
@ -321,6 +357,7 @@ TEST(RtcmTest, MSMCell)
auto rtcm = std::make_shared<Rtcm>(); auto rtcm = std::make_shared<Rtcm>();
Gps_Ephemeris gps_eph = Gps_Ephemeris(); Gps_Ephemeris gps_eph = Gps_Ephemeris();
Galileo_Ephemeris gal_eph = Galileo_Ephemeris(); Galileo_Ephemeris gal_eph = Galileo_Ephemeris();
Glonass_Gnav_Ephemeris glo_gnav_eph = Glonass_Gnav_Ephemeris();
std::map<int, Gnss_Synchro> pseudoranges; std::map<int, Gnss_Synchro> pseudoranges;
Gnss_Synchro gnss_synchro; Gnss_Synchro gnss_synchro;
@ -328,15 +365,18 @@ TEST(RtcmTest, MSMCell)
Gnss_Synchro gnss_synchro3; Gnss_Synchro gnss_synchro3;
Gnss_Synchro gnss_synchro4; Gnss_Synchro gnss_synchro4;
Gnss_Synchro gnss_synchro5; Gnss_Synchro gnss_synchro5;
Gnss_Synchro gnss_synchro6;
gnss_synchro.PRN = 4; gnss_synchro.PRN = 4;
gnss_synchro2.PRN = 8; gnss_synchro2.PRN = 8;
gnss_synchro3.PRN = 32; gnss_synchro3.PRN = 32;
gnss_synchro4.PRN = 10; gnss_synchro4.PRN = 10;
gnss_synchro5.PRN = 10; gnss_synchro5.PRN = 10;
gnss_synchro6.PRN = 10;
std::string gps = "G"; std::string gps = "G";
std::string gal = "E"; std::string gal = "E";
std::string glo = "R";
std::string c1 = "1C"; std::string c1 = "1C";
std::string s2 = "2S"; std::string s2 = "2S";
@ -347,24 +387,28 @@ TEST(RtcmTest, MSMCell)
gnss_synchro3.System = *gps.c_str(); gnss_synchro3.System = *gps.c_str();
gnss_synchro4.System = *gal.c_str(); gnss_synchro4.System = *gal.c_str();
gnss_synchro5.System = *gps.c_str(); gnss_synchro5.System = *gps.c_str();
gnss_synchro6.System = *glo.c_str();
std::memcpy(static_cast<void*>(gnss_synchro.Signal), x5.c_str(), 3); std::memcpy((void*)gnss_synchro.Signal, x5.c_str(), 3);
std::memcpy(static_cast<void*>(gnss_synchro2.Signal), s2.c_str(), 3); std::memcpy((void*)gnss_synchro2.Signal, s2.c_str(), 3);
std::memcpy(static_cast<void*>(gnss_synchro3.Signal), c1.c_str(), 3); std::memcpy((void*)gnss_synchro3.Signal, c1.c_str(), 3);
std::memcpy(static_cast<void*>(gnss_synchro4.Signal), x5.c_str(), 3); std::memcpy((void*)gnss_synchro4.Signal, x5.c_str(), 3);
std::memcpy(static_cast<void*>(gnss_synchro5.Signal), c1.c_str(), 3); std::memcpy((void*)gnss_synchro5.Signal, c1.c_str(), 3);
std::memcpy((void*)gnss_synchro6.Signal, c1.c_str(), 3);
gnss_synchro.Pseudorange_m = 20000000.0; gnss_synchro.Pseudorange_m = 20000000.0;
gnss_synchro2.Pseudorange_m = 20001010.0; gnss_synchro2.Pseudorange_m = 20001010.0;
gnss_synchro3.Pseudorange_m = 24002020.0; gnss_synchro3.Pseudorange_m = 24002020.0;
gnss_synchro4.Pseudorange_m = 20003010.1; gnss_synchro4.Pseudorange_m = 20003010.1;
gnss_synchro5.Pseudorange_m = 22003010.1; gnss_synchro5.Pseudorange_m = 22003010.1;
gnss_synchro6.Pseudorange_m = 22003010.1;
pseudoranges.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro)); pseudoranges.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro));
pseudoranges.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro2)); pseudoranges.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro2));
pseudoranges.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro3)); pseudoranges.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro3));
pseudoranges.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro4)); pseudoranges.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro4));
pseudoranges.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro5)); pseudoranges.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro5));
pseudoranges.insert(std::pair<int, Gnss_Synchro>(6, gnss_synchro5));
unsigned int ref_id = 1234; unsigned int ref_id = 1234;
unsigned int clock_steering_indicator = 0; unsigned int clock_steering_indicator = 0;
@ -376,10 +420,12 @@ TEST(RtcmTest, MSMCell)
gps_eph.i_satellite_PRN = gnss_synchro2.PRN; gps_eph.i_satellite_PRN = gnss_synchro2.PRN;
gal_eph.i_satellite_PRN = gnss_synchro.PRN; gal_eph.i_satellite_PRN = gnss_synchro.PRN;
glo_gnav_eph.i_satellite_PRN = gnss_synchro.PRN;
std::string MSM1 = rtcm->print_MSM_1(gps_eph, std::string MSM1 = rtcm->print_MSM_1(gps_eph,
{}, {},
gal_eph, gal_eph,
{},
obs_time, obs_time,
pseudoranges, pseudoranges,
ref_id, ref_id,
@ -397,14 +443,17 @@ TEST(RtcmTest, MSMCell)
EXPECT_EQ(0, MSM1_bin.substr(size_header + size_msg_length + 169, Nsat * Nsig).compare("001010101100")); // check cell mask EXPECT_EQ(0, MSM1_bin.substr(size_header + size_msg_length + 169, Nsat * Nsig).compare("001010101100")); // check cell mask
std::map<int, Gnss_Synchro> pseudoranges2; std::map<int, Gnss_Synchro> pseudoranges2;
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro6));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro5)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro5));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro4)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro4));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro3)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro3));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro2)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro2));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(6, gnss_synchro));
std::string MSM1_2 = rtcm->print_MSM_1(gps_eph, std::string MSM1_2 = rtcm->print_MSM_1(gps_eph,
{}, {},
gal_eph, gal_eph,
{},
obs_time, obs_time,
pseudoranges2, pseudoranges2,
ref_id, ref_id,
@ -416,22 +465,23 @@ TEST(RtcmTest, MSMCell)
std::string MSM1_bin_2 = rtcm->binary_data_to_bin(MSM1_2); std::string MSM1_bin_2 = rtcm->binary_data_to_bin(MSM1_2);
EXPECT_EQ(0, MSM1_bin_2.substr(size_header + size_msg_length + 169, Nsat * Nsig).compare("001010101100")); // check cell mask EXPECT_EQ(0, MSM1_bin_2.substr(size_header + size_msg_length + 169, Nsat * Nsig).compare("001010101100")); // check cell mask
Gnss_Synchro gnss_synchro6; Gnss_Synchro gnss_synchro7;
gnss_synchro6.PRN = 10; gnss_synchro7.PRN = 10;
gnss_synchro6.System = *gps.c_str(); gnss_synchro7.System = *gps.c_str();
std::memcpy(static_cast<void*>(gnss_synchro6.Signal), s2.c_str(), 3); std::memcpy((void*)gnss_synchro7.Signal, s2.c_str(), 3);
gnss_synchro6.Pseudorange_m = 24000000.0; gnss_synchro7.Pseudorange_m = 24000000.0;
std::map<int, Gnss_Synchro> pseudoranges3; std::map<int, Gnss_Synchro> pseudoranges3;
pseudoranges3.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro)); pseudoranges3.insert(std::pair<int, Gnss_Synchro>(1, gnss_synchro));
pseudoranges3.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro2)); pseudoranges3.insert(std::pair<int, Gnss_Synchro>(2, gnss_synchro2));
pseudoranges3.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro6)); pseudoranges3.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro7));
pseudoranges3.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro4)); pseudoranges3.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro4));
pseudoranges3.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro5)); pseudoranges3.insert(std::pair<int, Gnss_Synchro>(5, gnss_synchro5));
std::string MSM1_3 = rtcm->print_MSM_1(gps_eph, std::string MSM1_3 = rtcm->print_MSM_1(gps_eph,
{}, {},
gal_eph, gal_eph,
{},
obs_time, obs_time,
pseudoranges3, pseudoranges3,
ref_id, ref_id,
@ -498,7 +548,7 @@ TEST(RtcmTest, MSM1)
gps_eph.i_satellite_PRN = gnss_synchro.PRN; gps_eph.i_satellite_PRN = gnss_synchro.PRN;
std::string MSM1 = rtcm->print_MSM_1(gps_eph, std::string MSM1 = rtcm->print_MSM_1(gps_eph,
{}, {}, {}, {}, {},
obs_time, obs_time,
pseudoranges, pseudoranges,
ref_id, ref_id,
@ -545,7 +595,7 @@ TEST(RtcmTest, MSM1)
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro2)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(3, gnss_synchro2));
pseudoranges2.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro)); pseudoranges2.insert(std::pair<int, Gnss_Synchro>(4, gnss_synchro));
std::string MSM1_2 = rtcm->print_MSM_1(gps_eph, std::string MSM1_2 = rtcm->print_MSM_1(gps_eph,
{}, {}, {}, {}, {},
obs_time, obs_time,
pseudoranges2, pseudoranges2,
ref_id, ref_id,

View File

@ -1,6 +1,6 @@
/*! /*!
* \file gps_l1_ca_dll_pll_tracking_test.cc * \file gps_l1_ca_dll_pll_tracking_test.cc
* \brief This class implements a tracking test for Galileo_E5a_DLL_PLL_Tracking * \brief This class implements a telemetry decoder test for GPS_L1_CA_Telemetry_Decoder
* implementation based on some input parameters. * implementation based on some input parameters.
* \author Javier Arribas, 2015. jarribas(at)cttc.es * \author Javier Arribas, 2015. jarribas(at)cttc.es
* *
@ -477,4 +477,3 @@ TEST_F(GpsL1CATelemetryDecoderTest, ValidationOfResults)
std::cout << "Test completed in " << elapsed_seconds.count() * 1e6 << " microseconds" << std::endl; std::cout << "Test completed in " << elapsed_seconds.count() * 1e6 << " microseconds" << std::endl;
} }

View File

@ -0,0 +1,76 @@
/*!
* \file code_generation_test.cc
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <complex>
#include <ctime>
#include "gps_sdr_signal_processing.h"
#include "gnss_signal_processing.h"
#include <complex>
#include <ctime>
#include "gnss_signal_processing.h"
#include "glonass_gnav_almanac.h"
// See A 3.2.3
TEST(GlonassGnavAlmanacTest, SatellitePosition)
{
double N_i = 615; // [days]
double t_i = 33300.0; // [seconds]
double Xoi = 10947.021572; // [km]
double Yoi = 13078.978287; // [km]
double Zoi = 18922.063362; // [km]
double Vxoi = -3.375497; // [m/s]
double Vyoi = -0.161453; // [Кm/s]
double Vzoi = 2.060844; // [Кm/s]
double N_A = 615; // [days]
Glonass_Gnav_Almanac gnav_almanac;
gnav_almanac.d_lambda_n_A = -0.189986229; // [half cycles]
gnav_almanac.d_t_lambda_n_A = 27122.09375; // [second]
gnav_almanac.d_Delta_i_n_A = 0.011929512; // [half cycle]
gnav_almanac.d_Delta_T_n_A = -2655.76171875; // [seconds]
gnav_almanac.d_Delta_T_n_A_dot = 0.000549316; // [Secjnds/cycle2]
gnav_almanac.d_epsilon_n_A = 0.001482010; // [unitless]
gnav_almanac.d_omega_n_A = 0.440277100; // [Half cycle]
gnav_almanac.satellite_position(N_A, N_i, t_i);
ASSERT_TRUE(gnav_almanac.d_satpos_Xo - Xoi < DBL_EPSILON );
ASSERT_TRUE(gnav_almanac.d_satpos_Yo - Yoi < DBL_EPSILON );
ASSERT_TRUE(gnav_almanac.d_satpos_Zo - Zoi < DBL_EPSILON );
ASSERT_TRUE(gnav_almanac.d_satvel_Xo - Vxoi < DBL_EPSILON );
ASSERT_TRUE(gnav_almanac.d_satvel_Yo - Vyoi < DBL_EPSILON );
ASSERT_TRUE(gnav_almanac.d_satvel_Zo - Vzoi < DBL_EPSILON );
}

View File

@ -0,0 +1,65 @@
/*!
* \file code_generation_test.cc
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <complex>
#include <ctime>
#include <iostream>
#include "gnss_signal_processing.h"
#include "glonass_gnav_ephemeris.h"
TEST(GlonassGnavEphemerisTest, ComputeGlonassTime)
{
Glonass_Gnav_Ephemeris gnav_eph;
gnav_eph.d_yr = 2016;
gnav_eph.d_N_T = 367;
boost::posix_time::time_duration t(0, 0, 7560);
boost::gregorian::date d(gnav_eph.d_yr, 1, 1);
boost::gregorian::days d2(gnav_eph.d_N_T);
d = d + d2;
boost::gregorian::date expected_gdate;
boost::posix_time::time_duration expected_gtime;
boost::posix_time::ptime gtime = gnav_eph.compute_GLONASS_time(7560);
expected_gdate = gtime.date();
expected_gtime = gtime.time_of_day();
// Perform assertions of decoded fields
ASSERT_TRUE(expected_gdate.year() - d.year() < FLT_EPSILON );
ASSERT_TRUE(expected_gdate.month() - d.month() < FLT_EPSILON );
ASSERT_TRUE(expected_gdate.day() - d.day() < FLT_EPSILON );
ASSERT_TRUE(expected_gtime.hours() - t.hours() < FLT_EPSILON );
ASSERT_TRUE(expected_gtime.minutes() - t.minutes() < FLT_EPSILON );
ASSERT_TRUE(expected_gtime.seconds() - t.seconds() < FLT_EPSILON );
}

View File

@ -0,0 +1,243 @@
/*!
* \file glonass_gnav_navigation_message_test.cc
* \brief This file implements tests for the decoding of the GLONASS GNAV navigation message
* \note Code added as part of GSoC 2017 program
* \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
* \see <a href="http://russianspacesystems.ru/wp-content/uploads/2016/08/ICD_GLONASS_eng_v5.1.pdf">GLONASS ICD</a>
*
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2015 (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 <http://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include <complex>
#include <ctime>
#include <complex>
#include <ctime>
#include "gnss_signal_processing.h"
#include "glonass_gnav_navigation_message.h"
/*!
* \brief Testing CRC computation for GLONASS GNAV data bits of a string
* \test The provided string was generated with a version of MATLAB GNSS-SDR that
* the author coded to perform proper decoding of GLONASS GNAV signals.
*/
TEST(GlonassGnavNavigationMessageTest, CRCTest)
{
// Variables declarations in code
bool test_result;
std::bitset<GLONASS_GNAV_STRING_BITS> string_bits (std::string ("0010100100001100000000000000000000000000110011110001100000000000000001100100011000000"));
Glonass_Gnav_Navigation_Message gnav_nav_message;
gnav_nav_message.reset();
// Call function to test
test_result = gnav_nav_message.CRC_test(string_bits);
// Check results in unit test assetions
ASSERT_TRUE(test_result);
}
/*!
* \brief Testing string decoding for GLONASS GNAV messages
* \test The provided string (str1.....str15) was generated with a version of
* MATLAB GNSS-SDR that the author coded to perform proper decoding of GLONASS
* GNAV signals. The same assumption is to be applied for ephemeris and almanac
* data provided.
*/
TEST(GlonassGnavNavigationMessageTest, String1Decoder)
{
// Variable declarations
std::string str1("0000100000001000011001000011111011010101110100000010101011000100011010101011000101111");
Glonass_Gnav_Navigation_Message gnav_nav_message;
Glonass_Gnav_Ephemeris gnav_ephemeris;
// Fill out ephemeris values for truth
gnav_ephemeris.d_P_1 = 15;
gnav_ephemeris.d_t_k = 7560;
gnav_ephemeris.d_VXn = -0.490900039672852;
gnav_ephemeris.d_AXn = 0;
gnav_ephemeris.d_Xn = -11025.6669921875;
// Call target test method
gnav_nav_message.string_decoder(str1);
// Perform assertions of decoded fields
ASSERT_TRUE(gnav_ephemeris.d_P_1 - gnav_nav_message.gnav_ephemeris.d_P_1 < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_t_k - gnav_nav_message.gnav_ephemeris.d_t_k < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_VXn - gnav_nav_message.gnav_ephemeris.d_VXn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_AXn - gnav_nav_message.gnav_ephemeris.d_AXn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_Xn - gnav_nav_message.gnav_ephemeris.d_Xn < FLT_EPSILON );
}
/*!
* \brief Testing string decoding for GLONASS GNAV messages
* \test The provided string (str1.....str15) was generated with a version of
* MATLAB GNSS-SDR that the author coded to perform proper decoding of GLONASS
* GNAV signals. The same assumption is to be applied for ephemeris and almanac
* data provided.
*/
TEST(GlonassGnavNavigationMessageTest, String2Decoder)
{
// Variable declarations
std::string str2("0001000010001001000001010101100001011001011000000010101100110000001011110000110011110");
Glonass_Gnav_Navigation_Message gnav_nav_message;
Glonass_Gnav_Ephemeris gnav_ephemeris;
// Fill out ephemeris values for truth
gnav_ephemeris.d_B_n = 0;
gnav_ephemeris.d_P_2 = 1;
gnav_ephemeris.d_t_b = 8100;
gnav_ephemeris.d_VYn = -2.69022750854492;
gnav_ephemeris.d_AYn = 0;
gnav_ephemeris.d_Yn = -11456.7348632812;
// Call target test method
gnav_nav_message.flag_ephemeris_str_1 = true;
gnav_nav_message.gnav_ephemeris.d_P_1 = 15;
gnav_nav_message.string_decoder(str2);
// Perform assertions of decoded fields
ASSERT_TRUE(gnav_ephemeris.d_B_n - gnav_nav_message.gnav_ephemeris.d_B_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_P_2 - gnav_nav_message.gnav_ephemeris.d_P_2 < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_t_b - gnav_nav_message.gnav_ephemeris.d_t_b < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_VYn - gnav_nav_message.gnav_ephemeris.d_VYn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_AYn - gnav_nav_message.gnav_ephemeris.d_AYn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_Yn - gnav_nav_message.gnav_ephemeris.d_Yn < FLT_EPSILON );
}
/*!
* \brief Testing string decoding for GLONASS GNAV messages
* \test The provided string (str1.....str15) was generated with a version of
* MATLAB GNSS-SDR that the author coded to perform proper decoding of GLONASS
* GNAV signals. The same assumption is to be applied for ephemeris and almanac
* data provided.
*/
TEST(GlonassGnavNavigationMessageTest, String3Decoder)
{
// Variable declarations
std::string str3("0001110000000001001101001110100011111011010011001101001101110110010011110011100100011");
Glonass_Gnav_Navigation_Message gnav_nav_message;
Glonass_Gnav_Ephemeris gnav_ephemeris;
// Fill out ephemeris values for truth
gnav_ephemeris.d_P_3 = 1;
gnav_ephemeris.d_gamma_n = 1.81898940354586e-12;
gnav_ephemeris.d_P = 3;
gnav_ephemeris.d_l3rd_n = 0;
gnav_ephemeris.d_VZn = -1.82016849517822;
gnav_ephemeris.d_AZn = -2.79396772384644e-09;
gnav_ephemeris.d_Zn = 19929.2377929688;
// Call target test method
gnav_nav_message.string_decoder(str3);
// Perform assertions of decoded fields
ASSERT_TRUE(gnav_ephemeris.d_P_3 - gnav_nav_message.gnav_ephemeris.d_P_3 < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_gamma_n - gnav_nav_message.gnav_ephemeris.d_gamma_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_P - gnav_nav_message.gnav_ephemeris.d_P < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_l3rd_n - gnav_nav_message.gnav_ephemeris.d_l3rd_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_VZn - gnav_nav_message.gnav_ephemeris.d_VZn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_AZn - gnav_nav_message.gnav_ephemeris.d_AZn < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_Zn - gnav_nav_message.gnav_ephemeris.d_Zn < FLT_EPSILON );
}
/*!
* \brief Testing string decoding for GLONASS GNAV messages
* \test The provided string (str1.....str15) was generated with a version of
* MATLAB GNSS-SDR that the author coded to perform proper decoding of GLONASS
* GNAV signals. The same assumption is to be applied for ephemeris and almanac
* data provided.
*/
TEST(GlonassGnavNavigationMessageTest, String4Decoder)
{
// Variable declarations
std::string str4("0010010000101011100100000100000100000000000000000000011000100100001100101010100011101");
Glonass_Gnav_Navigation_Message gnav_nav_message;
Glonass_Gnav_Ephemeris gnav_ephemeris;
// Fill out ephemeris values for truth
gnav_ephemeris.d_tau_n = -8.30907374620438e-05;
gnav_ephemeris.d_Delta_tau_n = 9.31322574615479e-10;
gnav_ephemeris.d_E_n = 0;
gnav_ephemeris.d_P_4 = 0;
gnav_ephemeris.d_F_T = 6;
gnav_ephemeris.d_N_T = 268;
gnav_ephemeris.d_n = 21;
gnav_ephemeris.d_M = 1;
// Call target test method
gnav_nav_message.string_decoder(str4);
// Perform assertions of decoded fields
ASSERT_TRUE(gnav_ephemeris.d_tau_n - gnav_nav_message.gnav_ephemeris.d_tau_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_Delta_tau_n - gnav_nav_message.gnav_ephemeris.d_Delta_tau_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_E_n - gnav_nav_message.gnav_ephemeris.d_E_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_P_4 - gnav_nav_message.gnav_ephemeris.d_P_4 < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_F_T - gnav_nav_message.gnav_ephemeris.d_F_T < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_N_T - gnav_nav_message.gnav_ephemeris.d_N_T < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_n - gnav_nav_message.gnav_ephemeris.d_n < FLT_EPSILON );
ASSERT_TRUE(gnav_ephemeris.d_M - gnav_nav_message.gnav_ephemeris.d_M < FLT_EPSILON );
}
/*!
* \brief Testing string decoding for GLONASS GNAV messages
* \test The provided string (str1.....str15) was generated with a version of
* MATLAB GNSS-SDR that the author coded to perform proper decoding of GLONASS
* GNAV signals. The same assumption is to be applied for ephemeris and almanac
* data provided.
*/
TEST(GlonassGnavNavigationMessageTest, String5Decoder)
{
// Variable declarations
std::string str5("0010100100001100000000000000000000000000110011110001100000000000000001100100011000000");
Glonass_Gnav_Navigation_Message gnav_nav_message;
Glonass_Gnav_Utc_Model gnav_utc_model;
// Fill out ephemeris values for truth
gnav_utc_model.d_N_A = 268;
gnav_utc_model.d_tau_c = 9.6391886472702e-08;
gnav_utc_model.d_N_4 = 6;
gnav_utc_model.d_tau_gps = 9.313225746154785e-08;
// Call target test method
gnav_nav_message.string_decoder(str5);
// Perform assertions of decoded fields
ASSERT_TRUE(gnav_utc_model.d_N_A - gnav_nav_message.gnav_utc_model.d_N_A < FLT_EPSILON );
ASSERT_TRUE(gnav_utc_model.d_tau_c - gnav_nav_message.gnav_utc_model.d_tau_c < FLT_EPSILON );
ASSERT_TRUE(gnav_utc_model.d_N_4 - gnav_nav_message.gnav_utc_model.d_N_4 < FLT_EPSILON );
ASSERT_TRUE(gnav_utc_model.d_tau_gps - gnav_nav_message.gnav_utc_model.d_tau_gps < FLT_EPSILON );
}
std::string str6("0011010100110100001100111100011100001101011000000110101111001000000101100011111011001");
std::string str7("0011101101010001000010000110101111110000101101001011111110101110100010111100010001101");
std::string str8("0100010100111000000001111110001101000000110000001000100111011100001010101111010011010");
std::string str9("0100111010001001011100010000010100010101111101001011111110101011100010100101000110101");
std::string str10("0101010101000000000011101111111101111001011000001000101010001100001111000110101111110");
std::string str11("0101110111011011011100011001111011101111001101001011111111000110100100000110010001111");
std::string str12("0110010101001100000011110110100110100100010100001000111110000100001110001010111000001");
std::string str13("0110111011100100111110100001000110100010011101001011111110100100101010011010001101001");
std::string str14("0111010101010000000100011000011110100110111100001110110100001000001111001101010000101");
std::string str15("0111101110101010001110101010100111101100001101001011111111100010101010011001010011101");

View File

@ -68,6 +68,7 @@ for N=1:1:channels
trackResults(N).Q_L = zeros(1,length(GNSS_tracking(N).L)); trackResults(N).Q_L = zeros(1,length(GNSS_tracking(N).L));
trackResults(N).Q_VL = zeros(1,length(GNSS_tracking(N).VL)); trackResults(N).Q_VL = zeros(1,length(GNSS_tracking(N).VL));
trackResults(N).PRN = GNSS_tracking(N).PRN.'; trackResults(N).PRN = GNSS_tracking(N).PRN.';
trackResults(N).CNo = GNSS_tracking(N).CN0_SNV_dB_Hz.';
% Use original MATLAB tracking plot function % Use original MATLAB tracking plot function
settings.numberOfChannels = channels; settings.numberOfChannels = channels;

View File

@ -0,0 +1,74 @@
% /*!
% * \file glonass_ca_dll_pll_plot_sample.m
% * \brief Read GNSS-SDR Tracking dump binary file using the provided
% function and plot some internal variables
% * \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
% * -------------------------------------------------------------------------
% *
% * Copyright (C) 2010-2011 (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 <http://www.gnu.org/licenses/>.
% *
% * -------------------------------------------------------------------------
% */
close all;
clear all;
if ~exist('glonass_ca_dll_pll_read_tracking_dump.m','file')
addpath('./libs')
end
samplingFreq = 6625000; %[Hz]
channels = 5;
first_channel = 0;
path = '/archive/'; %% CHANGE THIS PATH
for N=1:1:channels
tracking_log_path = [path 'glo_tracking_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE epl_tracking_ch_ BY YOUR dump_filename
GNSS_tracking(N)= glonass_ca_dll_pll_read_tracking_dump(tracking_log_path);
end
% GNSS-SDR format conversion to MATLAB GPS receiver
for N=1:1:channels
trackResults(N).status = 'T'; %fake track
trackResults(N).codeFreq = GNSS_tracking(N).code_freq_hz.';
trackResults(N).carrFreq = GNSS_tracking(N).carrier_freq_hz.';
trackResults(N).dllDiscr = GNSS_tracking(N).code_error.';
trackResults(N).dllDiscrFilt = GNSS_tracking(N).code_nco.';
trackResults(N).pllDiscr = GNSS_tracking(N).carr_error.';
trackResults(N).pllDiscrFilt = GNSS_tracking(N).carr_nco.';
trackResults(N).I_P = GNSS_tracking(N).prompt_I.';
trackResults(N).Q_P = GNSS_tracking(N).prompt_Q.';
trackResults(N).I_E = GNSS_tracking(N).E.';
trackResults(N).I_L = GNSS_tracking(N).L.';
trackResults(N).Q_E = zeros(1,length(GNSS_tracking(N).E));
trackResults(N).Q_L = zeros(1,length(GNSS_tracking(N).E));
trackResults(N).CNo = GNSS_tracking(N).CN0_SNV_dB_Hz.';
trackResults(N).PRN = ones(1,length(GNSS_tracking(N).E));
% Use original MATLAB tracking plot function
settings.numberOfChannels = channels;
settings.msToProcess = length(GNSS_tracking(N).E);
plotTracking(N,trackResults,settings);
end

View File

@ -35,14 +35,14 @@ if ~exist('gps_l1_ca_dll_pll_read_tracking_dump.m','file')
end end
samplingFreq = 2600000; %[Hz] samplingFreq = 6625000; %[Hz]
channels = 2; channels = 5;
first_channel = 0; first_channel = 0;
path = '/home/javier/git/gnss-sdr/build/'; %% CHANGE THIS PATH path = '/archive/'; %% CHANGE THIS PATH
for N=1:1:channels for N=1:1:channels
tracking_log_path = [path 'tracking_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE epl_tracking_ch_ BY YOUR dump_filename tracking_log_path = [path 'glo_tracking_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE epl_tracking_ch_ BY YOUR dump_filename
GNSS_tracking(N)= gps_l1_ca_dll_pll_read_tracking_dump(tracking_log_path); GNSS_tracking(N)= gps_l1_ca_dll_pll_read_tracking_dump(tracking_log_path);
end end
@ -65,6 +65,7 @@ for N=1:1:channels
trackResults(N).Q_E = zeros(1,length(GNSS_tracking(N).E)); trackResults(N).Q_E = zeros(1,length(GNSS_tracking(N).E));
trackResults(N).Q_L = zeros(1,length(GNSS_tracking(N).E)); trackResults(N).Q_L = zeros(1,length(GNSS_tracking(N).E));
trackResults(N).PRN = ones(1,length(GNSS_tracking(N).E)); trackResults(N).PRN = ones(1,length(GNSS_tracking(N).E));
trackResults(N).CNo = GNSS_tracking(N).CN0_SNV_dB_Hz.';
% Use original MATLAB tracking plot function % Use original MATLAB tracking plot function
settings.numberOfChannels = channels; settings.numberOfChannels = channels;

View File

@ -0,0 +1,191 @@
% /*!
% * \file glonass_ca_dll_pll_read_tracking_dump.m
% * \brief Read GNSS-SDR Tracking dump binary file into MATLAB.
% * \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
% * -------------------------------------------------------------------------
% *
% * Copyright (C) 2010-2011 (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 <http://www.gnu.org/licenses/>.
% *
% * -------------------------------------------------------------------------
% */
function [GNSS_tracking] = glonass_ca_dll_pll_read_tracking_dump (filename, count)
%% usage: gps_l1_ca_dll_pll_read_tracking_dump_64bits (filename, [count])
%%
%% open GNSS-SDR tracking binary log file .dat and return the contents
%%
narginchk (1,2);
num_float_vars=5;
num_unsigned_long_int_vars=1;
num_double_vars=11;
num_unsigned_int_vars=1;
double_size_bytes=8;
unsigned_long_int_size_bytes=8;
float_size_bytes=4;
long_int_size_bytes=4;
skip_bytes_each_read=float_size_bytes*num_float_vars+unsigned_long_int_size_bytes*num_unsigned_long_int_vars+double_size_bytes*num_double_vars+long_int_size_bytes*num_unsigned_int_vars;
bytes_shift=0;
if (nargin < 2)
%count = Inf;
file_stats = dir(filename);
%round num bytes to read to integer number of samples (to protect the script from binary
%dump end file transitory)
count = (file_stats.bytes - mod(file_stats.bytes,skip_bytes_each_read))/skip_bytes_each_read;
end
%loops_counter = fread (f, count, 'uint32',4*12);
f = fopen (filename, 'rb');
if (f < 0)
else
v1 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v2 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v3 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v4 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v5 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved unsigned_long_int
v6 = fread (f, count, 'uint64',skip_bytes_each_read-unsigned_long_int_size_bytes);
bytes_shift=bytes_shift+unsigned_long_int_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v7 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v8 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v9 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v10 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v11 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v12 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v13 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v14 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v15 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v16 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v17 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v18 = fread (f, count, 'uint32',skip_bytes_each_read-double_size_bytes);
fclose (f);
%%%%%%%% output vars %%%%%%%%
% // EPR
% d_dump_file.write(reinterpret_cast<char*>(&tmp_E), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&tmp_P), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&tmp_L), sizeof(float));
% // PROMPT I and Q (to analyze navigation symbols)
% d_dump_file.write(reinterpret_cast<char*>(&prompt_I), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&prompt_Q), sizeof(float));
% // PRN start sample stamp
% //tmp_float=(float)d_sample_counter;
% d_dump_file.write(reinterpret_cast<char*>(&d_sample_counter), sizeof(unsigned long int));
% // accumulated carrier phase
% d_dump_file.write(reinterpret_cast<char*>(&d_acc_carrier_phase_rad), sizeof(double));
%
% // carrier and code frequency
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_code_freq_chips), sizeof(double));
%
% //PLL commands
% d_dump_file.write(reinterpret_cast<char*>(&carr_phase_error_secs_Ti), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
%
% //DLL commands
% d_dump_file.write(reinterpret_cast<char*>(&code_error_chips_Ti), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&code_error_filt_chips), sizeof(double));
%
% // CN0 and carrier lock test
% d_dump_file.write(reinterpret_cast<char*>(&d_CN0_SNV_dB_Hz), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_lock_test), sizeof(double));
%
% // AUX vars (for debug purposes)
% tmp_double = d_rem_code_phase_samples;
% d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
% tmp_double = static_cast<double>(d_sample_counter + d_current_prn_length_samples);
% d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
% // PRN
% unsigned int prn_ = d_acquisition_gnss_synchro->PRN;
% d_dump_file.write(reinterpret_cast<char*>(&prn_), sizeof(unsigned int));
E=v1;
P=v2;
L=v3;
prompt_I=v4;
prompt_Q=v5;
PRN_start_sample=v6;
acc_carrier_phase_rad=v7;
carrier_freq_hz=v8;
code_freq_hz=v9;
carr_error=v10;
carr_nco=v11;
code_error=v12;
code_nco=v13;
CN0_SNV_dB_Hz=v14;
carrier_lock_test=v15;
var1=v16;
var2=v17;
PRN=v18;
GNSS_tracking.E=E;
GNSS_tracking.P=P;
GNSS_tracking.L=L;
GNSS_tracking.prompt_I=prompt_I;
GNSS_tracking.prompt_Q=prompt_Q;
GNSS_tracking.PRN_start_sample=PRN_start_sample;
GNSS_tracking.acc_carrier_phase_rad=acc_carrier_phase_rad;
GNSS_tracking.carrier_freq_hz=carrier_freq_hz;
GNSS_tracking.code_freq_hz=code_freq_hz;
GNSS_tracking.carr_error=carr_error;
GNSS_tracking.carr_nco=carr_nco;
GNSS_tracking.code_error=code_error;
GNSS_tracking.code_nco=code_nco;
GNSS_tracking.CN0_SNV_dB_Hz=CN0_SNV_dB_Hz;
GNSS_tracking.carrier_lock_test=carrier_lock_test;
GNSS_tracking.d_rem_code_phase_samples=var1;
GNSS_tracking.var2=var2;
GNSS_tracking.PRN=PRN;
end

View File

@ -0,0 +1,193 @@
% /*!
% * \file glonass_l1_ca_dll_pll_read_tracking_dump.m
% * \brief Read GNSS-SDR Tracking dump binary file into MATLAB.
% * \author Damian Miralles, 2017. dmiralles2009(at)gmail.com
% * -------------------------------------------------------------------------
% *
% * Copyright (C) 2010-2011 (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 <http://www.gnu.org/licenses/>.
% *
% * -------------------------------------------------------------------------
% */
function [GNSS_tracking] = glonass_l1_ca_dll_pll_read_tracking_dump (filename, count)
%% usage: glonass_l1_ca_dll_pll_read_tracking_dump_64bits (filename, [count])
%%
%% open GNSS-SDR tracking binary log file .dat and return the contents
%%
m = nargchk (1,2,nargin);
num_float_vars=5;
num_unsigned_long_int_vars=1;
num_double_vars=11;
num_unsigned_int_vars=1;
double_size_bytes=8;
unsigned_long_int_size_bytes=8;
float_size_bytes=4;
long_int_size_bytes=4;
skip_bytes_each_read=float_size_bytes*num_float_vars+unsigned_long_int_size_bytes*num_unsigned_long_int_vars+double_size_bytes*num_double_vars+long_int_size_bytes*num_unsigned_int_vars;
bytes_shift=0;
if (m)
usage (m);
end
if (nargin < 2)
%count = Inf;
file_stats = dir(filename);
%round num bytes to read to integer number of samples (to protect the script from binary
%dump end file transitory)
count = (file_stats.bytes - mod(file_stats.bytes,skip_bytes_each_read))/skip_bytes_each_read;
end
%loops_counter = fread (f, count, 'uint32',4*12);
f = fopen (filename, 'rb');
if (f < 0)
else
v1 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v2 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v3 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v4 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved float
v5 = fread (f, count, 'float',skip_bytes_each_read-float_size_bytes);
bytes_shift=bytes_shift+float_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved unsigned_long_int
v6 = fread (f, count, 'uint64',skip_bytes_each_read-unsigned_long_int_size_bytes);
bytes_shift=bytes_shift+unsigned_long_int_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v7 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v8 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v9 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v10 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v11 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v12 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v13 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v14 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v15 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v16 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v17 = fread (f, count, 'float64',skip_bytes_each_read-double_size_bytes);
bytes_shift=bytes_shift+double_size_bytes;
fseek(f,bytes_shift,'bof'); % move to next interleaved double
v18 = fread (f, count, 'uint32',skip_bytes_each_read-double_size_bytes);
fclose (f);
%%%%%%%% output vars %%%%%%%%
% // EPR
% d_dump_file.write(reinterpret_cast<char*>(&tmp_E), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&tmp_P), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&tmp_L), sizeof(float));
% // PROMPT I and Q (to analyze navigation symbols)
% d_dump_file.write(reinterpret_cast<char*>(&prompt_I), sizeof(float));
% d_dump_file.write(reinterpret_cast<char*>(&prompt_Q), sizeof(float));
% // PRN start sample stamp
% //tmp_float=(float)d_sample_counter;
% d_dump_file.write(reinterpret_cast<char*>(&d_sample_counter), sizeof(unsigned long int));
% // accumulated carrier phase
% d_dump_file.write(reinterpret_cast<char*>(&d_acc_carrier_phase_rad), sizeof(double));
%
% // carrier and code frequency
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_code_freq_chips), sizeof(double));
%
% //PLL commands
% d_dump_file.write(reinterpret_cast<char*>(&carr_phase_error_secs_Ti), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_doppler_hz), sizeof(double));
%
% //DLL commands
% d_dump_file.write(reinterpret_cast<char*>(&code_error_chips_Ti), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&code_error_filt_chips), sizeof(double));
%
% // CN0 and carrier lock test
% d_dump_file.write(reinterpret_cast<char*>(&d_CN0_SNV_dB_Hz), sizeof(double));
% d_dump_file.write(reinterpret_cast<char*>(&d_carrier_lock_test), sizeof(double));
%
% // AUX vars (for debug purposes)
% tmp_double = d_rem_code_phase_samples;
% d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
% tmp_double = static_cast<double>(d_sample_counter + d_current_prn_length_samples);
% d_dump_file.write(reinterpret_cast<char*>(&tmp_double), sizeof(double));
% // PRN
% unsigned int prn_ = d_acquisition_gnss_synchro->PRN;
% d_dump_file.write(reinterpret_cast<char*>(&prn_), sizeof(unsigned int));
E=v1;
P=v2;
L=v3;
prompt_I=v4;
prompt_Q=v5;
PRN_start_sample=v6;
acc_carrier_phase_rad=v7;
carrier_doppler_hz=v8;
code_freq_hz=v9;
carr_error=v10;
carr_nco=v11;
code_error=v12;
code_nco=v13;
CN0_SNV_dB_Hz=v14;
carrier_lock_test=v15;
var1=v16;
var2=v17;
PRN=v18;
GNSS_tracking.E=E;
GNSS_tracking.P=P;
GNSS_tracking.L=L;
GNSS_tracking.prompt_I=prompt_I;
GNSS_tracking.prompt_Q=prompt_Q;
GNSS_tracking.PRN_start_sample=PRN_start_sample;
GNSS_tracking.acc_carrier_phase_rad=acc_carrier_phase_rad;
GNSS_tracking.carrier_doppler_hz=carrier_doppler_hz;
GNSS_tracking.code_freq_hz=code_freq_hz;
GNSS_tracking.carr_error=carr_error;
GNSS_tracking.carr_nco=carr_nco;
GNSS_tracking.code_error=code_error
GNSS_tracking.code_nco=code_nco;
GNSS_tracking.CN0_SNV_dB_Hz=CN0_SNV_dB_Hz;
GNSS_tracking.carrier_lock_test=carrier_lock_test;
GNSS_tracking.d_rem_code_phase_samples=var1;
GNSS_tracking.var2=var2;
GNSS_tracking.PRN=PRN;
end

View File

@ -54,15 +54,20 @@ for channelNr = channelList
%% Draw axes ============================================================== %% Draw axes ==============================================================
% Row 1 % Row 1
handles(1, 1) = subplot(3, 3, 1); handles(1, 1) = subplot(4, 3, 1);
handles(1, 2) = subplot(3, 3, [2 3]); handles(1, 2) = subplot(4, 3, [2 3]);
% Row 2 % Row 2
handles(2, 1) = subplot(3, 3, 4); handles(2, 1) = subplot(4, 3, 4);
handles(2, 2) = subplot(3, 3, [5 6]); handles(2, 2) = subplot(4, 3, [5 6]);
% Row 3 % Row 3
handles(3, 1) = subplot(3, 3, 7); handles(3, 1) = subplot(4, 3, 7);
handles(3, 2) = subplot(3, 3, 8); handles(3, 2) = subplot(4, 3, 8);
handles(3, 3) = subplot(3, 3, 9); handles(3, 3) = subplot(4, 3, 9);
% Row 4
handles(4, 1) = subplot(4, 3, 10);
handles(4, 2) = subplot(4, 3, 11);
handles(4, 3) = subplot(4, 3, 12);
%% Plot all figures ======================================================= %% Plot all figures =======================================================
@ -150,4 +155,34 @@ for channelNr = channelList
ylabel(handles(3, 3), 'Amplitude'); ylabel(handles(3, 3), 'Amplitude');
title (handles(3, 3), 'Filtered DLL discriminator'); title (handles(3, 3), 'Filtered DLL discriminator');
%----- CNo for signal----------------------------------
plot (handles(4, 1), timeAxisInSeconds, ...
trackResults(channelNr).CNo(1:settings.msToProcess), 'b');
grid (handles(4, 1));
axis (handles(4, 1), 'tight');
xlabel(handles(4, 1), 'Time (s)');
ylabel(handles(4, 1), 'CNo (dB-Hz)');
title (handles(4, 1), 'Carrier to Noise Ratio');
%----- Carrier Frequency --------------------------------
plot (handles(4, 2), timeAxisInSeconds, ...
trackResults(channelNr).carrFreq(1:settings.msToProcess), 'Color',[0.42 0.25 0.39]);
grid (handles(4, 2));
axis (handles(4, 2), 'tight');
xlabel(handles(4, 2), 'Time (s)');
ylabel(handles(4, 2), 'Freq (hz)');
title (handles(4, 2), 'Carrier Freq');
%----- Code Frequency----------------------------------
plot (handles(4, 3), timeAxisInSeconds, ...
trackResults(channelNr).codeFreq(1:settings.msToProcess), 'Color',[0.2 0.3 0.49]);
grid (handles(4, 3));
axis (handles(4, 3), 'tight');
xlabel(handles(4, 3), 'Time (s)');
ylabel(handles(4, 3), 'Freq (Hz)');
title (handles(4, 3), 'Code Freq');
end % for channelNr = channelList end % for channelNr = channelList