Applying code formatting rules

This commit is contained in:
Carles Fernandez 2019-01-28 02:29:43 +01:00
parent fa19b2e6a4
commit c561d7e799
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
51 changed files with 1760 additions and 2508 deletions

View File

@ -2,13 +2,13 @@
[![License: GPL v3](https://img.shields.io/badge/License-GPL%20v3-blue.svg)](https://www.gnu.org/licenses/gpl-3.0)
link to website: https://gnsssdrbeidoub1igsoc2018.wordpress.com/
**Welcome to GNSS-SDR!**
This program is a software-defined receiver which is able to process (that is, to perform detection, synchronization, demodulation and decoding of the navigation message, computation of observables and, finally, computation of position fixes) the following Global Navigation Satellite System's signals:
In the L1 band:
- 🛰 BeiDou B1I (centered at 1561.098 MHz) :white_check_mark:
- 🛰 GPS L1 C/A (centered at 1575.42 MHz) :white_check_mark:
- 🛰 Galileo E1b/c (centered at 1575.42 MHz) :white_check_mark:
- 🛰 GLONASS L1 C/A (centered at 1601.72 MHz) :white_check_mark:

View File

@ -5,8 +5,8 @@
[GNSS-SDR]
;######### GLOBAL OPTIONS ##################
;internal_fs_hz: Internal signal sampling frequency after the signal conditioning stage [Hz].
GNSS-SDR.internal_fs_hz=6625000
;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [Hz].
GNSS-SDR.internal_fs_sps=6625000
;######### CONTROL_THREAD CONFIG ############
ControlThread.wait_for_flowgraph=false
@ -54,7 +54,6 @@ Channel.signal=1R
Acquisition_1R.dump=false
Acquisition_1R.dump_filename=./acq_dump.dat
Acquisition_1R.item_type=cshort
Acquisition_1R.if=0
Acquisition_1R.sampled_ms=1
Acquisition_1R.implementation=GLONASS_L1_CA_PCPS_Acquisition
Acquisition_1R.threshold=0.008
@ -68,7 +67,6 @@ Acquisition_1R.tong_max_dwells=20
;######### TRACKING GLOBAL CONFIG ############
Tracking_1R.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking
Tracking_1R.item_type=cshort
Tracking_1R.if=0
Tracking_1R.dump=false
Tracking_1R.dump_filename=../data/epl_tracking_ch_
Tracking_1R.pll_bw_hz=40.0;
@ -78,7 +76,6 @@ Tracking_1R.order=3;
;######### TELEMETRY DECODER GPS CONFIG ############
TelemetryDecoder_1R.implementation=GLONASS_L1_CA_Telemetry_Decoder
TelemetryDecoder_1R.dump=false
TelemetryDecoder_1R.decimation_factor=1;
;######### OBSERVABLES CONFIG ############
Observables.implementation=Hybrid_Observables

View File

@ -1,110 +0,0 @@
; This is a GNSS-SDR configuration file
; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/
; You can define your own receiver and invoke it by doing
; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf
;
[GNSS-SDR]
;######### GLOBAL OPTIONS ##################
;internal_fs_sps: Internal signal sampling frequency after the signal conditioning stage [samples per second].
GNSS-SDR.internal_fs_sps=99375000
;######### CONTROL_THREAD CONFIG ############
ControlThread.wait_for_flowgraph=false
;######### SIGNAL_SOURCE CONFIG ############
SignalSource.implementation=File_Signal_Source
SignalSource.filename=/media/dmiralles/Seagate Backup Plus Drive/GNSS Data/Beidou_B1_IF_signal.bin
SignalSource.item_type=byte
SignalSource.sampling_frequency=99375000
SignalSource.samples=0
SignalSource.repeat=false
SignalSource.dump=false
SignalSource.enable_throttle_control=false
;######### SIGNAL_CONDITIONER CONFIG ############
SignalConditioner.implementation=Signal_Conditioner
DataTypeAdapter.implementation=Byte_To_Short
InputFilter.implementation=Freq_Xlating_Fir_Filter
InputFilter.input_item_type=short
InputFilter.output_item_type=gr_complex
InputFilter.taps_item_type=float
InputFilter.number_of_taps=5
InputFilter.number_of_bands=2
InputFilter.band1_begin=0.0
InputFilter.band1_end=0.70
InputFilter.band2_begin=0.80
InputFilter.band2_end=1.0
InputFilter.ampl1_begin=1.0
InputFilter.ampl1_end=1.0
InputFilter.ampl2_begin=0.0
InputFilter.ampl2_end=0.0
InputFilter.band1_error=1.0
InputFilter.band2_error=1.0
InputFilter.filter_type=bandpass
InputFilter.grid_density=16
InputFilter.sampling_frequency=99375000
InputFilter.IF=14580000
Resampler.implementation=Direct_Resampler
Resampler.sample_freq_in=99375000
Resampler.sample_freq_out=99375000
Resampler.item_type=gr_complex
;######### CHANNELS GLOBAL CONFIG ############
Channels_1C.count=8
Channels.in_acquisition=1
Channel.signal=1C
;######### ACQUISITION GLOBAL CONFIG ############
Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
Acquisition_1C.item_type=gr_complex
Acquisition_1C.coherent_integration_time_ms=1
Acquisition_1C.threshold=3.5
;Acquisition_1C.pfa=0.000001;
Acquisition_1C.doppler_max=14000
Acquisition_1C.doppler_step=100
Acquisition_1C.dump=true
Acquisition_1C.dump_filename=./gps_acq
Acquisition_1C.blocking=false;
Acquisition_1C.use_CFAR_algorithm=false
;######### TRACKING GLOBAL CONFIG ############
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
Tracking_1C.item_type=gr_complex
Tracking_1C.pll_bw_hz=30.0;
Tracking_1C.dll_bw_hz=3.0;
Tracking_1C.dump=true;
Tracking_1C.dump_filename=./epl_tracking_ch_
;######### TELEMETRY DECODER GPS CONFIG ############
TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder
TelemetryDecoder_1C.dump=false
;######### OBSERVABLES CONFIG ############
Observables.implementation=Hybrid_Observables
Observables.dump=true
Observables.dump_filename=./observables.dat
;######### PVT CONFIG ############
PVT.implementation=RTKLIB_PVT
PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic
PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX
PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad
PVT.output_rate_ms=100
PVT.display_rate_ms=500
PVT.dump_filename=./PVT
PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea;
PVT.flag_nmea_tty_port=false;
PVT.nmea_dump_devname=/dev/pts/4
PVT.flag_rtcm_server=false
PVT.flag_rtcm_tty_port=false
PVT.rtcm_dump_devname=/dev/pts/1
PVT.dump=false

View File

@ -16,7 +16,7 @@ ControlThread.wait_for_flowgraph=false
;######### SIGNAL_SOURCE CONFIG ############
SignalSource.implementation=File_Signal_Source
SignalSource.filename=/home/sergi/gnss/gnss-sdr/data/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE
SignalSource.filename=/archive/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat ; <- PUT YOUR FILE HERE
SignalSource.item_type=ishort
SignalSource.sampling_frequency=4000000
SignalSource.samples=0
@ -29,14 +29,13 @@ SignalSource.enable_throttle_control=false
;######### SIGNAL_CONDITIONER CONFIG ############
SignalConditioner.implementation=Signal_Conditioner
DataTypeAdapter.implementation=Ishort_To_Complex
DataTypeAdapter.implementation=Ishort_To_Cshort
InputFilter.implementation=Pass_Through
InputFilter.item_type=gr_complex
InputFilter.item_type=cshort
Resampler.implementation=Direct_Resampler
Resampler.sample_freq_in=4000000
Resampler.sample_freq_out=2000000
Resampler.item_type=gr_complex
Resampler.item_type=cshort
;######### CHANNELS GLOBAL CONFIG ############
Channels_1C.count=8
@ -46,19 +45,19 @@ Channel.signal=1C
;######### ACQUISITION GLOBAL CONFIG ############
Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
Acquisition_1C.item_type=gr_complex
Acquisition_1C.item_type=cshort
Acquisition_1C.coherent_integration_time_ms=1
Acquisition_1C.threshold=0.008
;Acquisition_1C.pfa=0.000001
Acquisition_1C.doppler_max=10000
Acquisition_1C.doppler_step=250
Acquisition_1C.dump=true
Acquisition_1C.dump=false
Acquisition_1C.dump_filename=./acq_dump.dat
Acquisition_1C.blocking=false;
;######### TRACKING GLOBAL CONFIG ############
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
Tracking_1C.item_type=gr_complex
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking
Tracking_1C.item_type=cshort
Tracking_1C.pll_bw_hz=40.0;
Tracking_1C.dll_bw_hz=4.0;
Tracking_1C.order=3;

View File

@ -1,56 +0,0 @@
[GNSS-SDR]
;######### GLOBAL OPTIONS ##################
GNSS-SDR.internal_fs_hz=2000000
;######### SIGNAL_SOURCE CONFIG ############
SignalSource.implementation=File_Signal_Source
SignalSource.filename=/home/sergi/gnss/gnss-sdr/data/2013_04_04_GNSS_SIGNAL_at_CTTC_SPAIN.dat
SignalSource.item_type=ishort
SignalSource.sampling_frequency=4000000
SignalSource.freq=1575420000
SignalSource.samples=0
;######### SIGNAL_CONDITIONER CONFIG ############
SignalConditioner.implementation=Signal_Conditioner
DataTypeAdapter.implementation=Ishort_To_Complex
InputFilter.implementation=Pass_Through
InputFilter.item_type=gr_complex
Resampler.implementation=Direct_Resampler
Resampler.sample_freq_in=4000000
Resampler.sample_freq_out=2000000
Resampler.item_type=gr_complex
;######### CHANNELS GLOBAL CONFIG ############
Channels_1C.count=8
Channels.in_acquisition=1
Channel.signal=1C
;######### ACQUISITION GLOBAL CONFIG ############
Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
Acquisition_1C.item_type=gr_complex
Acquisition_1C.threshold=0.008
Acquisition_1C.doppler_max=10000
Acquisition_1C.doppler_step=250
;######### TRACKING GLOBAL CONFIG ############
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
Tracking_1C.item_type=gr_complex
Tracking_1C.pll_bw_hz=40.0;
Tracking_1C.dll_bw_hz=4.0;
;######### TELEMETRY DECODER GPS CONFIG ############
TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder
;######### OBSERVABLES CONFIG ############
Observables.implementation=GPS_L1_CA_Observables
;######### PVT CONFIG ############
PVT.implementation=GPS_L1_CA_PVT
PVT.averaging_depth=100
PVT.flag_averaging=true
PVT.output_rate_ms=10
PVT.display_rate_ms=500

View File

@ -1,561 +0,0 @@
/*!
* \file rtklib_pvt.cc
* \brief Interface of a Position Velocity and Time computation block
* \author Javier Arribas, 2017. jarribas(at)cttc.es
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2018 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
*
* This file is part of GNSS-SDR.
*
* GNSS-SDR is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GNSS-SDR is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with GNSS-SDR. If not, see <https://www.gnu.org/licenses/>.
*
* -------------------------------------------------------------------------
*/
#include "rtklib_pvt.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include <boost/archive/xml_oarchive.hpp>
#include <boost/archive/xml_iarchive.hpp>
#include <boost/math/common_factor_rt.hpp>
#include <boost/serialization/map.hpp>
#include <glog/logging.h>
using google::LogMessage;
RtklibPvt::RtklibPvt(ConfigurationInterface* configuration,
std::string role,
unsigned int in_streams,
unsigned int out_streams) : role_(role),
in_streams_(in_streams),
out_streams_(out_streams)
{
// dump parameters
std::string default_dump_filename = "./pvt.dat";
std::string default_nmea_dump_filename = "./nmea_pvt.nmea";
std::string default_nmea_dump_devname = "/dev/tty1";
std::string default_rtcm_dump_devname = "/dev/pts/1";
DLOG(INFO) << "role " << role;
dump_ = configuration->property(role + ".dump", false);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
// output rate
int output_rate_ms = configuration->property(role + ".output_rate_ms", 500);
// display rate
int display_rate_ms = configuration->property(role + ".display_rate_ms", 500);
// NMEA Printer settings
bool flag_nmea_tty_port = configuration->property(role + ".flag_nmea_tty_port", false);
std::string nmea_dump_filename = configuration->property(role + ".nmea_dump_filename", default_nmea_dump_filename);
std::string nmea_dump_devname = configuration->property(role + ".nmea_dump_devname", default_nmea_dump_devname);
// RINEX version
int rinex_version = configuration->property(role + ".rinex_version", 3);
if (FLAGS_RINEX_version.compare("3.01") == 0)
{
rinex_version = 3;
}
else if (FLAGS_RINEX_version.compare("3.02") == 0)
{
rinex_version = 3;
}
else if (FLAGS_RINEX_version.compare("3") == 0)
{
rinex_version = 3;
}
else if (FLAGS_RINEX_version.compare("2.11") == 0)
{
rinex_version = 2;
}
else if (FLAGS_RINEX_version.compare("2.10") == 0)
{
rinex_version = 2;
}
else if (FLAGS_RINEX_version.compare("2") == 0)
{
rinex_version = 2;
}
int rinexobs_rate_ms = boost::math::lcm(configuration->property(role + ".rinexobs_rate_ms", 1000), output_rate_ms);
int rinexnav_rate_ms = boost::math::lcm(configuration->property(role + ".rinexnav_rate_ms", 6000), output_rate_ms);
// RTCM Printer settings
bool flag_rtcm_tty_port = configuration->property(role + ".flag_rtcm_tty_port", false);
std::string rtcm_dump_devname = configuration->property(role + ".rtcm_dump_devname", default_rtcm_dump_devname);
bool flag_rtcm_server = configuration->property(role + ".flag_rtcm_server", false);
unsigned short rtcm_tcp_port = configuration->property(role + ".rtcm_tcp_port", 2101);
unsigned short rtcm_station_id = configuration->property(role + ".rtcm_station_id", 1234);
// 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_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_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_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);
std::map<int, int> rtcm_msg_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;
for (int k = 1071; k < 1078; k++) // All GPS MSM
{
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
{
rtcm_msg_rate_ms[k] = rtcm_MT1097_rate_ms;
}
// getting names from the config file, if available
// default filename for assistance data
const std::string eph_default_xml_filename = "./gps_ephemeris.xml";
const std::string utc_default_xml_filename = "./gps_utc_model.xml";
const std::string iono_default_xml_filename = "./gps_iono.xml";
const std::string ref_time_default_xml_filename = "./gps_ref_time.xml";
const std::string ref_location_default_xml_filename = "./gps_ref_location.xml";
eph_xml_filename_ = configuration->property("GNSS-SDR.SUPL_gps_ephemeris_xml", eph_default_xml_filename);
//std::string utc_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_utc_model.xml", utc_default_xml_filename);
//std::string iono_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_iono_xml", iono_default_xml_filename);
//std::string ref_time_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_time_xml", ref_time_default_xml_filename);
//std::string ref_location_xml_filename = configuration_->property("GNSS-SDR.SUPL_gps_ref_location_xml", ref_location_default_xml_filename);
// Infer the type of receiver
/*
* TYPE | RECEIVER
* 0 | Unknown
* 1 | GPS L1 C/A
* 2 | GPS L2C
* 3 | GPS L5
* 4 | Galileo E1B
* 5 | Galileo E5a
* 6 | Galileo E5b
* 7 | GPS L1 C/A + GPS L2C
* 8 | GPS L1 C/A + GPS L5
* 9 | GPS L1 C/A + Galileo E1B
* 10 | GPS L1 C/A + Galileo E5a
* 11 | GPS L1 C/A + Galileo E5b
* 12 | Galileo E1B + GPS L2C
* 13 | Galileo E1B + GPS L5
* 14 | Galileo E1B + Galileo E5a
* 15 | Galileo E1B + Galileo E5b
* 16 | GPS L2C + GPS L5
* 17 | GPS L2C + Galileo E5a
* 18 | GPS L2C + Galileo E5b
* 19 | GPS L5 + Galileo E5a
* 20 | GPS L5 + Galileo E5b
* 21 | GPS L1 C/A + Galileo E1B + GPS L2C
* 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
* 28 | GPS L2C + GLONASS L1 C/A
*/
int gps_1C_count = configuration->property("Channels_1C.count", 0);
int gps_2S_count = configuration->property("Channels_2S.count", 0);
int gps_L5_count = configuration->property("Channels_L5.count", 0);
int gal_1B_count = configuration->property("Channels_1B.count", 0);
int gal_E5a_count = configuration->property("Channels_5X.count", 0);
int gal_E5b_count = configuration->property("Channels_7X.count", 0);
int glo_1G_count = configuration->property("Channels_1G.count", 0);
int glo_2G_count = configuration->property("Channels_2G.count", 0);
unsigned int type_of_receiver = 0;
// *******************WARNING!!!!!!!***********
// GPS L5 only configurable for single frequency, single system at the moment!!!!!!
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 1;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 2;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count != 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 3;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 4;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 5;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 6;
if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 7;
//if( (gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 8;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 9;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 10;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 11;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) 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) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 14;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 15;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 16;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count != 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 17;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count != 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 18;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 19;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) type_of_receiver = 20;
if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0)) type_of_receiver = 21;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count = 0)) type_of_receiver = 22;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0)) type_of_receiver = 23;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 24;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count != 0)) type_of_receiver = 25;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 26;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 27;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count != 0) && (glo_2G_count == 0)) type_of_receiver = 28;
if ((gps_1C_count != 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 29;
if ((gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 30;
if ((gps_1C_count == 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count != 0)) type_of_receiver = 31;
//RTKLIB PVT solver options
// Settings 1
int positioning_mode = -1;
std::string default_pos_mode("Single");
std::string positioning_mode_str = configuration->property(role + ".positioning_mode", default_pos_mode); /* (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h */
if (positioning_mode_str.compare("Single") == 0) positioning_mode = PMODE_SINGLE;
if (positioning_mode_str.compare("Static") == 0) positioning_mode = PMODE_STATIC;
if (positioning_mode_str.compare("Kinematic") == 0) positioning_mode = PMODE_KINEMA;
if (positioning_mode_str.compare("PPP_Static") == 0) positioning_mode = PMODE_PPP_STATIC;
if (positioning_mode_str.compare("PPP_Kinematic") == 0) positioning_mode = PMODE_PPP_KINEMA;
if (positioning_mode == -1)
{
//warn user and set the default
std::cout << "WARNING: Bad specification of positioning mode." << std::endl;
std::cout << "positioning_mode possible values: Single / Static / Kinematic / PPP_Static / PPP_Kinematic" << std::endl;
std::cout << "positioning_mode specified value: " << positioning_mode_str << std::endl;
std::cout << "Setting positioning_mode to Single" << std::endl;
positioning_mode = PMODE_SINGLE;
}
int num_bands = 0;
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) || (glo_1G_count > 0)) && ((gps_2S_count > 0) || (glo_2G_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) || (gps_L5_count > 0))) num_bands = 2;
if (((gps_1C_count > 0) || (gal_1B_count > 0) || (glo_1G_count > 0)) && ((gps_2S_count > 0) || (glo_2G_count > 0)) && ((gal_E5a_count > 0) || (gal_E5b_count > 0) || (gps_L5_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) */
if ((number_of_frequencies < 1) || (number_of_frequencies > 3))
{
//warn user and set the default
number_of_frequencies = num_bands;
}
double elevation_mask = configuration->property(role + ".elevation_mask", 15.0);
if ((elevation_mask < 0.0) || (elevation_mask > 90.0))
{
//warn user and set the default
LOG(WARNING) << "Erroneous Elevation Mask. Setting to default value of 15.0 degrees";
elevation_mask = 15.0;
}
int dynamics_model = configuration->property(role + ".dynamics_model", 0); /* dynamics model (0:none, 1:velocity, 2:accel) */
if ((dynamics_model < 0) || (dynamics_model > 2))
{
//warn user and set the default
LOG(WARNING) << "Erroneous Dynamics Model configuration. Setting to default value of (0:none)";
dynamics_model = 0;
}
std::string default_iono_model("OFF");
std::string iono_model_str = configuration->property(role + ".iono_model", default_iono_model); /* (IONOOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */
int iono_model = -1;
if (iono_model_str.compare("OFF") == 0) iono_model = IONOOPT_OFF;
if (iono_model_str.compare("Broadcast") == 0) iono_model = IONOOPT_BRDC;
if (iono_model_str.compare("SBAS") == 0) iono_model = IONOOPT_SBAS;
if (iono_model_str.compare("Iono-Free-LC") == 0) iono_model = IONOOPT_IFLC;
if (iono_model_str.compare("Estimate_STEC") == 0) iono_model = IONOOPT_EST;
if (iono_model_str.compare("IONEX") == 0) iono_model = IONOOPT_TEC;
if (iono_model == -1)
{
//warn user and set the default
std::cout << "WARNING: Bad specification of ionospheric model." << std::endl;
std::cout << "iono_model possible values: OFF / Broadcast / SBAS / Iono-Free-LC / Estimate_STEC / IONEX" << std::endl;
std::cout << "iono_model specified value: " << iono_model_str << std::endl;
std::cout << "Setting iono_model to OFF" << std::endl;
iono_model = IONOOPT_OFF; /* 0: ionosphere option: correction off */
}
std::string default_trop_model("OFF");
int trop_model = -1;
std::string trop_model_str = configuration->property(role + ".trop_model", default_trop_model); /* (TROPOPT_XXX) see src/algorithms/libs/rtklib/rtklib.h */
if (trop_model_str.compare("OFF") == 0) trop_model = TROPOPT_OFF;
if (trop_model_str.compare("Saastamoinen") == 0) trop_model = TROPOPT_SAAS;
if (trop_model_str.compare("SBAS") == 0) trop_model = TROPOPT_SBAS;
if (trop_model_str.compare("Estimate_ZTD") == 0) trop_model = TROPOPT_EST;
if (trop_model_str.compare("Estimate_ZTD_Grad") == 0) trop_model = TROPOPT_ESTG;
if (trop_model == -1)
{
//warn user and set the default
std::cout << "WARNING: Bad specification of tropospheric model." << std::endl;
std::cout << "trop_model possible values: OFF / Saastamoinen / SBAS / Estimate_ZTD / Estimate_ZTD_Grad" << std::endl;
std::cout << "trop_model specified value: " << trop_model_str << std::endl;
std::cout << "Setting trop_model to OFF" << std::endl;
trop_model = TROPOPT_OFF;
}
/* RTKLIB positioning options */
int sat_PCV = 0; /* Set whether the satellite antenna PCV (phase center variation) model is used or not. This feature requires a Satellite Antenna PCV File. */
int rec_PCV = 0; /* Set whether the receiver antenna PCV (phase center variation) model is used or not. This feature requires a Receiver Antenna PCV File. */
/* Set whether the phase windup correction for PPP modes is applied or not. Only applicable to PPP* modes.*/
int phwindup = configuration->property(role + ".phwindup", 0);
/* Set whether the GPS Block IIA satellites in eclipse are excluded or not.
The eclipsing Block IIA satellites often degrade the PPP solutions due to unpredicted behavior of yawattitude. Only applicable to PPP* modes.*/
int reject_GPS_IIA = configuration->property(role + ".reject_GPS_IIA", 0);
/* Set whether RAIM (receiver autonomous integrity monitoring) FDE (fault detection and exclusion) feature is enabled or not.
In case of RAIM FDE enabled, a satellite is excluded if SSE (sum of squared errors) of residuals is over a threshold.
The excluded satellite is selected to indicate the minimum SSE. */
int raim_fde = configuration->property(role + ".raim_fde", 0);
int earth_tide = configuration->property(role + ".earth_tide", 0);
int nsys = 0;
if ((gps_1C_count > 0) || (gps_2S_count > 0) || (gps_L5_count > 0)) nsys += SYS_GPS;
if ((gal_1B_count > 0) || (gal_E5a_count > 0) || (gal_E5b_count > 0)) nsys += SYS_GAL;
if ((glo_1G_count > 0) || (glo_2G_count > 0)) nsys += SYS_GLO;
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 */
{
//warn user and set the default
LOG(WARNING) << "Erroneous Navigation System. Setting to default value of (0:none)";
navigation_system = nsys;
}
// Settings 2
std::string default_gps_ar("Continuous");
std::string integer_ambiguity_resolution_gps_str = configuration->property(role + ".AR_GPS", default_gps_ar); /* Integer Ambiguity Resolution mode for GPS (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */
int integer_ambiguity_resolution_gps = -1;
if (integer_ambiguity_resolution_gps_str.compare("OFF") == 0) integer_ambiguity_resolution_gps = ARMODE_OFF;
if (integer_ambiguity_resolution_gps_str.compare("Continuous") == 0) integer_ambiguity_resolution_gps = ARMODE_CONT;
if (integer_ambiguity_resolution_gps_str.compare("Instantaneous") == 0) integer_ambiguity_resolution_gps = ARMODE_INST;
if (integer_ambiguity_resolution_gps_str.compare("Fix-and-Hold") == 0) integer_ambiguity_resolution_gps = ARMODE_FIXHOLD;
if (integer_ambiguity_resolution_gps_str.compare("PPP-AR") == 0) integer_ambiguity_resolution_gps = ARMODE_PPPAR;
if (integer_ambiguity_resolution_gps == -1)
{
//warn user and set the default
std::cout << "WARNING: Bad specification of GPS ambiguity resolution method." << std::endl;
std::cout << "AR_GPS possible values: OFF / Continuous / Instantaneous / Fix-and-Hold / PPP-AR" << std::endl;
std::cout << "AR_GPS specified value: " << integer_ambiguity_resolution_gps_str << std::endl;
std::cout << "Setting AR_GPS to OFF" << std::endl;
integer_ambiguity_resolution_gps = ARMODE_OFF;
}
int integer_ambiguity_resolution_glo = configuration->property(role + ".AR_GLO", 1); /* Integer Ambiguity Resolution mode for GLONASS (0:off,1:on,2:auto cal,3:ext cal) */
if ((integer_ambiguity_resolution_glo < 0) || (integer_ambiguity_resolution_glo > 3))
{
//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;
}
int integer_ambiguity_resolution_bds = configuration->property(role + ".AR_DBS", 1); /* Integer Ambiguity Resolution mode for BEIDOU (0:off,1:on) */
if ((integer_ambiguity_resolution_bds < 0) || (integer_ambiguity_resolution_bds > 1))
{
//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;
}
double min_ratio_to_fix_ambiguity = configuration->property(role + ".min_ratio_to_fix_ambiguity", 3.0); /* Set the integer ambiguity validation threshold for ratiotest,
which uses the ratio of squared residuals of the best integer vector to the secondbest vector. */
int min_lock_to_fix_ambiguity = configuration->property(role + ".min_lock_to_fix_ambiguity", 0); /* Set the minimum lock count to fix integer ambiguity.
If the lock count is less than the value, the ambiguity is excluded from the fixed integer vector. */
double min_elevation_to_fix_ambiguity = configuration->property(role + ".min_elevation_to_fix_ambiguity", 0.0); /* Set the minimum elevation (deg) to fix integer ambiguity.
If the elevation of the satellite is less than the value, the ambiguity is excluded from the fixed integer vector. */
int outage_reset_ambiguity = configuration->property(role + ".outage_reset_ambiguity", 5); /* Set the outage count to reset ambiguity. If the data outage count is over the value, the estimated ambiguity is reset to the initial value. */
double slip_threshold = configuration->property(role + ".slip_threshold", 0.05); /* set the cycleslip threshold (m) of geometryfree LC carrierphase difference between epochs */
double threshold_reject_gdop = configuration->property(role + ".threshold_reject_gdop", 30.0); /* reject threshold of GDOP. If the GDOP is over the value, the observable is excluded for the estimation process as an outlier. */
double threshold_reject_innovation = configuration->property(role + ".threshold_reject_innovation", 30.0); /* reject threshold of innovation (m). If the innovation is over the value, the observable is excluded for the estimation process as an outlier. */
int number_filter_iter = configuration->property(role + ".number_filter_iter", 1); /* Set the number of iteration in the measurement update of the estimation filter.
If the baseline length is very short like 1 m, the iteration may be effective to handle
the nonlinearity of measurement equation. */
/// Statistics
double bias_0 = configuration->property(role + ".bias_0", 30.0);
double iono_0 = configuration->property(role + ".iono_0", 0.03);
double trop_0 = configuration->property(role + ".trop_0", 0.3);
double sigma_bias = configuration->property(role + ".sigma_bias", 1e-4); /* Set the process noise standard deviation of carrierphase
bias (ambiguity) (cycle/sqrt(s)) */
double sigma_iono = configuration->property(role + ".sigma_iono", 1e-3); /* Set the process noise standard deviation of vertical ionospheric delay per 10 km baseline (m/sqrt(s)). */
double sigma_trop = configuration->property(role + ".sigma_trop", 1e-4); /* Set the process noise standard deviation of zenith tropospheric delay (m/sqrt(s)). */
double sigma_acch = configuration->property(role + ".sigma_acch", 1e-1); /* Set the process noise standard deviation of the receiver acceleration as
the horizontal component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */
double sigma_accv = configuration->property(role + ".sigma_accv", 1e-2); /* Set the process noise standard deviation of the receiver acceleration as
the vertical component. (m/s2/sqrt(s)). If Receiver Dynamics is set to OFF, they are not used. */
double sigma_pos = configuration->property(role + ".sigma_pos", 0.0);
double code_phase_error_ratio_l1 = configuration->property(role + ".code_phase_error_ratio_l1", 100.0);
double code_phase_error_ratio_l2 = configuration->property(role + ".code_phase_error_ratio_l2", 100.0);
double code_phase_error_ratio_l5 = configuration->property(role + ".code_phase_error_ratio_l5", 100.0);
double carrier_phase_error_factor_a = configuration->property(role + ".carrier_phase_error_factor_a", 0.003);
double carrier_phase_error_factor_b = configuration->property(role + ".carrier_phase_error_factor_b", 0.003);
snrmask_t snrmask = {{}, {{}, {}}};
prcopt_t rtklib_configuration_options = {
positioning_mode, /* positioning mode (PMODE_XXX) see src/algorithms/libs/rtklib/rtklib.h */
0, /* solution type (0:forward,1:backward,2:combined) */
number_of_frequencies, /* number of frequencies (1:L1, 2:L1+L2, 3:L1+L2+L5)*/
navigation_system, /* navigation system */
elevation_mask * D2R, /* elevation mask angle (degrees) */
snrmask, /* snrmask_t snrmask SNR mask */
0, /* satellite ephemeris/clock (EPHOPT_XXX) */
integer_ambiguity_resolution_gps, /* AR mode (0:off,1:continuous,2:instantaneous,3:fix and hold,4:ppp-ar) */
integer_ambiguity_resolution_glo, /* GLONASS AR mode (0:off,1:on,2:auto cal,3:ext cal) */
integer_ambiguity_resolution_bds, /* BeiDou AR mode (0:off,1:on) */
outage_reset_ambiguity, /* obs outage count to reset bias */
min_lock_to_fix_ambiguity, /* min lock count to fix ambiguity */
10, /* min fix count to hold ambiguity */
1, /* max iteration to resolve ambiguity */
iono_model, /* ionosphere option (IONOOPT_XXX) */
trop_model, /* troposphere option (TROPOPT_XXX) */
dynamics_model, /* dynamics model (0:none, 1:velocity, 2:accel) */
earth_tide, /* earth tide correction (0:off,1:solid,2:solid+otl+pole) */
number_filter_iter, /* number of filter iteration */
0, /* code smoothing window size (0:none) */
0, /* interpolate reference obs (for post mission) */
0, /* sbssat_t sbssat SBAS correction options */
0, /* sbsion_t sbsion[MAXBAND+1] SBAS satellite selection (0:all) */
0, /* rover position for fixed mode */
0, /* base position for relative mode */
/* 0:pos in prcopt, 1:average of single pos, */
/* 2:read from file, 3:rinex header, 4:rtcm pos */
{code_phase_error_ratio_l1, code_phase_error_ratio_l2, code_phase_error_ratio_l5}, /* eratio[NFREQ] code/phase error ratio */
{100.0, carrier_phase_error_factor_a, carrier_phase_error_factor_b, 0.0, 1.0}, /* err[5]: measurement error factor [0]:reserved, [1-3]:error factor a/b/c of phase (m) , [4]:doppler frequency (hz) */
{bias_0, iono_0, trop_0}, /* std[3]: initial-state std [0]bias,[1]iono [2]trop*/
{sigma_bias, sigma_iono, sigma_trop, sigma_acch, sigma_accv, sigma_pos}, /* prn[6] process-noise std */
5e-12, /* sclkstab: satellite clock stability (sec/sec) */
{min_ratio_to_fix_ambiguity, 0.9999, 0.25, 0.1, 0.05, 0.0, 0.0, 0.0}, /* thresar[8]: AR validation threshold */
min_elevation_to_fix_ambiguity, /* elevation mask of AR for rising satellite (deg) */
0.0, /* elevation mask to hold ambiguity (deg) */
slip_threshold, /* slip threshold of geometry-free phase (m) */
30.0, /* max difference of time (sec) */
threshold_reject_innovation, /* reject threshold of innovation (m) */
threshold_reject_gdop, /* reject threshold of gdop */
{}, /* double baseline[2] baseline length constraint {const,sigma} (m) */
{}, /* double ru[3] rover position for fixed mode {x,y,z} (ecef) (m) */
{}, /* double rb[3] base position for relative mode {x,y,z} (ecef) (m) */
{"", ""}, /* char anttype[2][MAXANT] antenna types {rover,base} */
{{}, {}}, /* double antdel[2][3] antenna delta {{rov_e,rov_n,rov_u},{ref_e,ref_n,ref_u}} */
{}, /* pcv_t pcvr[2] receiver antenna parameters {rov,base} */
{}, /* unsigned char exsats[MAXSAT] excluded satellites (1:excluded, 2:included) */
0, /* max averaging epoches */
0, /* initialize by restart */
1, /* output single by dgps/float/fix/ppp outage */
{"", ""}, /* char rnxopt[2][256] rinex options {rover,base} */
{sat_PCV, rec_PCV, phwindup, reject_GPS_IIA, raim_fde}, /* posopt[6] positioning options [0]: satellite and receiver antenna PCV model; [1]: interpolate antenna parameters; [2]: apply phase wind-up correction for PPP modes; [3]: exclude measurements of GPS Block IIA satellites satellite [4]: RAIM FDE (fault detection and exclusion) [5]: handle day-boundary clock jump */
0, /* solution sync mode (0:off,1:on) */
{{}, {}}, /* odisp[2][6*11] ocean tide loading parameters {rov,base} */
{{}, {{}, {}}, {{}, {}}, {}, {}}, /* exterr_t exterr extended receiver error model */
0, /* disable L2-AR */
{} /* char pppopt[256] ppp option "-GAP_RESION=" default gap to reset iono parameters (ep) */
};
rtkinit(&rtk, &rtklib_configuration_options);
// make PVT object
pvt_ = rtklib_make_pvt_cc(in_streams_, dump_, dump_filename_, output_rate_ms, display_rate_ms, flag_nmea_tty_port, nmea_dump_filename, nmea_dump_devname, rinex_version, rinexobs_rate_ms, rinexnav_rate_ms, flag_rtcm_server, flag_rtcm_tty_port, rtcm_tcp_port, rtcm_station_id, rtcm_msg_rate_ms, rtcm_dump_devname, type_of_receiver, rtk);
DLOG(INFO) << "pvt(" << pvt_->unique_id() << ")";
if (out_streams_ > 0)
{
LOG(ERROR) << "The PVT block does not have an output stream";
}
}
bool RtklibPvt::save_assistance_to_XML()
{
LOG(INFO) << "SUPL: Try to save GPS ephemeris to XML file " << eph_xml_filename_;
std::map<int, Gps_Ephemeris> eph_map = pvt_->get_GPS_L1_ephemeris_map();
if (eph_map.size() > 0)
{
try
{
std::ofstream ofs(eph_xml_filename_.c_str(), std::ofstream::trunc | std::ofstream::out);
boost::archive::xml_oarchive xml(ofs);
xml << boost::serialization::make_nvp("GNSS-SDR_ephemeris_map", eph_map);
ofs.close();
LOG(INFO) << "Saved GPS L1 Ephemeris map data";
}
catch (const std::exception& e)
{
LOG(WARNING) << e.what();
return false;
}
return true; // return variable (true == succeeded)
}
else
{
LOG(WARNING) << "Failed to save Ephemeris, map is empty";
return false;
}
}
RtklibPvt::~RtklibPvt()
{
rtkfree(&rtk);
save_assistance_to_XML();
}
void RtklibPvt::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 RtklibPvt::disconnect(gr::top_block_sptr top_block)
{
if (top_block)
{ /* top_block is not null */
};
// Nothing to disconnect
}
gr::basic_block_sptr RtklibPvt::get_left_block()
{
return pvt_;
}
gr::basic_block_sptr RtklibPvt::get_right_block()
{
return pvt_; // this is a sink, nothing downstream
}

View File

@ -321,8 +321,8 @@ void rtklib_pvt_cc::clear_ephemeris()
rtklib_pvt_cc::rtklib_pvt_cc(uint32_t nchannels,
const Pvt_Conf& conf_,
const rtk_t& rtk) : gr::sync_block("rtklib_pvt_cc",
gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)),
gr::io_signature::make(0, 0, 0))
gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)),
gr::io_signature::make(0, 0, 0))
{
d_output_rate_ms = conf_.output_rate_ms;
d_display_rate_ms = conf_.display_rate_ms;
@ -1018,8 +1018,8 @@ bool rtklib_pvt_cc::save_gnss_synchro_map_xml(const std::string& file_name)
return true;
}
LOG(WARNING) << "Failed to save gnss_synchro, map is empty";
return false;
LOG(WARNING) << "Failed to save gnss_synchro, map is empty";
return false;
}
@ -1064,7 +1064,7 @@ bool rtklib_pvt_cc::get_latest_PVT(double* longitude_deg,
return true;
}
return false;
return false;
}
@ -1564,7 +1564,7 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
rp->rinex_nav_header(rp->navMixFile, d_pvt_solver->gps_iono, d_pvt_solver->gps_utc_model, d_pvt_solver->galileo_iono, d_pvt_solver->galileo_utc_model);
b_rinex_header_written = true; // do not write header anymore
}
break;
break;
case 50: // BDS B1I only
if (beidou_dnav_ephemeris_iter != d_pvt_solver->beidou_dnav_ephemeris_map.cend())
{
@ -2149,10 +2149,10 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
{
// This is a channel with valid GPS signal
gps_cnav_eph_iter = d_pvt_solver->gps_cnav_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (gps_cnav_eph_iter != d_pvt_solver->gps_cnav_ephemeris_map.cend())
{
if (gps_cnav_eph_iter != d_pvt_solver->gps_cnav_ephemeris_map.cend())
{
gps_channel = 1;
}
}
}
}
if (gal_channel == 0)
@ -2160,8 +2160,8 @@ int rtklib_pvt_cc::work(int noutput_items, gr_vector_const_void_star& input_item
if (system == "E")
{
gal_eph_iter = d_pvt_solver->galileo_ephemeris_map.find(gnss_observables_iter->second.PRN);
if (gal_eph_iter != d_pvt_solver->galileo_ephemeris_map.cend())
{
if (gal_eph_iter != d_pvt_solver->galileo_ephemeris_map.cend())
{
gal_channel = 1;
}
}

View File

@ -247,9 +247,9 @@ Rinex_Printer::~Rinex_Printer()
if (remove(navGlofilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}
if (posnc == 0)
{
if (remove(navBdsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}
{
if (remove(navBdsfilename.c_str()) != 0) LOG(INFO) << "Error deleting temporary file";
}
}
@ -1367,8 +1367,8 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Gps_Iono& iono, co
line += std::string(3, ' ');
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0, 18, 2), 19);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1, 18, 2), 19);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_t_OT), 9);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_T + 1024), 9); // valid until 2019
line += Rinex_Printer::rightJustify(std::to_string(utc_model.d_t_OT), 9);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_T + 1024), 9); // valid until 2019
line += std::string(1, ' ');
line += Rinex_Printer::leftJustify("DELTA-UTC: A0,A1,T,W", 20);
}
@ -1378,8 +1378,8 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Gps_Iono& iono, co
line += std::string("GPUT");
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0, 16, 2), 18);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1, 15, 2), 16);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_t_OT), 7);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_T + 1024), 5); // valid until 2019
line += Rinex_Printer::rightJustify(std::to_string(utc_model.d_t_OT), 7);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_T + 1024), 5); // valid until 2019
/* if ( SBAS )
{
line += string(1, ' ');
@ -1399,16 +1399,16 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Gps_Iono& iono, co
// -------- Line 6 leap seconds
// For leap second information, see http://www.endruntechnologies.com/leap.htm
line.clear();
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.d_DeltaT_LS), 6);
if (version == 2)
{
line += std::string(54, ' ');
}
if (version == 3)
{
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_LSF), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_DN), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.d_DeltaT_LSF), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_LSF), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_DN), 6);
line += std::string(36, ' ');
}
line += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
@ -1612,38 +1612,38 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Beidou_Dnav_Iono&
// -------- Line ionospheric info 1, only version 3 supported
line.clear();
line += std::string("BDSA");
line += std::string(1, ' ');
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha0, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha1, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha2, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha3, 10, 2), 12);
line += std::string(7, ' ');
line += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
line += std::string(1, ' ');
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha0, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha1, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha2, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha3, 10, 2), 12);
line += std::string(7, ' ');
line += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
Rinex_Printer::lengthCheck(line);
out << line << std::endl;
// -------- Line ionospheric info 2
line.clear();
line += std::string("BDSB");
line += std::string(1, ' ');
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta0, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta1, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta2, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta3, 10, 2), 12);
line += std::string(7, ' ');
line += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
line += std::string("BDSB");
line += std::string(1, ' ');
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta0, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta1, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta2, 10, 2), 12);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta3, 10, 2), 12);
line += std::string(7, ' ');
line += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
Rinex_Printer::lengthCheck(line);
out << line << std::endl;
// -------- Line 5 system time correction
line.clear();
line += std::string("BDUT");
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0_UTC, 16, 2), 18);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1_UTC, 15, 2), 16);
line += std::string(22, ' ');
line += Rinex_Printer::leftJustify("TIME SYSTEM CORR", 20);
line += std::string("BDUT");
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0_UTC, 16, 2), 18);
line += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1_UTC, 15, 2), 16);
line += std::string(22, ' ');
line += Rinex_Printer::leftJustify("TIME SYSTEM CORR", 20);
Rinex_Printer::lengthCheck(line);
out << line << std::endl;
@ -1652,9 +1652,9 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Beidou_Dnav_Iono&
// For leap second information, see http://www.endruntechnologies.com/leap.htm
line.clear();
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_LSF), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_DN), 6);
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_LSF), 6);
line += Rinex_Printer::rightJustify(std::to_string(utc_model.i_DN), 6);
line += std::string(36, ' ');
line += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
Rinex_Printer::lengthCheck(line);
@ -2790,59 +2790,58 @@ void Rinex_Printer::update_nav_header(std::fstream& out, const Beidou_Dnav_Utc_M
{
line_aux.clear();
if (line_str.find("BDSA", 0) != std::string::npos)
{
line_aux += std::string("GPSA");
line_aux += std::string(1, ' ');
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha0, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha1, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha2, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha3, 10, 2), 12);
line_aux += std::string(7, ' ');
line_aux += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("BDSB", 0) != std::string::npos)
{
line_aux += std::string("GPSB");
line_aux += std::string(1, ' ');
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta0, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta1, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta2, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta3, 10, 2), 12);
line_aux += std::string(7, ' ');
line_aux += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("BDUT", 0) != std::string::npos)
{
line_aux += std::string("GPUT");
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0_UTC, 16, 2), 18);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1_UTC, 15, 2), 16);
line_aux += std::string(22, ' ');
line_aux += Rinex_Printer::leftJustify("TIME SYSTEM CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("LEAP SECONDS", 59) != std::string::npos)
{
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_LSF), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_DN), 6);
line_aux += std::string(36, ' ');
line_aux += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
data.push_back(line_aux);
}
else if (line_str.find("END OF HEADER", 59) != std::string::npos)
{
data.push_back(line_str);
no_more_finds = true;
}
else
{
data.push_back(line_str);
}
if (line_str.find("BDSA", 0) != std::string::npos)
{
line_aux += std::string("GPSA");
line_aux += std::string(1, ' ');
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha0, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha1, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha2, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_alpha3, 10, 2), 12);
line_aux += std::string(7, ' ');
line_aux += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("BDSB", 0) != std::string::npos)
{
line_aux += std::string("GPSB");
line_aux += std::string(1, ' ');
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta0, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta1, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta2, 10, 2), 12);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(iono.d_beta3, 10, 2), 12);
line_aux += std::string(7, ' ');
line_aux += Rinex_Printer::leftJustify("IONOSPHERIC CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("BDUT", 0) != std::string::npos)
{
line_aux += std::string("GPUT");
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A0_UTC, 16, 2), 18);
line_aux += Rinex_Printer::rightJustify(Rinex_Printer::doub2for(utc_model.d_A1_UTC, 15, 2), 16);
line_aux += std::string(22, ' ');
line_aux += Rinex_Printer::leftJustify("TIME SYSTEM CORR", 20);
data.push_back(line_aux);
}
else if (line_str.find("LEAP SECONDS", 59) != std::string::npos)
{
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line_aux += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_LSF), 6);
line_aux += Rinex_Printer::rightJustify(std::to_string(utc_model.i_DN), 6);
line_aux += std::string(36, ' ');
line_aux += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
data.push_back(line_aux);
}
else if (line_str.find("END OF HEADER", 59) != std::string::npos)
{
data.push_back(line_str);
no_more_finds = true;
}
else
{
data.push_back(line_str);
}
}
else
{
@ -3755,7 +3754,7 @@ void Rinex_Printer::log_rinex_nav(std::fstream& out, const std::map<int32_t, Bei
std::map<int32_t, Beidou_Dnav_Ephemeris>::const_iterator bds_ephemeris_iter;
for (bds_ephemeris_iter = eph_map.cbegin();
bds_ephemeris_iter != eph_map.cend();
bds_ephemeris_iter != eph_map.cend();
bds_ephemeris_iter++)
{
// -------- SV / EPOCH / SV CLK
@ -3767,28 +3766,28 @@ void Rinex_Printer::log_rinex_nav(std::fstream& out, const std::map<int32_t, Bei
std::string minutes(timestring, 11, 2);
std::string seconds(timestring, 13, 2);
line += satelliteSystem["Beidou"];
if (bds_ephemeris_iter->second.i_satellite_PRN < 10) line += std::string("0");
line += boost::lexical_cast<std::string>(bds_ephemeris_iter->second.i_satellite_PRN);
std::string year(timestring, 0, 4);
line += std::string(1, ' ');
line += year;
line += std::string(1, ' ');
line += month;
line += std::string(1, ' ');
line += day;
line += std::string(1, ' ');
line += hour;
line += std::string(1, ' ');
line += minutes;
line += std::string(1, ' ');
line += seconds;
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f0, 18, 2);
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f1, 18, 2);
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f2, 18, 2);
line += satelliteSystem["Beidou"];
if (bds_ephemeris_iter->second.i_satellite_PRN < 10) line += std::string("0");
line += std::to_string(bds_ephemeris_iter->second.i_satellite_PRN);
std::string year(timestring, 0, 4);
line += std::string(1, ' ');
line += year;
line += std::string(1, ' ');
line += month;
line += std::string(1, ' ');
line += day;
line += std::string(1, ' ');
line += hour;
line += std::string(1, ' ');
line += minutes;
line += std::string(1, ' ');
line += seconds;
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f0, 18, 2);
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f1, 18, 2);
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(bds_ephemeris_iter->second.d_A_f2, 18, 2);
Rinex_Printer::lengthCheck(line);
out << line << std::endl;
@ -3851,7 +3850,7 @@ void Rinex_Printer::log_rinex_nav(std::fstream& out, const std::map<int32_t, Bei
line += std::string(1, ' ');
line += std::string(18, ' '); // spare
line += std::string(1, ' ');
double BDS_week_continuous_number = static_cast<double>(bds_ephemeris_iter->second.i_BEIDOU_week);
auto BDS_week_continuous_number = static_cast<double>(bds_ephemeris_iter->second.i_BEIDOU_week);
line += Rinex_Printer::doub2for(BDS_week_continuous_number, 18, 2);
line += std::string(1, ' ');
line += std::string(18, ' '); // spare
@ -7201,7 +7200,7 @@ void Rinex_Printer::rinex_obs_header(std::fstream& out, const Gps_Ephemeris& gps
}
void Rinex_Printer::rinex_obs_header(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, const double d_TOW_first_observation, const std::string bands)
void Rinex_Printer::rinex_obs_header(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, const double d_TOW_first_observation, const std::string& bands)
{
std::string line;
version = 3;
@ -7658,27 +7657,26 @@ void Rinex_Printer::update_obs_header(std::fstream& out, const Beidou_Dnav_Utc_M
{
line_aux.clear();
if (line_str.find("TIME OF FIRST OBS", 59) != std::string::npos)
{
data.push_back(line_str);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_WN_LSF), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.i_DN), 6);
line_aux += std::string(36, ' ');
line_aux += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
data.push_back(line_aux);
}
else if (line_str.find("END OF HEADER", 59) != std::string::npos)
{
data.push_back(line_str);
no_more_finds = true;
}
else
{
data.push_back(line_str);
}
if (line_str.find("TIME OF FIRST OBS", 59) != std::string::npos)
{
data.push_back(line_str);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LS), 6);
line_aux += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(utc_model.d_DeltaT_LSF), 6);
line_aux += Rinex_Printer::rightJustify(std::to_string(utc_model.i_WN_LSF), 6);
line_aux += Rinex_Printer::rightJustify(std::to_string(utc_model.i_DN), 6);
line_aux += std::string(36, ' ');
line_aux += Rinex_Printer::leftJustify("LEAP SECONDS", 20);
data.push_back(line_aux);
}
else if (line_str.find("END OF HEADER", 59) != std::string::npos)
{
data.push_back(line_str);
no_more_finds = true;
}
else
{
data.push_back(line_str);
}
}
else
{
@ -10409,7 +10407,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
}
void Rinex_Printer::log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, double obs_time, const std::map<int32_t, Gnss_Synchro>& observables, const std::string bds_bands)
void Rinex_Printer::log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, double obs_time, const std::map<int32_t, Gnss_Synchro>& observables, const std::string& bds_bands)
{
std::string line;
@ -10520,7 +10518,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris
}
int32_t numSatellitesObserved = available_prns.size();
line += Rinex_Printer::rightJustify(boost::lexical_cast<std::string>(numSatellitesObserved), 3);
line += Rinex_Printer::rightJustify(std::to_string(numSatellitesObserved), 3);
// Receiver clock offset (optional)
//line += rightJustify(asString(clockOffset, 12), 15);
line += std::string(80 - line.size(), ' ');
@ -10536,9 +10534,9 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris
lineObs.clear();
lineObs += satelliteSystem["Beidou"];
if (static_cast<int32_t>(*it) < 10) lineObs += std::string(1, '0');
lineObs += boost::lexical_cast<std::string>(static_cast<int32_t>(*it));
lineObs += std::to_string(static_cast<int32_t>(*it));
ret = total_map.equal_range(*it);
for (std::multimap<uint32_t, Gnss_Synchro>::iterator iter = ret.first; iter != ret.second; ++iter)
for (auto iter = ret.first; iter != ret.second; ++iter)
{
lineObs += Rinex_Printer::rightJustify(asString(iter->second.Pseudorange_m, 3), 14);

View File

@ -51,21 +51,19 @@
#ifndef GNSS_SDR_RINEX_PRINTER_H_
#define GNSS_SDR_RINEX_PRINTER_H_
#include "gps_navigation_message.h"
#include "gps_cnav_navigation_message.h"
#include "galileo_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
#include "beidou_dnav_navigation_message.h"
#include "Beidou_B1I.h"
#include "GLONASS_L1_L2_CA.h"
#include "GPS_L1_CA.h"
#include "Galileo_E1.h"
#include "GLONASS_L1_L2_CA.h"
#include "Beidou_B1I.h"
#include "beidou_dnav_navigation_message.h"
#include "galileo_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
#include "gnss_synchro.h"
#include "gps_cnav_navigation_message.h"
#include "gps_navigation_message.h"
#include <boost/date_time/posix_time/posix_time.hpp>
#include <cstdint>
#include <string>
#include <fstream>
#include <sstream> // for stringstream
#include <iomanip> // for setprecision
#include <map>
#include <sstream> // for stringstream
@ -203,7 +201,7 @@ public:
/*!
* \brief Generates the a Beidou B1I Observation data header. Example: beidou_bands("B1")
*/
void rinex_obs_header(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, const double d_TOW_first_observation, const std::string bands);
void rinex_obs_header(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, const double d_TOW_first_observation, const std::string& bands);
/*!
* \brief Generates the SBAS raw data header
@ -363,7 +361,7 @@ public:
/*!
* \brief Writes BDS B1I observables into the RINEX file
*/
void log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, double obs_time, const std::map<int32_t, Gnss_Synchro>& observables, const std::string bds_bands);
void log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris& eph, double obs_time, const std::map<int32_t, Gnss_Synchro>& observables, const std::string& bds_bands);
/*!

View File

@ -52,10 +52,10 @@
* -----------------------------------------------------------------------*/
#include "rtklib_solver.h"
#include "Beidou_B1I.h"
#include "GLONASS_L1_L2_CA.h"
#include "GPS_L1_CA.h"
#include "Galileo_E1.h"
#include "Beidou_B1I.h"
#include "rtklib_conversions.h"
#include "rtklib_solution.h"
#include <glog/logging.h>
@ -785,7 +785,7 @@ bool rtklib_solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
}
}
break;
}
}
default:
DLOG(INFO) << "Hybrid observables: Unknown GNSS";

View File

@ -55,13 +55,13 @@
#define GNSS_SDR_RTKLIB_SOLVER_H_
#include "beidou_dnav_navigation_message.h"
#include "galileo_almanac.h"
#include "galileo_navigation_message.h"
#include "glonass_gnav_navigation_message.h"
#include "gnss_synchro.h"
#include "gps_cnav_navigation_message.h"
#include "gps_navigation_message.h"
#include "beidou_dnav_navigation_message.h"
#include "pvt_solution.h"
#include "rtklib_rtkpos.h"
#include <array>
@ -102,7 +102,7 @@ public:
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, Glonass_Gnav_Ephemeris> glonass_gnav_ephemeris_map; //!< Map storing new GLONASS GNAV Ephemeris
std::map<int, Beidou_Dnav_Ephemeris> beidou_dnav_ephemeris_map; //!< Map storing new GLONASS GNAV Ephmeris
std::map<int, Beidou_Dnav_Ephemeris> beidou_dnav_ephemeris_map; //!< Map storing new GLONASS GNAV Ephmeris
Galileo_Utc_Model galileo_utc_model;
Galileo_Iono galileo_iono;

View File

@ -36,11 +36,11 @@
#include "acq_conf.h"
#include "acquisition_interface.h"
#include "complex_byte_to_float_x2.h"
#include "gnss_synchro.h"
#include "pcps_acquisition.h"
#include "complex_byte_to_float_x2.h"
#include <gnuradio/blocks/stream_to_vector.h>
#include <gnuradio/blocks/float_to_complex.h>
#include <gnuradio/blocks/stream_to_vector.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#include <string>
@ -55,7 +55,7 @@ class BeidouB1iPcpsAcquisition : public AcquisitionInterface
{
public:
BeidouB1iPcpsAcquisition(ConfigurationInterface* configuration,
std::string role, unsigned int in_streams,
const std::string& role, unsigned int in_streams,
unsigned int out_streams);
virtual ~BeidouB1iPcpsAcquisition();

View File

@ -39,8 +39,8 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
const unsigned int _code_length = 2046;
bool G1[_code_length];
bool G2[_code_length];
bool G1_register[11] = {0,1,0,1,0,1,0,1,0,1,0};
bool G2_register[11] = {0,1,0,1,0,1,0,1,0,1,0};
bool G1_register[11] = {false, true, false, true, false, true, false, true, false, true, false};
bool G2_register[11] = {false, true, false, true, false, true, false, true, false, true, false};
bool feedback1, feedback2;
bool aux;
unsigned int lcv, lcv2;
@ -70,7 +70,7 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
for (lcv = 0; lcv < _code_length; lcv++)
{
G1[lcv] = G1_register[0];
G2[lcv] = G2_register[-(phase1[prn_idx] - 11) ] ^ G2_register[-(phase2[prn_idx] - 11) ];
G2[lcv] = G2_register[-(phase1[prn_idx] - 11)] ^ G2_register[-(phase2[prn_idx] - 11)];
feedback1 = (G1_register[0] + G1_register[1] + G1_register[2] + G1_register[3] + G1_register[4] + G1_register[10]) & 0x1;
feedback2 = (G2_register[0] + G2_register[2] + G2_register[3] + G2_register[6] + G2_register[7] + G2_register[8] + G2_register[9] + G2_register[10]) & 0x1;
@ -86,7 +86,7 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
}
/* Set the delay */
delay = _code_length - delays[prn_idx]*0; //**********************************
delay = _code_length - delays[prn_idx] * 0; //**********************************
delay += _chip_shift;
delay %= _code_length;
@ -104,7 +104,7 @@ void beidou_b1i_code_gen_int(int* _dest, signed int _prn, unsigned int _chip_shi
}
delay++;
//std::cout << _dest[lcv] << " ";
//std::cout << _dest[lcv] << " ";
delay %= _code_length;
}
}
@ -156,8 +156,8 @@ void beidou_b1i_code_gen_complex_sampled(std::complex<float>* _dest, unsigned in
_samplesPerCode = static_cast<signed int>(static_cast<double>(_fs) / static_cast<double>(_codeFreqBasis / _codeLength));
//--- Find time constants --------------------------------------------------
_ts = 1.0 / static_cast<float>(_fs); // Sampling period in sec
_tc = 1.0 / static_cast<float>(_codeFreqBasis); // C/A chip period in sec
_ts = 1.0 / static_cast<float>(_fs); // Sampling period in sec
_tc = 1.0 / static_cast<float>(_codeFreqBasis); // C/A chip period in sec
beidou_b1i_code_gen_complex(_code, _prn, _chip_shift); //generate C/A code 1 sample per chip
for (signed int i = 0; i < _samplesPerCode; i++)

View File

@ -223,8 +223,8 @@ const int NSYSQZS = 0;
#define ENABDS
#ifdef ENABDS
const int MINPRNBDS = 1; //!< min satellite sat number of BeiDou
const int MAXPRNBDS = 35; //!< max satellite sat number of BeiDou
const int MINPRNBDS = 1; //!< min satellite sat number of BeiDou
const int MAXPRNBDS = 35; //!< max satellite sat number of BeiDou
const int NSATBDS = (MAXPRNBDS - MINPRNBDS + 1); //!< number of BeiDou satellites
const int NSYSBDS = 1;
#else

View File

@ -75,15 +75,15 @@ obsd_t insert_obs_to_rtklib(obsd_t& rtklib_obs, const Gnss_Synchro& gnss_synchro
// Mote that BeiDou week numbers do not need adjustment for foreseeable future. Consider change
// to more elegant solution
// if(gnss_synchro.System == 'C')
// {
// rtklib_obs.time = bdt2gpst(bdt2time(week, gnss_synchro.RX_time));
// }
// else
// {
// rtklib_obs.time = gpst2time(adjgpsweek(week), gnss_synchro.RX_time);
// }
//
// if(gnss_synchro.System == 'C')
// {
// rtklib_obs.time = bdt2gpst(bdt2time(week, gnss_synchro.RX_time));
// }
// else
// {
// rtklib_obs.time = gpst2time(adjgpsweek(week), gnss_synchro.RX_time);
// }
//
rtklib_obs.time = gpst2time(adjgpsweek(week), gnss_synchro.RX_time);
rtklib_obs.rcv = 1;
return rtklib_obs;
@ -245,8 +245,8 @@ eph_t eph_to_rtklib(const Gps_Ephemeris& gps_eph)
eph_t eph_to_rtklib(const Beidou_Dnav_Ephemeris& bei_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,
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 };
rtklib_sat.sat = bei_eph.i_satellite_PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS ;
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};
rtklib_sat.sat = bei_eph.i_satellite_PRN + NSATGPS + NSATGLO + NSATGAL + NSATQZS;
rtklib_sat.A = bei_eph.d_sqrt_A * bei_eph.d_sqrt_A;
rtklib_sat.M0 = bei_eph.d_M_0;
rtklib_sat.deln = bei_eph.d_Delta_n;
@ -259,10 +259,10 @@ eph_t eph_to_rtklib(const Beidou_Dnav_Ephemeris& bei_eph)
rtklib_sat.Adot = 0; //only in CNAV;
rtklib_sat.ndot = 0; //only in CNAV;
rtklib_sat.code = bei_eph.i_sig_type; /*B1I data*/
rtklib_sat.flag = bei_eph.i_nav_type; /*MEO/IGSO satellite*/
rtklib_sat.iode=(int32_t)bei_eph.d_AODE; /* AODE */
rtklib_sat.iodc=(int32_t)bei_eph.d_AODC; /* AODC */
rtklib_sat.code = bei_eph.i_sig_type; /*B1I data*/
rtklib_sat.flag = bei_eph.i_nav_type; /*MEO/IGSO satellite*/
rtklib_sat.iode = static_cast<int32_t>(bei_eph.d_AODE); /* AODE */
rtklib_sat.iodc = static_cast<int32_t>(bei_eph.d_AODC); /* AODC */
rtklib_sat.week = bei_eph.i_BEIDOU_week; /* week of tow */
rtklib_sat.cic = bei_eph.d_Cic;
@ -285,8 +285,8 @@ eph_t eph_to_rtklib(const Beidou_Dnav_Ephemeris& bei_eph)
/* adjustment for week handover */
double tow, toc, toe;
tow = time2gpst(rtklib_sat.ttr, &rtklib_sat.week);
toc = time2gpst(rtklib_sat.toc, NULL);
toe = time2gpst(rtklib_sat.toe, NULL);
toc = time2gpst(rtklib_sat.toc, nullptr);
toe = time2gpst(rtklib_sat.toe, nullptr);
if (rtklib_sat.toes < tow - 302400.0)
{
@ -306,7 +306,6 @@ eph_t eph_to_rtklib(const Beidou_Dnav_Ephemeris& bei_eph)
}
eph_t eph_to_rtklib(const Gps_CNAV_Ephemeris& gps_cnav_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,

View File

@ -31,6 +31,7 @@
#ifndef GNSS_SDR_RTKLIB_CONVERSIONS_H_
#define GNSS_SDR_RTKLIB_CONVERSIONS_H_
#include "beidou_dnav_ephemeris.h"
#include "galileo_almanac.h"
#include "galileo_ephemeris.h"
#include "glonass_gnav_ephemeris.h"
@ -39,7 +40,6 @@
#include "gps_almanac.h"
#include "gps_cnav_ephemeris.h"
#include "gps_ephemeris.h"
#include "beidou_dnav_ephemeris.h"
#include "rtklib.h"
eph_t eph_to_rtklib(const Galileo_Ephemeris& gal_eph);

View File

@ -31,11 +31,11 @@
#include "signal_generator.h"
#include "Beidou_B1I.h"
#include "GLONASS_L1_L2_CA.h"
#include "GPS_L1_CA.h"
#include "Galileo_E1.h"
#include "Galileo_E5a.h"
#include "Beidou_B1I.h"
#include "configuration_interface.h"
#include <glog/logging.h>
#include <cstdint>

View File

@ -20,39 +20,39 @@
set(TELEMETRY_DECODER_ADAPTER_SOURCES
gps_l1_ca_telemetry_decoder.cc
gps_l2c_telemetry_decoder.cc
gps_l5_telemetry_decoder.cc
gps_l5_telemetry_decoder.cc
galileo_e1b_telemetry_decoder.cc
sbas_l1_telemetry_decoder.cc
galileo_e5a_telemetry_decoder.cc
glonass_l1_ca_telemetry_decoder.cc
glonass_l2_ca_telemetry_decoder.cc
glonass_l2_ca_telemetry_decoder.cc
beidou_b1i_telemetry_decoder.cc
)
set(TELEMETRY_DECODER_ADAPTER_HEADERS
gps_l1_ca_telemetry_decoder.h
gps_l2c_telemetry_decoder.h
gps_l5_telemetry_decoder.h
gps_l5_telemetry_decoder.h
galileo_e1b_telemetry_decoder.h
sbas_l1_telemetry_decoder.h
galileo_e5a_telemetry_decoder.h
glonass_l1_ca_telemetry_decoder.h
glonass_l2_ca_telemetry_decoder.h
beidou_b1i_telemetry_decoder.h
beidou_b1i_telemetry_decoder.h
)
include_directories(
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/gnuradio_blocks
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs/libswiftcnav
${Boost_INCLUDE_DIRS}
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${GNURADIO_RUNTIME_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/gnuradio_blocks
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs/libswiftcnav
${Boost_INCLUDE_DIRS}
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${GNURADIO_RUNTIME_INCLUDE_DIRS}
)
list(SORT TELEMETRY_DECODER_ADAPTER_HEADERS)

View File

@ -31,19 +31,19 @@
#include "beidou_b1i_telemetry_decoder.h"
#include "configuration_interface.h"
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "beidou_dnav_almanac.h"
#include "beidou_dnav_ephemeris.h"
#include "beidou_dnav_iono.h"
#include "beidou_dnav_utc_model.h"
#include "configuration_interface.h"
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
using google::LogMessage;
BeidouB1iTelemetryDecoder::BeidouB1iTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
const std::string& role,
unsigned int in_streams,
unsigned int out_streams) : role_(role),
in_streams_(in_streams),
@ -68,9 +68,7 @@ BeidouB1iTelemetryDecoder::BeidouB1iTelemetryDecoder(ConfigurationInterface* con
}
BeidouB1iTelemetryDecoder::~BeidouB1iTelemetryDecoder()
{
}
BeidouB1iTelemetryDecoder::~BeidouB1iTelemetryDecoder() = default;
void BeidouB1iTelemetryDecoder::set_satellite(const Gnss_Satellite& satellite)

View File

@ -34,9 +34,9 @@
#ifndef GNSS_SDR_BEIDOU_B1I_TELEMETRY_DECODER_H_
#define GNSS_SDR_BEIDOU_B1I_TELEMETRY_DECODER_H_
#include "beidou_b1i_telemetry_decoder_cc.h"
#include "telemetry_decoder_interface.h"
#include <string>
#include "beidou_b1i_telemetry_decoder_cc.h"
class ConfigurationInterface;
@ -47,7 +47,7 @@ class BeidouB1iTelemetryDecoder : public TelemetryDecoderInterface
{
public:
BeidouB1iTelemetryDecoder(ConfigurationInterface* configuration,
std::string role,
const std::string& role,
unsigned int in_streams,
unsigned int out_streams);

View File

@ -17,38 +17,38 @@
#
set(TELEMETRY_DECODER_GR_BLOCKS_SOURCES
gps_l1_ca_telemetry_decoder_cc.cc
gps_l2c_telemetry_decoder_cc.cc
gps_l5_telemetry_decoder_cc.cc
sbas_l1_telemetry_decoder_cc.cc
glonass_l1_ca_telemetry_decoder_cc.cc
glonass_l2_ca_telemetry_decoder_cc.cc
galileo_telemetry_decoder_cc.cc
beidou_b1i_telemetry_decoder_cc.cc
gps_l1_ca_telemetry_decoder_cc.cc
gps_l2c_telemetry_decoder_cc.cc
gps_l5_telemetry_decoder_cc.cc
sbas_l1_telemetry_decoder_cc.cc
glonass_l1_ca_telemetry_decoder_cc.cc
glonass_l2_ca_telemetry_decoder_cc.cc
galileo_telemetry_decoder_cc.cc
beidou_b1i_telemetry_decoder_cc.cc
)
set(TELEMETRY_DECODER_GR_BLOCKS_HEADERS
gps_l1_ca_telemetry_decoder_cc.h
gps_l2c_telemetry_decoder_cc.h
gps_l5_telemetry_decoder_cc.h
sbas_l1_telemetry_decoder_cc.h
glonass_l1_ca_telemetry_decoder_cc.h
glonass_l2_ca_telemetry_decoder_cc.h
galileo_telemetry_decoder_cc.h
beidou_b1i_telemetry_decoder_cc.h
gps_l1_ca_telemetry_decoder_cc.h
gps_l2c_telemetry_decoder_cc.h
gps_l5_telemetry_decoder_cc.h
sbas_l1_telemetry_decoder_cc.h
glonass_l1_ca_telemetry_decoder_cc.h
glonass_l2_ca_telemetry_decoder_cc.h
galileo_telemetry_decoder_cc.h
beidou_b1i_telemetry_decoder_cc.h
)
include_directories(
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs/libswiftcnav
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GNURADIO_RUNTIME_INCLUDE_DIRS}
${VOLK_GNSSSDR_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs/libswiftcnav
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GNURADIO_RUNTIME_INCLUDE_DIRS}
${VOLK_GNSSSDR_INCLUDE_DIRS}
)
list(SORT TELEMETRY_DECODER_GR_BLOCKS_HEADERS)
@ -70,5 +70,5 @@ target_link_libraries(telemetry_decoder_gr_blocks
)
if(NOT VOLKGNSSSDR_FOUND)
add_dependencies(telemetry_decoder_gr_blocks volk_gnsssdr_module)
add_dependencies(telemetry_decoder_gr_blocks volk_gnsssdr_module)
endif()

View File

@ -38,8 +38,8 @@
#include "display.h"
#include "gnss_synchro.h"
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk_gnsssdr/volk_gnsssdr.h>
#include <iostream>
@ -58,66 +58,66 @@ beidou_b1i_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump)
beidou_b1i_telemetry_decoder_cc::beidou_b1i_telemetry_decoder_cc(
const Gnss_Satellite &satellite,
bool dump) : gr::block("beidou_b1i_telemetry_decoder_cc",
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{
// 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 BeiDou B1i Telemetry Decoding for satellite "<< this->d_satellite;
LOG(INFO) << "Initializing BeiDou B1i Telemetry Decoding for satellite " << this->d_satellite;
d_samples_per_symbol = (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS) / BEIDOU_D1NAV_SYMBOL_RATE_SPS;
d_symbols_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS;
d_samples_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS * d_samples_per_symbol;
d_secondary_code_symbols = static_cast<int32_t *>(volk_gnsssdr_malloc(BEIDOU_B1I_SECONDARY_CODE_LENGTH * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_samples = static_cast<int32_t *>(volk_gnsssdr_malloc(d_samples_per_preamble * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_period_samples = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS*d_samples_per_symbol;
d_subframe_length_symbols = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS;
d_symbols_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS;
d_samples_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS * d_samples_per_symbol;
d_secondary_code_symbols = static_cast<int32_t *>(volk_gnsssdr_malloc(BEIDOU_B1I_SECONDARY_CODE_LENGTH * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_samples = static_cast<int32_t *>(volk_gnsssdr_malloc(d_samples_per_preamble * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_period_samples = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS * d_samples_per_symbol;
d_subframe_length_symbols = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS;
// Setting samples of secondary code
for (int32_t i = 0; i < BEIDOU_B1I_SECONDARY_CODE_LENGTH; i++)
{
if (BEIDOU_B1I_SECONDARY_CODE.at(i) == '1')
{
d_secondary_code_symbols[i] = 1;
}
else
{
d_secondary_code_symbols[i] = -1;
}
}
// Setting samples of secondary code
for (int32_t i = 0; i < BEIDOU_B1I_SECONDARY_CODE_LENGTH; i++)
{
if (BEIDOU_B1I_SECONDARY_CODE.at(i) == '1')
{
d_secondary_code_symbols[i] = 1;
}
else
{
d_secondary_code_symbols[i] = -1;
}
}
// Setting samples of preamble code
int32_t n = 0;
for (int32_t i = 0; i < d_symbols_per_preamble; i++)
{
int32_t m = 0;
if (BEIDOU_DNAV_PREAMBLE.at(i) == '1')
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = d_secondary_code_symbols[m];
n++;
m++;
m = m % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
else
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = -d_secondary_code_symbols[m];
n++;
m++;
m = m % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
}
// Setting samples of preamble code
int32_t n = 0;
for (int32_t i = 0; i < d_symbols_per_preamble; i++)
{
int32_t m = 0;
if (BEIDOU_DNAV_PREAMBLE.at(i) == '1')
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = d_secondary_code_symbols[m];
n++;
m++;
m = m % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
else
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = -d_secondary_code_symbols[m];
n++;
m++;
m = m % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
}
d_subframe_symbols = static_cast<double *>(volk_gnsssdr_malloc(d_subframe_length_symbols * sizeof(double), volk_gnsssdr_get_alignment()));
d_required_symbols = BEIDOU_DNAV_SUBFRAME_SYMBOLS*d_samples_per_symbol + d_samples_per_preamble;
d_subframe_symbols = static_cast<double *>(volk_gnsssdr_malloc(d_subframe_length_symbols * sizeof(double), volk_gnsssdr_get_alignment()));
d_required_symbols = BEIDOU_DNAV_SUBFRAME_SYMBOLS * d_samples_per_symbol + d_samples_per_preamble;
// Generic settings
d_sample_counter = 0;
@ -130,13 +130,12 @@ beidou_b1i_telemetry_decoder_cc::beidou_b1i_telemetry_decoder_cc(
d_flag_preamble = false;
d_channel = 0;
flag_SOW_set = false;
}
beidou_b1i_telemetry_decoder_cc::~beidou_b1i_telemetry_decoder_cc()
{
volk_gnsssdr_free(d_preamble_samples);
volk_gnsssdr_free(d_preamble_samples);
volk_gnsssdr_free(d_secondary_code_symbols);
volk_gnsssdr_free(d_subframe_symbols);
@ -154,7 +153,7 @@ beidou_b1i_telemetry_decoder_cc::~beidou_b1i_telemetry_decoder_cc()
}
void beidou_b1i_telemetry_decoder_cc::decode_bch15_11_01(int32_t *bits, int32_t *decbits)
void beidou_b1i_telemetry_decoder_cc::decode_bch15_11_01(const int32_t *bits, int32_t *decbits)
{
int bit, err, reg[4] = {1, 1, 1, 1};
int errind[15] = {14, 13, 10, 12, 6, 9, 4, 11, 0, 5, 7, 8, 1, 3, 2};
@ -174,7 +173,7 @@ void beidou_b1i_telemetry_decoder_cc::decode_bch15_11_01(int32_t *bits, int32_t
reg[1] *= bit;
}
err = errind[reg[0] + reg[1]*2 + reg[2]*4 + reg[3]*8];
err = errind[reg[0] + reg[1] * 2 + reg[2] * 4 + reg[3] * 8];
if (err > 0)
{
@ -183,82 +182,80 @@ void beidou_b1i_telemetry_decoder_cc::decode_bch15_11_01(int32_t *bits, int32_t
}
void beidou_b1i_telemetry_decoder_cc::decode_word(
int32_t word_counter,
double* enc_word_symbols,
int32_t* dec_word_symbols)
int32_t word_counter,
const double *enc_word_symbols,
int32_t *dec_word_symbols)
{
int32_t bitsbch[30], first_branch[15], second_branch[15];
if (word_counter == 1)
{
for (unsigned int j = 0; j < 30; j++)
{
dec_word_symbols[j] = (int32_t)(enc_word_symbols[j] > 0) ? (1) : (-1);
}
}
{
dec_word_symbols[j] = (int32_t)(enc_word_symbols[j] > 0) ? (1) : (-1);
}
}
else
{
for (unsigned int r = 0; r < 2; r++)
{
for (unsigned int c = 0; c < 15; c++)
for (unsigned int r = 0; r < 2; r++)
{
for (unsigned int c = 0; c < 15; c++)
{
bitsbch[r*15 + c] = (int32_t)(enc_word_symbols[c*2 + r] > 0) ? (1) : (-1);
bitsbch[r * 15 + c] = (int32_t)(enc_word_symbols[c * 2 + r] > 0) ? (1) : (-1);
}
}
}
decode_bch15_11_01(&bitsbch[0], first_branch);
decode_bch15_11_01(&bitsbch[15], second_branch);
for (unsigned int j = 0; j < 11; j++)
{
dec_word_symbols[j] = first_branch[j];
dec_word_symbols[j + 11] = second_branch[j];
}
for (unsigned int j = 0; j < 11; j++)
{
dec_word_symbols[j] = first_branch[j];
dec_word_symbols[j + 11] = second_branch[j];
}
for (unsigned int j = 0; j < 4; j++)
{
dec_word_symbols[j + 22] = first_branch[11 + j];
dec_word_symbols[j + 26] = second_branch[11 + j];
}
for (unsigned int j = 0; j < 4; j++)
{
dec_word_symbols[j + 22] = first_branch[11 + j];
dec_word_symbols[j + 26] = second_branch[11 + j];
}
}
}
void beidou_b1i_telemetry_decoder_cc::decode_subframe(double *frame_symbols, int32_t frame_length)
{
// 1. Transform from symbols to bits
// 1. Transform from symbols to bits
std::string data_bits;
int32_t dec_word_bits[30];
// Decode each word in subframe
for(uint32_t ii = 0; ii < BEIDOU_DNAV_WORDS_SUBFRAME; ii++)
{
// decode the word
decode_word((ii+1), &frame_symbols[ii*30], dec_word_bits);
for (uint32_t ii = 0; ii < BEIDOU_DNAV_WORDS_SUBFRAME; ii++)
{
// decode the word
decode_word((ii + 1), &frame_symbols[ii * 30], dec_word_bits);
// Save word to string format
for (uint32_t jj = 0; jj < (BEIDOU_DNAV_WORD_LENGTH_BITS); jj++)
{
data_bits.push_back( (dec_word_bits[jj] > 0) ? ('1') : ('0') );
}
}
// Save word to string format
for (uint32_t jj = 0; jj < (BEIDOU_DNAV_WORD_LENGTH_BITS); jj++)
{
data_bits.push_back((dec_word_bits[jj] > 0) ? ('1') : ('0'));
}
}
if ( d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6 )
{
d_nav.d2_subframe_decoder(data_bits);
}
else
{
d_nav.d1_subframe_decoder(data_bits);
}
if (d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6)
{
d_nav.d2_subframe_decoder(data_bits);
}
else
{
d_nav.d1_subframe_decoder(data_bits);
}
// 3. Check operation executed correctly
if (d_nav.flag_crc_test == true)
{
LOG(INFO) << "BeiDou DNAV CRC correct in channel " << d_channel << " from satellite " << d_satellite;
LOG(INFO) << "BeiDou DNAV CRC correct in channel " << d_channel << " from satellite " << d_satellite;
}
else
{
@ -268,7 +265,7 @@ void beidou_b1i_telemetry_decoder_cc::decode_subframe(double *frame_symbols, int
if (d_nav.have_new_ephemeris() == true)
{
// get object for this SV (mandatory)
std::shared_ptr<Beidou_Dnav_Ephemeris> tmp_obj = std::make_shared<Beidou_Dnav_Ephemeris>(d_nav.get_ephemeris());
std::shared_ptr<Beidou_Dnav_Ephemeris> tmp_obj = std::make_shared<Beidou_Dnav_Ephemeris>(d_nav.get_ephemeris());
this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "BEIDOU DNAV Ephemeris have been received in channel" << d_channel << " from satellite " << d_satellite;
std::cout << "New BEIDOU B1I DNAV message received in channel " << d_channel << ": ephemeris from satellite " << d_satellite << std::endl;
@ -291,9 +288,9 @@ void beidou_b1i_telemetry_decoder_cc::decode_subframe(double *frame_symbols, int
}
if (d_nav.have_new_almanac() == true)
{
// unsigned int slot_nbr = d_nav.i_alm_satellite_PRN;
// std::shared_ptr<Beidou_Dnav_Almanac> tmp_obj = std::make_shared<Beidou_Dnav_Almanac>(d_nav.get_almanac(slot_nbr));
// this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
// unsigned int slot_nbr = d_nav.i_alm_satellite_PRN;
// std::shared_ptr<Beidou_Dnav_Almanac> tmp_obj = std::make_shared<Beidou_Dnav_Almanac>(d_nav.get_almanac(slot_nbr));
// this->message_port_pub(pmt::mp("telemetry"), pmt::make_any(tmp_obj));
LOG(INFO) << "BEIDOU DNAV Almanac have been received in channel" << d_channel << " from satellite " << d_satellite << std::endl;
std::cout << "New BEIDOU B1I DNAV almanac received in channel " << d_channel << " from satellite " << d_satellite << std::endl;
}
@ -302,7 +299,7 @@ void beidou_b1i_telemetry_decoder_cc::decode_subframe(double *frame_symbols, int
void beidou_b1i_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satellite)
{
uint32_t sat_prn = 0;
uint32_t sat_prn = 0;
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;
@ -312,46 +309,46 @@ void beidou_b1i_telemetry_decoder_cc::set_satellite(const Gnss_Satellite &satell
d_nav.i_satellite_PRN = sat_prn;
// Update tel dec parameters for D2 NAV Messages
if ( sat_prn > 0 and sat_prn < 6 )
{
// Clear values from previous declaration
volk_gnsssdr_free(d_preamble_samples);
volk_gnsssdr_free(d_secondary_code_symbols);
volk_gnsssdr_free(d_subframe_symbols);
if (sat_prn > 0 and sat_prn < 6)
{
// Clear values from previous declaration
volk_gnsssdr_free(d_preamble_samples);
volk_gnsssdr_free(d_secondary_code_symbols);
volk_gnsssdr_free(d_subframe_symbols);
d_samples_per_symbol = (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS) / BEIDOU_D2NAV_SYMBOL_RATE_SPS;
d_symbols_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS;
d_samples_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS * d_samples_per_symbol;
d_secondary_code_symbols = nullptr;
d_preamble_samples = static_cast<int32_t *>(volk_gnsssdr_malloc(d_samples_per_preamble * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_period_samples = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS*d_samples_per_symbol;
d_subframe_length_symbols = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS;
d_samples_per_symbol = (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS) / BEIDOU_D2NAV_SYMBOL_RATE_SPS;
d_symbols_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS;
d_samples_per_preamble = BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS * d_samples_per_symbol;
d_secondary_code_symbols = nullptr;
d_preamble_samples = static_cast<int32_t *>(volk_gnsssdr_malloc(d_samples_per_preamble * sizeof(int32_t), volk_gnsssdr_get_alignment()));
d_preamble_period_samples = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS * d_samples_per_symbol;
d_subframe_length_symbols = BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS;
// Setting samples of preamble code
int32_t n = 0;
for (int32_t i = 0; i < d_symbols_per_preamble; i++)
{
if (BEIDOU_DNAV_PREAMBLE.at(i) == '1')
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = 1;
n++;
}
}
else
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = -1;
n++;
}
}
}
// Setting samples of preamble code
int32_t n = 0;
for (int32_t i = 0; i < d_symbols_per_preamble; i++)
{
if (BEIDOU_DNAV_PREAMBLE.at(i) == '1')
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = 1;
n++;
}
}
else
{
for (uint32_t j = 0; j < d_samples_per_symbol; j++)
{
d_preamble_samples[n] = -1;
n++;
}
}
}
d_subframe_symbols = static_cast<double *>(volk_gnsssdr_malloc(d_subframe_length_symbols * sizeof(double), volk_gnsssdr_get_alignment()));
d_required_symbols = BEIDOU_DNAV_SUBFRAME_SYMBOLS*d_samples_per_symbol + d_samples_per_preamble;
}
d_subframe_symbols = static_cast<double *>(volk_gnsssdr_malloc(d_subframe_length_symbols * sizeof(double), volk_gnsssdr_get_alignment()));
d_required_symbols = BEIDOU_DNAV_SUBFRAME_SYMBOLS * d_samples_per_symbol + d_samples_per_preamble;
}
}
@ -367,7 +364,7 @@ void beidou_b1i_telemetry_decoder_cc::set_channel(int channel)
try
{
d_dump_filename = "telemetry";
d_dump_filename.append(boost::lexical_cast<std::string>(d_channel));
d_dump_filename.append(std::to_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);
@ -385,17 +382,17 @@ void beidou_b1i_telemetry_decoder_cc::set_channel(int channel)
int beidou_b1i_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)
{
int32_t corr_value = 0;
int32_t preamble_diff = 0;
int32_t corr_value = 0;
int32_t preamble_diff = 0;
Gnss_Synchro **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer
const Gnss_Synchro **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer pointer
auto **out = reinterpret_cast<Gnss_Synchro **>(&output_items[0]); // Get the output buffer pointer
const auto **in = reinterpret_cast<const Gnss_Synchro **>(&input_items[0]); // Get the input buffer 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.Prompt_I); //add new symbol to the symbol queue
d_sample_counter++; //count for the processed samples
d_sample_counter++; //count for the processed samples
consume_each(1);
d_flag_preamble = false;
@ -451,9 +448,9 @@ int beidou_b1i_telemetry_decoder_cc::general_work(int noutput_items __attribute_
}
}
}
else if (d_stat == 2) // preamble acquired
else if (d_stat == 2) // preamble acquired
{
if (d_sample_counter == d_preamble_index + static_cast<uint64_t>(d_preamble_period_samples))
if (d_sample_counter == d_preamble_index + static_cast<uint64_t>(d_preamble_period_samples))
{
//******* SAMPLES TO SYMBOLS *******
if (corr_value > 0) //normal PLL lock
@ -461,22 +458,22 @@ int beidou_b1i_telemetry_decoder_cc::general_work(int noutput_items __attribute_
int k = 0;
for (uint32_t i = 0; i < d_subframe_length_symbols; i++)
{
d_subframe_symbols[i] = 0;
//integrate samples into symbols
d_subframe_symbols[i] = 0;
//integrate samples into symbols
for (uint32_t m = 0; m < d_samples_per_symbol; m++)
{
if ( d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6 )
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] += d_symbol_history.at(i * d_samples_per_symbol + m);
}
else
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] += static_cast<float>(d_secondary_code_symbols[k]) * d_symbol_history.at(i * d_samples_per_symbol + m);
k++;
k = k % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
if (d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6)
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] += d_symbol_history.at(i * d_samples_per_symbol + m);
}
else
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] += static_cast<float>(d_secondary_code_symbols[k]) * d_symbol_history.at(i * d_samples_per_symbol + m);
k++;
k = k % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
}
}
@ -485,22 +482,22 @@ int beidou_b1i_telemetry_decoder_cc::general_work(int noutput_items __attribute_
int k = 0;
for (uint32_t i = 0; i < d_subframe_length_symbols; i++)
{
d_subframe_symbols[i] = 0;
//integrate samples into symbols
d_subframe_symbols[i] = 0;
//integrate samples into symbols
for (uint32_t m = 0; m < d_samples_per_symbol; m++)
{
if ( d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6 )
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] -= d_symbol_history.at(i * d_samples_per_symbol + m);
}
else
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] -= static_cast<float>(d_secondary_code_symbols[k]) * d_symbol_history.at(i * d_samples_per_symbol + m);
k++;
k = k % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
if (d_satellite.get_PRN() > 0 and d_satellite.get_PRN() < 6)
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] -= d_symbol_history.at(i * d_samples_per_symbol + m);
}
else
{
// because last symbol of the preamble is just received now!
d_subframe_symbols[i] -= static_cast<float>(d_secondary_code_symbols[k]) * d_symbol_history.at(i * d_samples_per_symbol + m);
k++;
k = k % BEIDOU_B1I_SECONDARY_CODE_LENGTH;
}
}
}
}
@ -539,15 +536,15 @@ int beidou_b1i_telemetry_decoder_cc::general_work(int noutput_items __attribute_
if (this->d_flag_preamble == true and d_nav.flag_new_SOW_available == true)
//update TOW at the preamble instant
{
// Reporting sow as gps time of week
d_TOW_at_Preamble_ms = static_cast<uint32_t>((d_nav.d_SOW + 14) * 1000.0);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * BEIDOU_B1I_CODE_PERIOD_MS);
flag_SOW_set = true;
d_nav.flag_new_SOW_available = false;
// Reporting sow as gps time of week
d_TOW_at_Preamble_ms = static_cast<uint32_t>((d_nav.d_SOW + 14) * 1000.0);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * BEIDOU_B1I_CODE_PERIOD_MS);
flag_SOW_set = true;
d_nav.flag_new_SOW_available = false;
}
else //if there is not a new preamble, we define the TOW of the current symbol
{
d_TOW_at_current_symbol_ms += static_cast<uint32_t>(BEIDOU_B1I_CODE_PERIOD_MS);
d_TOW_at_current_symbol_ms += static_cast<uint32_t>(BEIDOU_B1I_CODE_PERIOD_MS);
}

View File

@ -35,13 +35,13 @@
#ifndef GNSS_SDR_BEIDOU_B1I_TELEMETRY_DECODER_CC_H
#define GNSS_SDR_BEIDOU_B1I_TELEMETRY_DECODER_CC_H
#include "beidou_dnav_navigation_message.h"
#include "beidou_dnav_ephemeris.h"
#include "Beidou_B1I.h"
#include "beidou_dnav_almanac.h"
#include "beidou_dnav_ephemeris.h"
#include "beidou_dnav_navigation_message.h"
#include "beidou_dnav_utc_model.h"
#include "gnss_satellite.h"
#include "gnss_synchro.h"
#include "Beidou_B1I.h"
#include <gnuradio/block.h>
#include <fstream>
#include <string>
@ -63,7 +63,7 @@ beidou_b1i_telemetry_decoder_cc_sptr beidou_b1i_make_telemetry_decoder_cc(const
class beidou_b1i_telemetry_decoder_cc : public gr::block
{
public:
~beidou_b1i_telemetry_decoder_cc(); //!< Class destructor
~beidou_b1i_telemetry_decoder_cc(); //!< Class destructor
void set_satellite(const Gnss_Satellite &satellite); //!< Set satellite PRN
void set_channel(int channel); //!< Set receiver's channel
@ -75,37 +75,37 @@ public:
private:
friend beidou_b1i_telemetry_decoder_cc_sptr
beidou_b1i_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
beidou_b1i_make_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
beidou_b1i_telemetry_decoder_cc(const Gnss_Satellite &satellite, bool dump);
void decode_subframe(double *symbols, int32_t frame_length);
void decode_word(int32_t word_counter, double* enc_word_symbols, int32_t* dec_word_symbols);
void decode_bch15_11_01(int32_t *bits, int32_t *decbits);
void decode_word(int32_t word_counter, const double *enc_word_symbols, int32_t *dec_word_symbols);
void decode_bch15_11_01(const int32_t *bits, int32_t *decbits);
//!< Preamble decoding
unsigned short int d_preambles_symbols[BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS];
int32_t *d_preamble_samples;
int32_t *d_secondary_code_symbols;
uint32_t d_samples_per_symbol;
int32_t d_symbols_per_preamble;
int32_t d_samples_per_preamble;
int32_t d_preamble_period_samples;
double *d_subframe_symbols;
uint32_t d_subframe_length_symbols;
uint32_t d_required_symbols;
int32_t *d_preamble_samples;
int32_t *d_secondary_code_symbols;
uint32_t d_samples_per_symbol;
int32_t d_symbols_per_preamble;
int32_t d_samples_per_preamble;
int32_t d_preamble_period_samples;
double *d_subframe_symbols;
uint32_t d_subframe_length_symbols;
uint32_t d_required_symbols;
//!< Storage for incoming data
std::deque<float> d_symbol_history;
//!< Variables for internal functionality
uint64_t d_sample_counter; //!< Sample counter as an index (1,2,3,..etc) indicating number of samples processed
uint64_t d_preamble_index; //!< Index of sample number where preamble was found
uint32_t d_stat; //!< Status of decoder
bool d_flag_frame_sync; //!< Indicate when a frame sync is achieved
bool d_flag_preamble; //!< Flag indicating when preamble was found
int32_t d_CRC_error_counter; //!< Number of failed CRC operations
bool flag_SOW_set; //!< Indicates when time of week is set
uint64_t d_sample_counter; //!< Sample counter as an index (1,2,3,..etc) indicating number of samples processed
uint64_t d_preamble_index; //!< Index of sample number where preamble was found
uint32_t d_stat; //!< Status of decoder
bool d_flag_frame_sync; //!< Indicate when a frame sync is achieved
bool d_flag_preamble; //!< Flag indicating when preamble was found
int32_t d_CRC_error_counter; //!< Number of failed CRC operations
bool flag_SOW_set; //!< Indicates when time of week is set
//!< Navigation Message variable
Beidou_Dnav_Navigation_Message d_nav;

View File

@ -20,23 +20,23 @@
add_subdirectory(libswiftcnav)
set(TELEMETRY_DECODER_LIB_SOURCES
viterbi_decoder.cc
viterbi_decoder.cc
)
set(TELEMETRY_DECODER_LIB_HEADERS
viterbi_decoder.h
convolutional.h
viterbi_decoder.h
convolutional.h
)
include_directories(
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/adapters
${Boost_INCLUDE_DIRS}
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/system_parameters
${CMAKE_SOURCE_DIR}/src/core/interfaces
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/adapters
${Boost_INCLUDE_DIRS}
${GLOG_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
)
list(SORT TELEMETRY_DECODER_LIB_HEADERS)

View File

@ -35,56 +35,56 @@ endif()
if(ENABLE_FPGA)
set(OPT_TRACKING_ADAPTERS_SOURCES
${OPT_TRACKING_ADAPTERS_SOURCES}
gps_l1_ca_dll_pll_tracking_fpga.cc
gps_l2_m_dll_pll_tracking_fpga.cc
galileo_e1_dll_pll_veml_tracking_fpga.cc
galileo_e5a_dll_pll_tracking_fpga.cc
gps_l1_ca_dll_pll_tracking_fpga.cc
gps_l2_m_dll_pll_tracking_fpga.cc
galileo_e1_dll_pll_veml_tracking_fpga.cc
galileo_e5a_dll_pll_tracking_fpga.cc
gps_l5_dll_pll_tracking_fpga.cc
)
set(OPT_TRACKING_ADAPTERS_HEADERS
${OPT_TRACKING_ADAPTERS_HEADERS}
gps_l1_ca_dll_pll_tracking_fpga.h
gps_l2_m_dll_pll_tracking_fpga.h
galileo_e1_dll_pll_veml_tracking_fpga.h
galileo_e5a_dll_pll_tracking_fpga.h
gps_l1_ca_dll_pll_tracking_fpga.h
gps_l2_m_dll_pll_tracking_fpga.h
galileo_e1_dll_pll_veml_tracking_fpga.h
galileo_e5a_dll_pll_tracking_fpga.h
gps_l5_dll_pll_tracking_fpga.h
)
endif()
set(TRACKING_ADAPTER_SOURCES
galileo_e1_dll_pll_veml_tracking.cc
galileo_e1_tcp_connector_tracking.cc
gps_l1_ca_dll_pll_tracking.cc
gps_l1_ca_dll_pll_c_aid_tracking.cc
gps_l1_ca_tcp_connector_tracking.cc
galileo_e5a_dll_pll_tracking.cc
gps_l2_m_dll_pll_tracking.cc
glonass_l1_ca_dll_pll_tracking.cc
glonass_l1_ca_dll_pll_c_aid_tracking.cc
gps_l1_ca_kf_tracking.cc
gps_l5_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_c_aid_tracking.cc
beidou_b1i_dll_pll_tracking.cc
${OPT_TRACKING_ADAPTERS_SOURCES}
galileo_e1_dll_pll_veml_tracking.cc
galileo_e1_tcp_connector_tracking.cc
gps_l1_ca_dll_pll_tracking.cc
gps_l1_ca_dll_pll_c_aid_tracking.cc
gps_l1_ca_tcp_connector_tracking.cc
galileo_e5a_dll_pll_tracking.cc
gps_l2_m_dll_pll_tracking.cc
glonass_l1_ca_dll_pll_tracking.cc
glonass_l1_ca_dll_pll_c_aid_tracking.cc
gps_l1_ca_kf_tracking.cc
gps_l5_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_tracking.cc
glonass_l2_ca_dll_pll_c_aid_tracking.cc
beidou_b1i_dll_pll_tracking.cc
${OPT_TRACKING_ADAPTERS_SOURCES}
)
set(TRACKING_ADAPTER_HEADERS
galileo_e1_dll_pll_veml_tracking.h
galileo_e1_tcp_connector_tracking.h
gps_l1_ca_dll_pll_tracking.h
gps_l1_ca_dll_pll_c_aid_tracking.h
gps_l1_ca_tcp_connector_tracking.h
galileo_e5a_dll_pll_tracking.h
gps_l2_m_dll_pll_tracking.h
glonass_l1_ca_dll_pll_tracking.h
glonass_l1_ca_dll_pll_c_aid_tracking.h
gps_l1_ca_kf_tracking.h
gps_l5_dll_pll_tracking.h
glonass_l2_ca_dll_pll_tracking.h
glonass_l2_ca_dll_pll_c_aid_tracking.h
beidou_b1i_dll_pll_tracking.h
${OPT_TRACKING_ADAPTERS_HEADERS}
galileo_e1_dll_pll_veml_tracking.h
galileo_e1_tcp_connector_tracking.h
gps_l1_ca_dll_pll_tracking.h
gps_l1_ca_dll_pll_c_aid_tracking.h
gps_l1_ca_tcp_connector_tracking.h
galileo_e5a_dll_pll_tracking.h
gps_l2_m_dll_pll_tracking.h
glonass_l1_ca_dll_pll_tracking.h
glonass_l1_ca_dll_pll_c_aid_tracking.h
gps_l1_ca_kf_tracking.h
gps_l5_dll_pll_tracking.h
glonass_l2_ca_dll_pll_tracking.h
glonass_l2_ca_dll_pll_c_aid_tracking.h
beidou_b1i_dll_pll_tracking.h
${OPT_TRACKING_ADAPTERS_HEADERS}
)
include_directories(

View File

@ -34,21 +34,21 @@
* -------------------------------------------------------------------------
*/
#include "dll_pll_conf.h"
#include "beidou_b1i_dll_pll_tracking.h"
#include "configuration_interface.h"
#include "gnss_sdr_flags.h"
#include "display.h"
#include <glog/logging.h>
#include "Beidou_B1I.h"
#include "configuration_interface.h"
#include "display.h"
#include "dll_pll_conf.h"
#include "gnss_sdr_flags.h"
#include <glog/logging.h>
using google::LogMessage;
BeidouB1iDllPllTracking::BeidouB1iDllPllTracking(
ConfigurationInterface* configuration, std::string role,
ConfigurationInterface* configuration, const std::string& role,
unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{
Dll_Pll_Conf trk_param = Dll_Pll_Conf();
Dll_Pll_Conf trk_param = Dll_Pll_Conf();
DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ########################
std::string default_item_type = "gr_complex";
@ -118,7 +118,7 @@ BeidouB1iDllPllTracking::BeidouB1iDllPllTracking(
trk_param.carrier_lock_th = carrier_lock_th;
//################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0)
if (item_type == "gr_complex")
{
item_size_ = sizeof(gr_complex);
tracking_ = dll_pll_veml_make_tracking(trk_param);
@ -141,9 +141,7 @@ BeidouB1iDllPllTracking::BeidouB1iDllPllTracking(
}
BeidouB1iDllPllTracking::~BeidouB1iDllPllTracking()
{
}
BeidouB1iDllPllTracking::~BeidouB1iDllPllTracking() = default;
void BeidouB1iDllPllTracking::start_tracking()

View File

@ -37,8 +37,8 @@
#ifndef GNSS_SDR_BEIDOU_B1I_DLL_PLL_TRACKING_H_
#define GNSS_SDR_BEIDOU_B1I_DLL_PLL_TRACKING_H_
#include "tracking_interface.h"
#include "dll_pll_veml_tracking.h"
#include "tracking_interface.h"
#include <string>
class ConfigurationInterface;
@ -50,7 +50,7 @@ class BeidouB1iDllPllTracking : public TrackingInterface
{
public:
BeidouB1iDllPllTracking(ConfigurationInterface* configuration,
std::string role,
const std::string& role,
unsigned int in_streams,
unsigned int out_streams);

View File

@ -35,17 +35,17 @@
*/
#include "dll_pll_veml_tracking.h"
#include "Beidou_B1I.h"
#include "GPS_L1_CA.h"
#include "GPS_L2C.h"
#include "GPS_L5.h"
#include "Galileo_E1.h"
#include "Galileo_E5a.h"
#include "Beidou_B1I.h"
#include "MATH_CONSTANTS.h"
#include "beidou_b1i_signal_processing.h"
#include "control_message_factory.h"
#include "galileo_e1_signal_processing.h"
#include "galileo_e5_signal_processing.h"
#include "beidou_b1i_signal_processing.h"
#include "gnss_sdr_create_directory.h"
#include "gps_l2c_signal.h"
#include "gps_l5_signal.h"
@ -279,19 +279,19 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(const Dll_Pll_Conf &conf_) : gr::bl
systemName = "Beidou";
if (signal_type == "B1")
{
// GEO Satellites use different secondary code
d_signal_carrier_freq = BEIDOU_B1I_FREQ_HZ;
d_code_period = BEIDOU_B1I_CODE_PERIOD;
d_code_chip_rate = BEIDOU_B1I_CODE_RATE_HZ;
d_code_length_chips = static_cast<unsigned int>(BEIDOU_B1I_CODE_LENGTH_CHIPS);
d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT;
d_correlation_length_ms = 1;
d_code_samples_per_chip = 1;
d_secondary = true;
trk_parameters.track_pilot = false;
interchange_iq = false;
d_secondary_code_length = static_cast<unsigned int>(BEIDOU_B1I_SECONDARY_CODE_LENGTH);
d_secondary_code_string = const_cast<std::string *>(&BEIDOU_B1I_SECONDARY_CODE_STR);
// GEO Satellites use different secondary code
d_signal_carrier_freq = BEIDOU_B1I_FREQ_HZ;
d_code_period = BEIDOU_B1I_CODE_PERIOD;
d_code_chip_rate = BEIDOU_B1I_CODE_RATE_HZ;
d_code_length_chips = static_cast<unsigned int>(BEIDOU_B1I_CODE_LENGTH_CHIPS);
d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT;
d_correlation_length_ms = 1;
d_code_samples_per_chip = 1;
d_secondary = true;
trk_parameters.track_pilot = false;
interchange_iq = false;
d_secondary_code_length = static_cast<unsigned int>(BEIDOU_B1I_SECONDARY_CODE_LENGTH);
d_secondary_code_string = const_cast<std::string *>(&BEIDOU_B1I_SECONDARY_CODE_STR);
}
else
{
@ -575,41 +575,40 @@ void dll_pll_veml_tracking::start_tracking()
{
beidou_b1i_code_gen_float(d_tracking_code, d_acquisition_gnss_synchro->PRN, 0);
// Update secondary code settings for geo satellites
if(d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6)
if (d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6)
{
d_symbols_per_bit = 2;
d_correlation_length_ms = 1;
d_code_samples_per_chip = 1;
d_secondary = false;
trk_parameters.track_pilot = false;
interchange_iq = false;
d_secondary_code_length = 0;
d_secondary_code_string = const_cast<std::string *>(&BEIDOU_B1I_D2_SECONDARY_CODE_STR);
d_symbols_per_bit = 2;
d_correlation_length_ms = 1;
d_code_samples_per_chip = 1;
d_secondary = false;
trk_parameters.track_pilot = false;
interchange_iq = false;
d_secondary_code_length = 0;
d_secondary_code_string = const_cast<std::string *>(&BEIDOU_B1I_D2_SECONDARY_CODE_STR);
// preamble bits to sampled symbols
d_preamble_length_symbols = 22;
d_preambles_symbols = static_cast<int32_t *>(volk_gnsssdr_malloc(22 * sizeof(int32_t), volk_gnsssdr_get_alignment()));
int32_t n = 0;
uint16_t preambles_bits[BEIDOU_B1I_PREAMBLE_LENGTH_BITS] = {1,1,1,0,0,0,1,0,0,1,0};
for (uint16_t preambles_bit : preambles_bits)
{
for (uint32_t j = 0; j < d_symbols_per_bit; j++)
{
if (preambles_bit == 1)
{
d_preambles_symbols[n] = 1;
}
else
{
d_preambles_symbols[n] = -1;
}
n++;
}
}
d_symbol_history.resize(22); // Change fixed buffer size
d_symbol_history.clear();
// preamble bits to sampled symbols
d_preamble_length_symbols = 22;
d_preambles_symbols = static_cast<int32_t *>(volk_gnsssdr_malloc(22 * sizeof(int32_t), volk_gnsssdr_get_alignment()));
int32_t n = 0;
uint16_t preambles_bits[BEIDOU_B1I_PREAMBLE_LENGTH_BITS] = {1, 1, 1, 0, 0, 0, 1, 0, 0, 1, 0};
for (uint16_t preambles_bit : preambles_bits)
{
for (uint32_t j = 0; j < d_symbols_per_bit; j++)
{
if (preambles_bit == 1)
{
d_preambles_symbols[n] = 1;
}
else
{
d_preambles_symbols[n] = -1;
}
n++;
}
}
d_symbol_history.resize(22); // Change fixed buffer size
d_symbol_history.clear();
}
}
multicorrelator_cpu.set_local_code_and_taps(d_code_samples_per_chip * d_code_length_chips, d_tracking_code, d_local_code_shift_chips);
@ -732,7 +731,7 @@ bool dll_pll_veml_tracking::acquire_secondary()
return true;
}
return false;
return false;
}
@ -746,29 +745,29 @@ bool dll_pll_veml_tracking::cn0_and_tracking_lock_status(double coh_integration_
d_cn0_estimation_counter++;
return true;
}
d_cn0_estimation_counter = 0;
// Code lock indicator
d_CN0_SNV_dB_Hz = cn0_svn_estimator(d_Prompt_buffer, trk_parameters.cn0_samples, coh_integration_time_s);
// Carrier lock indicator
d_carrier_lock_test = carrier_lock_detector(d_Prompt_buffer, trk_parameters.cn0_samples);
// Loss of lock detection
if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < trk_parameters.cn0_min)
{
d_carrier_lock_fail_counter++;
}
else
{
if (d_carrier_lock_fail_counter > 0) d_carrier_lock_fail_counter--;
}
if (d_carrier_lock_fail_counter > trk_parameters.max_lock_fail)
{
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0;
return false;
}
return true;
d_cn0_estimation_counter = 0;
// Code lock indicator
d_CN0_SNV_dB_Hz = cn0_svn_estimator(d_Prompt_buffer, trk_parameters.cn0_samples, coh_integration_time_s);
// Carrier lock indicator
d_carrier_lock_test = carrier_lock_detector(d_Prompt_buffer, trk_parameters.cn0_samples);
// Loss of lock detection
if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < trk_parameters.cn0_min)
{
d_carrier_lock_fail_counter++;
}
else
{
if (d_carrier_lock_fail_counter > 0) d_carrier_lock_fail_counter--;
}
if (d_carrier_lock_fail_counter > trk_parameters.max_lock_fail)
{
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0;
return false;
}
return true;
}
@ -1452,7 +1451,7 @@ int dll_pll_veml_tracking::general_work(int noutput_items __attribute__((unused)
DLOG(INFO) << "PULL-IN Doppler [Hz] = " << d_carrier_doppler_hz
<< ". PULL-IN Code Phase [samples] = " << d_acq_code_phase_samples;
consume_each(samples_offset); // shift input to perform alignment with local replica
consume_each(samples_offset); // shift input to perform alignment with local replica
return 0;
}
case 2: // Wide tracking and symbol synchronization
@ -1492,8 +1491,8 @@ int dll_pll_veml_tracking::general_work(int noutput_items __attribute__((unused)
next_state = acquire_secondary();
if (next_state)
{
LOG(INFO) << systemName << " " << signal_pretty_name << " secondary code locked in channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << systemName << " " << signal_pretty_name << " secondary code locked in channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
std::cout << systemName << " " << signal_pretty_name << " secondary code locked in channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
}
@ -1525,7 +1524,7 @@ int dll_pll_veml_tracking::general_work(int noutput_items __attribute__((unused)
}
if (corr_value == d_preamble_length_symbols)
{
LOG(INFO) << systemName << " " << signal_pretty_name << " tracking preamble detected in channel " << d_channel
LOG(INFO) << systemName << " " << signal_pretty_name << " tracking preamble detected in channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName, d_acquisition_gnss_synchro->PRN) << std::endl;
next_state = true;
}

View File

@ -38,6 +38,9 @@
#include "gnss_block_factory.h"
#include "array_signal_conditioner.h"
#include "beamformer_filter.h"
#include "beidou_b1i_dll_pll_tracking.h"
#include "beidou_b1i_pcps_acquisition.h"
#include "beidou_b1i_telemetry_decoder.h"
#include "byte_to_short.h"
#include "channel.h"
#include "configuration_interface.h"
@ -65,9 +68,6 @@
#include "glonass_l2_ca_dll_pll_tracking.h"
#include "glonass_l2_ca_pcps_acquisition.h"
#include "glonass_l2_ca_telemetry_decoder.h"
#include "beidou_b1i_pcps_acquisition.h"
#include "beidou_b1i_dll_pll_tracking.h"
#include "beidou_b1i_telemetry_decoder.h"
#include "gnss_block_interface.h"
#include "gps_l1_ca_dll_pll_c_aid_tracking.h"
#include "gps_l1_ca_dll_pll_tracking.h"
@ -289,12 +289,12 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetObservables(std::shared
Galileo_channels +
GPS_channels +
Glonass_channels +
Beidou_channels +
Beidou_channels +
extra_channels,
Galileo_channels +
Galileo_channels +
GPS_channels +
Glonass_channels +
Beidou_channels);
Beidou_channels);
}
@ -312,7 +312,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetPVT(std::shared_ptr<Con
Glonass_channels += configuration->property("Channels_2G.count", 0);
unsigned int Beidou_channels = configuration->property("Channels_B1.count", 0);
return GetBlock(configuration, "PVT", implementation,
Galileo_channels + GPS_channels + Glonass_channels + Beidou_channels, 0);
Galileo_channels + GPS_channels + Glonass_channels + Beidou_channels, 0);
}
@ -798,7 +798,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_B1(
<< acq << ", Tracking Implementation: " << trk << ", Telemetry Decoder implementation: " << tlm;
std::string aux = configuration->property("Acquisition_B1" + std::to_string(channel) + ".implementation", std::string("W"));
std::string appendix1;
if (aux.compare("W") != 0)
if (aux != "W")
{
appendix1 = std::to_string(channel);
}
@ -808,7 +808,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_B1(
}
aux = configuration->property("Tracking_B1" + std::to_string(channel) + ".implementation", std::string("W"));
std::string appendix2;
if (aux.compare("W") != 0)
if (aux != "W")
{
appendix2 = std::to_string(channel);
}
@ -818,7 +818,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_B1(
}
aux = configuration->property("TelemetryDecoder_B1" + std::to_string(channel) + ".implementation", std::string("W"));
std::string appendix3;
if (aux.compare("W") != 0)
if (aux != "W")
{
appendix3 = std::to_string(channel);
}
@ -1117,7 +1117,6 @@ std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GNSSBlockFacto
queue);
channel_absolute_id++;
}
}
catch (const std::exception &e)
{
@ -1613,7 +1612,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
else if (implementation == "GPS_L1_CA_KF_Tracking")
{
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaKfTracking(configuration.get(), role, in_streams,
out_streams));
out_streams));
block = std::move(block_);
}
else if (implementation == "GPS_L1_CA_DLL_PLL_C_Aid_Tracking")
@ -2014,7 +2013,7 @@ std::unique_ptr<TrackingInterface> GNSSBlockFactory::GetTrkBlock(
else if (implementation == "GPS_L1_CA_KF_Tracking")
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaKfTracking(configuration.get(), role, in_streams,
out_streams));
out_streams));
block = std::move(block_);
}
else if (implementation == "GPS_L1_CA_DLL_PLL_C_Aid_Tracking")

View File

@ -1024,13 +1024,13 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
break;
case evBDS_B1:
available_BDS_B1_signals_.push_back(channels_[who]->get_signal());
available_BDS_B1_signals_.push_back(channels_[who]->get_signal());
break;
default:
LOG(ERROR) << "This should not happen :-(";
break;
}
}
}
channels_state_[who] = 0;
acq_channels_count_--;
@ -1561,7 +1561,7 @@ void GNSSFlowgraph::set_signals_list()
std::set<unsigned int> available_beidou_prn = {1, 2, 3, 4, 5, 6, 7, 8, 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};
30, 31, 32, 33, 34, 35, 36, 37};
std::string sv_list = configuration_->property("Galileo.prns", std::string(""));
@ -1627,7 +1627,7 @@ void GNSSFlowgraph::set_signals_list()
}
}
sv_list = configuration_->property("Beidou.prns", std::string(""));
if (sv_list.length() > 0)
{
@ -1760,10 +1760,8 @@ void GNSSFlowgraph::set_signals_list()
available_BDS_B1_signals_.push_back(Gnss_Signal(
Gnss_Satellite(std::string("Beidou"), *available_gnss_prn_iter),
std::string("B1")));
}
}
}
@ -1806,7 +1804,7 @@ Gnss_Signal GNSSFlowgraph::search_next_signal(const std::string& searched_signal
if (!pop)
{
available_GPS_1C_signals_.push_back(result);
}
}
if (tracked)
{
if ((configuration_->property("Channels_2S.count", 0) > 0) or (configuration_->property("Channels_L5.count", 0) > 0))
@ -2002,28 +2000,28 @@ Gnss_Signal GNSSFlowgraph::search_next_signal(const std::string& searched_signal
}
if (tracked)
{
// In the near future Beidou B2a will be added
// if (configuration_->property("Channels_5C.count", 0) > 0)
// {
// for (unsigned int ch = 0; ch < channels_count_; ch++)
// {
// if ((channels_[ch]->get_signal().get_satellite() == result.get_satellite()) and (channels_[ch]->get_signal().get_signal_str().compare("5C") != 0)) untracked_satellite = false;
// }
// if (untracked_satellite)
// {
// Gnss_Signal gs = Gnss_Signal(result.get_satellite(), "5C");
// available_BDS_5C_signals_.remove(gs);
// available_BDS_5C_signals_.push_front(gs);
// }
// }
// In the near future Beidou B2a will be added
// if (configuration_->property("Channels_5C.count", 0) > 0)
// {
// for (unsigned int ch = 0; ch < channels_count_; ch++)
// {
// if ((channels_[ch]->get_signal().get_satellite() == result.get_satellite()) and (channels_[ch]->get_signal().get_signal_str().compare("5C") != 0)) untracked_satellite = false;
// }
// if (untracked_satellite)
// {
// Gnss_Signal gs = Gnss_Signal(result.get_satellite(), "5C");
// available_BDS_5C_signals_.remove(gs);
// available_BDS_5C_signals_.push_front(gs);
// }
// }
}
break;
default:
LOG(ERROR) << "This should not happen :-(";
result = available_GPS_1C_signals_.front();
if (pop)
{
if (pop)
{
available_GPS_1C_signals_.pop_front();
}
break;

View File

@ -55,7 +55,6 @@
#include <queue>
#include <string>
#include <vector>
#include <map>
#if ENABLE_FPGA
#include "gnss_sdr_fpga_sample_counter.h"
@ -195,7 +194,7 @@ private:
evGAL_5X,
evGLO_1G,
evGLO_2G,
evBDS_B1
evBDS_B1
};
std::map<std::string, StringValue> mapStringValues_;

View File

@ -32,27 +32,27 @@
#ifndef GNSS_SDR_BEIDOU_B1I_H_
#define GNSS_SDR_BEIDOU_B1I_H_
#include <vector>
#include <utility> // std::pair
#include "MATH_CONSTANTS.h"
#include <utility> // std::pair
#include <vector>
// Physical constants
const double BEIDOU_C_m_s = 299792458.0; //!< The speed of light, [m/s]
const double BEIDOU_C_m_ms = 299792.4580; //!< The speed of light, [m/ms]
const double BEIDOU_PI = 3.1415926535898; //!< Pi
const double BEIDOU_TWO_PI = 6.283185307179586;//!< 2Pi
const double BEIDOU_OMEGA_EARTH_DOT = 7.2921150e-5; //!< Earth rotation rate, [rad/s] as defined in CGCS2000
const double BEIDOU_GM = 3.986004418e14; //!< Universal gravitational constant times the mass of the Earth, [m^3/s^2] as defined in CGCS2000
const double BEIDOU_F = -4.442807309e-10; //!< Constant, [s/(m)^(1/2)] F=-2(GM)^.5/C^2
const double BEIDOU_C_m_s = 299792458.0; //!< The speed of light, [m/s]
const double BEIDOU_C_m_ms = 299792.4580; //!< The speed of light, [m/ms]
const double BEIDOU_PI = 3.1415926535898; //!< Pi
const double BEIDOU_TWO_PI = 6.283185307179586; //!< 2Pi
const double BEIDOU_OMEGA_EARTH_DOT = 7.2921150e-5; //!< Earth rotation rate, [rad/s] as defined in CGCS2000
const double BEIDOU_GM = 3.986004418e14; //!< Universal gravitational constant times the mass of the Earth, [m^3/s^2] as defined in CGCS2000
const double BEIDOU_F = -4.442807309e-10; //!< Constant, [s/(m)^(1/2)] F=-2(GM)^.5/C^2
// carrier and code frequencies
const double BEIDOU_B1I_FREQ_HZ = 1.561098e9; //!< b1I [Hz]
const double BEIDOU_B1I_CODE_RATE_HZ = 2.046e6; //!< beidou b1I code rate [chips/s]
const double BEIDOU_B1I_CODE_LENGTH_CHIPS = 2046.0; //!< beidou b1I code length [chips]
const double BEIDOU_B1I_CODE_PERIOD = 0.001; //!< beidou b1I code period [seconds]
const double BEIDOU_B1I_FREQ_HZ = 1.561098e9; //!< b1I [Hz]
const double BEIDOU_B1I_CODE_RATE_HZ = 2.046e6; //!< beidou b1I code rate [chips/s]
const double BEIDOU_B1I_CODE_LENGTH_CHIPS = 2046.0; //!< beidou b1I code length [chips]
const double BEIDOU_B1I_CODE_PERIOD = 0.001; //!< beidou b1I code period [seconds]
const unsigned int BEIDOU_B1I_CODE_PERIOD_MS = 1; //!< GPS L1 C/A code period [ms]
const double BEIDOU_B1I_CHIP_PERIOD = 4.8875e-07; //!< beidou b1I chip period [seconds]
const double BEIDOU_B1I_CHIP_PERIOD = 4.8875e-07; //!< beidou b1I chip period [seconds]
const int BEIDOU_B1I_SECONDARY_CODE_LENGTH = 20;
const std::string BEIDOU_B1I_SECONDARY_CODE = "00000100110101001110";
const std::string BEIDOU_B1I_SECONDARY_CODE_STR = "00000100110101001110";
@ -66,34 +66,34 @@ const std::string BEIDOU_B1I_D2_SECONDARY_CODE_STR = "00";
* [1] J. Bao-Yen Tsui, Fundamentals of Global Positioning System Receivers. A Software Approach, John Wiley & Sons,
* Inc., Hoboken, NJ, 2nd edition, 2005.
*/
const double BEIDOU_MAX_TOA_DELAY_MS = 20; //******************
const double BEIDOU_MAX_TOA_DELAY_MS = 20; //******************
//#define NAVIGATION_SOLUTION_RATE_MS 1000 // this cannot go here
const double BEIDOU_STARTOFFSET_ms = 68.802; //**************[ms] Initial sign. travel time (this cannot go here)
const double BEIDOU_STARTOFFSET_ms = 68.802; //**************[ms] Initial sign. travel time (this cannot go here)
// OBSERVABLE HISTORY DEEP FOR INTERPOLATION
const int BEIDOU_B1I_HISTORY_DEEP = 100; // ****************
const int BEIDOU_B1I_HISTORY_DEEP = 100; // ****************
// NAVIGATION MESSAGE DEMODULATION AND DECODING
const int BEIDOU_B1I_PREAMBLE_LENGTH_BITS = 11;
const int BEIDOU_B1I_PREAMBLE_LENGTH_SYMBOLS = 220; // **************
const int BEIDOU_B1I_PREAMBLE_LENGTH_SYMBOLS = 220; // **************
const double BEIDOU_B1I_PREAMBLE_DURATION_S = 0.220;
const int BEIDOU_B1I_PREAMBLE_DURATION_MS = 220;
const int BEIDOU_B1I_TELEMETRY_RATE_BITS_SECOND = 50; //!< D1 NAV message bit rate [bits/s]
const int BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT = 20; // *************
const int BEIDOU_B1I_TELEMETRY_RATE_SYMBOLS_SECOND = BEIDOU_B1I_TELEMETRY_RATE_BITS_SECOND*BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; //************!< NAV message bit rate [symbols/s]
const int BEIDOU_WORD_LENGTH = 4; //**************!< CRC + BEIDOU WORD (-2 -1 0 ... 29) Bits = 4 bytes
const int BEIDOU_SUBFRAME_LENGTH = 40; //**************!< BEIDOU_WORD_LENGTH x 10 = 40 bytes
const int BEIDOU_DNAV_SUBFRAME_DATA_BITS = 300; //!< Number of bits per subframe in the NAV message [bits]
const int BEIDOU_SUBFRAME_SECONDS = 6; //!< Subframe duration [seconds]
const int BEIDOU_SUBFRAME_MS = 6000; //!< Subframe duration [miliseconds]
const int BEIDOU_WORD_BITS = 30; //!< Number of bits per word in the NAV message [bits]
const int BEIDOU_B1I_TELEMETRY_RATE_BITS_SECOND = 50; //!< D1 NAV message bit rate [bits/s]
const int BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT = 20; // *************
const int BEIDOU_B1I_TELEMETRY_RATE_SYMBOLS_SECOND = BEIDOU_B1I_TELEMETRY_RATE_BITS_SECOND * BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; //************!< NAV message bit rate [symbols/s]
const int BEIDOU_WORD_LENGTH = 4; //**************!< CRC + BEIDOU WORD (-2 -1 0 ... 29) Bits = 4 bytes
const int BEIDOU_SUBFRAME_LENGTH = 40; //**************!< BEIDOU_WORD_LENGTH x 10 = 40 bytes
const int BEIDOU_DNAV_SUBFRAME_DATA_BITS = 300; //!< Number of bits per subframe in the NAV message [bits]
const int BEIDOU_SUBFRAME_SECONDS = 6; //!< Subframe duration [seconds]
const int BEIDOU_SUBFRAME_MS = 6000; //!< Subframe duration [miliseconds]
const int BEIDOU_WORD_BITS = 30; //!< Number of bits per word in the NAV message [bits]
const std::string BEIDOU_DNAV_PREAMBLE = "11100010010";
const int BEIDOU_DNAV_PREAMBLE_LENGTH_BITS = 11;
const int BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS = 11; // **************
const int BEIDOU_DNAV_PREAMBLE_LENGTH_SYMBOLS = 11; // **************
const double BEIDOU_DNAV_PREAMBLE_PERIOD_SYMBOLS = 300;
const double BEIDOU_DNAV_SUBFRAME_SYMBOLS = 300;
const double BEIDOU_DNAV_DATA_BITS = 300;
@ -106,10 +106,10 @@ const double BEIDOU_B1I_PREAMBLE_PERIOD_SYMBOLS = 300;
// BEIDOU D1 NAVIGATION MESSAGE STRUCTURE
// GENERAL
const std::vector<std::pair<int,int> > D1_PRE( { {1,11} } );
const std::vector<std::pair<int,int> > D1_FRAID( { {16,3} } );
const std::vector<std::pair<int,int> > D1_SOW( { {19,8},{31,12} } );
const std::vector<std::pair<int,int> > D1_PNUM( { {44,7} } );
const std::vector<std::pair<int, int> > D1_PRE({{1, 11}});
const std::vector<std::pair<int, int> > D1_FRAID({{16, 3}});
const std::vector<std::pair<int, int> > D1_SOW({{19, 8}, {31, 12}});
const std::vector<std::pair<int, int> > D1_PNUM({{44, 7}});
// DNAV SCALE FACTORS
// EPH
@ -127,220 +127,220 @@ const double D1_BETA3_LSB = TWO_P16;
const double D1_A2_LSB = TWO_N66;
const double D1_A0_LSB = TWO_N33;
const double D1_A1_LSB = TWO_N50;
const double D1_DELTA_N_LSB = PI_TWO_N43;
const double D1_DELTA_N_LSB = PI_TWO_N43;
const double D1_CUC_LSB = TWO_N31;
const double D1_M0_LSB = PI_TWO_N31;
const double D1_M0_LSB = PI_TWO_N31;
const double D1_E_LSB = TWO_N33;
const double D1_CUS_LSB = TWO_N31;
const double D1_CRC_LSB = TWO_N6;
const double D1_CRS_LSB = TWO_N6;
const double D1_SQRT_A_LSB = TWO_N19;
const double D1_TOE_LSB = TWO_P3;
const double D1_I0_LSB = PI_TWO_N31;
const double D1_I0_LSB = PI_TWO_N31;
const double D1_CIC_LSB = TWO_N31;
const double D1_OMEGA_DOT_LSB = PI_TWO_N43;
const double D1_OMEGA_DOT_LSB = PI_TWO_N43;
const double D1_CIS_LSB = TWO_N31;
const double D1_IDOT_LSB = PI_TWO_N43;
const double D1_OMEGA0_LSB = PI_TWO_N31;
const double D1_OMEGA_LSB = PI_TWO_N31;
const double D1_IDOT_LSB = PI_TWO_N43;
const double D1_OMEGA0_LSB = PI_TWO_N31;
const double D1_OMEGA_LSB = PI_TWO_N31;
//ALM
const double D1_SQRT_A_ALMANAC_LSB = TWO_N11;
const double D1_A1_ALMANAC_LSB = TWO_N38;
const double D1_A0_ALMANAC_LSB = TWO_N20;
const double D1_OMEGA0_ALMANAC_LSB = PI_TWO_N23;
const double D1_OMEGA0_ALMANAC_LSB = PI_TWO_N23;
const double D1_E_ALMANAC_LSB = TWO_N21;
const double D1_DELTA_I_LSB = PI_TWO_N19;
const double D1_DELTA_I_LSB = PI_TWO_N19;
const double D1_TOA_LSB = TWO_P12;
const double D1_OMEGA_DOT_ALMANAC_LSB = PI_TWO_N38;
const double D1_OMEGA_ALMANAC_LSB = PI_TWO_N23;
const double D1_M0_ALMANAC_LSB = PI_TWO_N23;
const double D1_A0GPS_LSB = 0.1e-9;
const double D1_A1GPS_LSB = 0.1e-9;
const double D1_A0GAL_LSB = 0.1e-9;
const double D1_A1GAL_LSB = 0.1e-9;
const double D1_A0GLO_LSB = 0.1e-9;
const double D1_A1GLO_LSB = 0.1e-9;
const double D1_A0UTC_LSB = TWO_N30;
const double D1_A1UTC_LSB = TWO_N50;
const double D1_OMEGA_DOT_ALMANAC_LSB = PI_TWO_N38;
const double D1_OMEGA_ALMANAC_LSB = PI_TWO_N23;
const double D1_M0_ALMANAC_LSB = PI_TWO_N23;
const double D1_A0GPS_LSB = 0.1e-9;
const double D1_A1GPS_LSB = 0.1e-9;
const double D1_A0GAL_LSB = 0.1e-9;
const double D1_A1GAL_LSB = 0.1e-9;
const double D1_A0GLO_LSB = 0.1e-9;
const double D1_A1GLO_LSB = 0.1e-9;
const double D1_A0UTC_LSB = TWO_N30;
const double D1_A1UTC_LSB = TWO_N50;
// SUBFRAME 1
const std::vector<std::pair<int,int> > D1_SAT_H1( { {43,1} } );
const std::vector<std::pair<int,int> > D1_AODC( { {44,5} } );
const std::vector<std::pair<int,int> > D1_URAI( { {49,4} } );
const std::vector<std::pair<int,int> > D1_WN( { {61,13} } );
const std::vector<std::pair<int,int> > D1_TOC( { {74,9},{91,8} } );
const std::vector<std::pair<int,int> > D1_TGD1( { {99,10} } );
const std::vector<std::pair<int,int> > D1_TGD2( { {121,6} } );
const std::vector<std::pair<int,int> > D1_ALPHA0( { {127,8} } );
const std::vector<std::pair<int,int> > D1_ALPHA1( { {135,8} } );
const std::vector<std::pair<int,int> > D1_ALPHA2( { {151,8} } );
const std::vector<std::pair<int,int> > D1_ALPHA3( { {159,8} } );
const std::vector<std::pair<int,int> > D1_BETA0( { {167,6}, {181,2} } );
const std::vector<std::pair<int,int> > D1_BETA1( { {183,8} } );
const std::vector<std::pair<int,int> > D1_BETA2( { {191,8} } );
const std::vector<std::pair<int,int> > D1_BETA3( { {199,4},{211,4} } );
const std::vector<std::pair<int,int> > D1_A2( { {215,11} } );
const std::vector<std::pair<int,int> > D1_A0( { {226,7},{241,17} } );
const std::vector<std::pair<int,int> > D1_A1( { {258,5},{271,17} } );
const std::vector<std::pair<int,int> > D1_AODE( { {288,5} } );
const std::vector<std::pair<int, int> > D1_SAT_H1({{43, 1}});
const std::vector<std::pair<int, int> > D1_AODC({{44, 5}});
const std::vector<std::pair<int, int> > D1_URAI({{49, 4}});
const std::vector<std::pair<int, int> > D1_WN({{61, 13}});
const std::vector<std::pair<int, int> > D1_TOC({{74, 9}, {91, 8}});
const std::vector<std::pair<int, int> > D1_TGD1({{99, 10}});
const std::vector<std::pair<int, int> > D1_TGD2({{121, 6}});
const std::vector<std::pair<int, int> > D1_ALPHA0({{127, 8}});
const std::vector<std::pair<int, int> > D1_ALPHA1({{135, 8}});
const std::vector<std::pair<int, int> > D1_ALPHA2({{151, 8}});
const std::vector<std::pair<int, int> > D1_ALPHA3({{159, 8}});
const std::vector<std::pair<int, int> > D1_BETA0({{167, 6}, {181, 2}});
const std::vector<std::pair<int, int> > D1_BETA1({{183, 8}});
const std::vector<std::pair<int, int> > D1_BETA2({{191, 8}});
const std::vector<std::pair<int, int> > D1_BETA3({{199, 4}, {211, 4}});
const std::vector<std::pair<int, int> > D1_A2({{215, 11}});
const std::vector<std::pair<int, int> > D1_A0({{226, 7}, {241, 17}});
const std::vector<std::pair<int, int> > D1_A1({{258, 5}, {271, 17}});
const std::vector<std::pair<int, int> > D1_AODE({{288, 5}});
//SUBFRAME 2
const std::vector<std::pair<int,int> > D1_DELTA_N( { {43,10},{61,6} } );
const std::vector<std::pair<int,int> > D1_CUC( { {67,16},{91,2} } );
const std::vector<std::pair<int,int> > D1_M0( { {93,20}, {121,12} } );
const std::vector<std::pair<int,int> > D1_E( { {133,10},{151,22} } );
const std::vector<std::pair<int,int> > D1_CUS( { {181,18} } );
const std::vector<std::pair<int,int> > D1_CRC( { {199,4},{211,14} } );
const std::vector<std::pair<int,int> > D1_CRS( { {225,8},{241,10} } );
const std::vector<std::pair<int,int> > D1_SQRT_A( { {251,12},{271,20} } );
const std::vector<std::pair<int,int> > D1_TOE_SF2( { {291,2} } );
const std::vector<std::pair<int, int> > D1_DELTA_N({{43, 10}, {61, 6}});
const std::vector<std::pair<int, int> > D1_CUC({{67, 16}, {91, 2}});
const std::vector<std::pair<int, int> > D1_M0({{93, 20}, {121, 12}});
const std::vector<std::pair<int, int> > D1_E({{133, 10}, {151, 22}});
const std::vector<std::pair<int, int> > D1_CUS({{181, 18}});
const std::vector<std::pair<int, int> > D1_CRC({{199, 4}, {211, 14}});
const std::vector<std::pair<int, int> > D1_CRS({{225, 8}, {241, 10}});
const std::vector<std::pair<int, int> > D1_SQRT_A({{251, 12}, {271, 20}});
const std::vector<std::pair<int, int> > D1_TOE_SF2({{291, 2}});
//SUBFRAME 3
const std::vector<std::pair<int,int> > D1_TOE_SF3( { {43,10},{61,5} } );
const std::vector<std::pair<int,int> > D1_I0( { {66,17},{91,15} } );
const std::vector<std::pair<int,int> > D1_CIC( { {106,7},{121,11} } );
const std::vector<std::pair<int,int> > D1_OMEGA_DOT( { {132,11},{151,13} } );
const std::vector<std::pair<int,int> > D1_CIS( { {164,9},{181,9} } );
const std::vector<std::pair<int,int> > D1_IDOT( { {190,13},{211,1} } );
const std::vector<std::pair<int,int> > D1_OMEGA0( { {212,21},{241,11} } );
const std::vector<std::pair<int,int> > D1_OMEGA( { {252,11},{271,21} } );
const std::vector<std::pair<int, int> > D1_TOE_SF3({{43, 10}, {61, 5}});
const std::vector<std::pair<int, int> > D1_I0({{66, 17}, {91, 15}});
const std::vector<std::pair<int, int> > D1_CIC({{106, 7}, {121, 11}});
const std::vector<std::pair<int, int> > D1_OMEGA_DOT({{132, 11}, {151, 13}});
const std::vector<std::pair<int, int> > D1_CIS({{164, 9}, {181, 9}});
const std::vector<std::pair<int, int> > D1_IDOT({{190, 13}, {211, 1}});
const std::vector<std::pair<int, int> > D1_OMEGA0({{212, 21}, {241, 11}});
const std::vector<std::pair<int, int> > D1_OMEGA({{252, 11}, {271, 21}});
//SUBFRAME 4 AND PAGES 1 THROUGH 6 IN SUBFRAME 5
const std::vector<std::pair<int,int> > D1_SQRT_A_ALMANAC( { {51,2},{61,22} } );
const std::vector<std::pair<int,int> > D1_A1_ALMANAC( { {91,11} } );
const std::vector<std::pair<int,int> > D1_A0_ALMANAC( { {102,11} } );
const std::vector<std::pair<int,int> > D1_OMEGA0_ALMANAC( { {121,22},{151,2} } );
const std::vector<std::pair<int,int> > D1_E_ALMANAC( { {153,17} } );
const std::vector<std::pair<int,int> > D1_DELTA_I( { {170,3},{181,13} } );
const std::vector<std::pair<int,int> > D1_TOA( { {194,8} } );
const std::vector<std::pair<int,int> > D1_OMEGA_DOT_ALMANAC( { {202,1}, {211,16} } );
const std::vector<std::pair<int,int> > D1_OMEGA_ALMANAC( { {227,6},{241,18} } );
const std::vector<std::pair<int,int> > D1_M0_ALMANAC( { {259,4},{271,20} } );
const std::vector<std::pair<int, int> > D1_SQRT_A_ALMANAC({{51, 2}, {61, 22}});
const std::vector<std::pair<int, int> > D1_A1_ALMANAC({{91, 11}});
const std::vector<std::pair<int, int> > D1_A0_ALMANAC({{102, 11}});
const std::vector<std::pair<int, int> > D1_OMEGA0_ALMANAC({{121, 22}, {151, 2}});
const std::vector<std::pair<int, int> > D1_E_ALMANAC({{153, 17}});
const std::vector<std::pair<int, int> > D1_DELTA_I({{170, 3}, {181, 13}});
const std::vector<std::pair<int, int> > D1_TOA({{194, 8}});
const std::vector<std::pair<int, int> > D1_OMEGA_DOT_ALMANAC({{202, 1}, {211, 16}});
const std::vector<std::pair<int, int> > D1_OMEGA_ALMANAC({{227, 6}, {241, 18}});
const std::vector<std::pair<int, int> > D1_M0_ALMANAC({{259, 4}, {271, 20}});
//SUBFRAME 5 PAGE 7
const std::vector<std::pair<int,int> > D1_HEA1( { {51,2},{61,7} } );
const std::vector<std::pair<int,int> > D1_HEA2( { {68,9} } );
const std::vector<std::pair<int,int> > D1_HEA3( { {77,6},{91,3} } );
const std::vector<std::pair<int,int> > D1_HEA4( { {94,9} } );
const std::vector<std::pair<int,int> > D1_HEA5( { {103,9} } );
const std::vector<std::pair<int,int> > D1_HEA6( { {112,1},{121,8} } );
const std::vector<std::pair<int,int> > D1_HEA7( { {129,9} } );
const std::vector<std::pair<int,int> > D1_HEA8( { {138,5},{151,4} } );
const std::vector<std::pair<int,int> > D1_HEA9( { {155,9} } );
const std::vector<std::pair<int,int> > D1_HEA10( { {164,9} } );
const std::vector<std::pair<int,int> > D1_HEA11( { {181,9} } );
const std::vector<std::pair<int,int> > D1_HEA12( { {190,9} } );
const std::vector<std::pair<int,int> > D1_HEA13( { {199,4},{211,5} } );
const std::vector<std::pair<int,int> > D1_HEA14( { {216,9} } );
const std::vector<std::pair<int,int> > D1_HEA15( { {225,8},{241,1} } );
const std::vector<std::pair<int,int> > D1_HEA16( { {242,9} } );
const std::vector<std::pair<int,int> > D1_HEA17( { {251,9} } );
const std::vector<std::pair<int,int> > D1_HEA18( { {260,3},{271,6} } );
const std::vector<std::pair<int,int> > D1_HEA19( { {277,9} } );
const std::vector<std::pair<int, int> > D1_HEA1({{51, 2}, {61, 7}});
const std::vector<std::pair<int, int> > D1_HEA2({{68, 9}});
const std::vector<std::pair<int, int> > D1_HEA3({{77, 6}, {91, 3}});
const std::vector<std::pair<int, int> > D1_HEA4({{94, 9}});
const std::vector<std::pair<int, int> > D1_HEA5({{103, 9}});
const std::vector<std::pair<int, int> > D1_HEA6({{112, 1}, {121, 8}});
const std::vector<std::pair<int, int> > D1_HEA7({{129, 9}});
const std::vector<std::pair<int, int> > D1_HEA8({{138, 5}, {151, 4}});
const std::vector<std::pair<int, int> > D1_HEA9({{155, 9}});
const std::vector<std::pair<int, int> > D1_HEA10({{164, 9}});
const std::vector<std::pair<int, int> > D1_HEA11({{181, 9}});
const std::vector<std::pair<int, int> > D1_HEA12({{190, 9}});
const std::vector<std::pair<int, int> > D1_HEA13({{199, 4}, {211, 5}});
const std::vector<std::pair<int, int> > D1_HEA14({{216, 9}});
const std::vector<std::pair<int, int> > D1_HEA15({{225, 8}, {241, 1}});
const std::vector<std::pair<int, int> > D1_HEA16({{242, 9}});
const std::vector<std::pair<int, int> > D1_HEA17({{251, 9}});
const std::vector<std::pair<int, int> > D1_HEA18({{260, 3}, {271, 6}});
const std::vector<std::pair<int, int> > D1_HEA19({{277, 9}});
//SUBFRAME 5 PAGE 8
const std::vector<std::pair<int,int> > D1_HEA20( { {51,2},{61,7} } );
const std::vector<std::pair<int,int> > D1_HEA21( { {68,9} } );
const std::vector<std::pair<int,int> > D1_HEA22( { {77,6},{91,3} } );
const std::vector<std::pair<int,int> > D1_HEA23( { {94,9} } );
const std::vector<std::pair<int,int> > D1_HEA24( { {103,9} } );
const std::vector<std::pair<int,int> > D1_HEA25( { {112,1},{121,8} } );
const std::vector<std::pair<int,int> > D1_HEA26( { {129,9} } );
const std::vector<std::pair<int,int> > D1_HEA27( { {138,5},{151,4} } );
const std::vector<std::pair<int,int> > D1_HEA28( { {155,9} } );
const std::vector<std::pair<int,int> > D1_HEA29( { {164,9} } );
const std::vector<std::pair<int,int> > D1_HEA30( { {181,9} } );
const std::vector<std::pair<int,int> > D1_WNA( { {190,8} } );
const std::vector<std::pair<int,int> > D1_TOA2( { {198,5},{211,3} } );
const std::vector<std::pair<int, int> > D1_HEA20({{51, 2}, {61, 7}});
const std::vector<std::pair<int, int> > D1_HEA21({{68, 9}});
const std::vector<std::pair<int, int> > D1_HEA22({{77, 6}, {91, 3}});
const std::vector<std::pair<int, int> > D1_HEA23({{94, 9}});
const std::vector<std::pair<int, int> > D1_HEA24({{103, 9}});
const std::vector<std::pair<int, int> > D1_HEA25({{112, 1}, {121, 8}});
const std::vector<std::pair<int, int> > D1_HEA26({{129, 9}});
const std::vector<std::pair<int, int> > D1_HEA27({{138, 5}, {151, 4}});
const std::vector<std::pair<int, int> > D1_HEA28({{155, 9}});
const std::vector<std::pair<int, int> > D1_HEA29({{164, 9}});
const std::vector<std::pair<int, int> > D1_HEA30({{181, 9}});
const std::vector<std::pair<int, int> > D1_WNA({{190, 8}});
const std::vector<std::pair<int, int> > D1_TOA2({{198, 5}, {211, 3}});
//SUBFRAME 5 PAGE 9
const std::vector<std::pair<int,int> > D1_A0GPS( { {97,14} } );
const std::vector<std::pair<int,int> > D1_A1GPS( { {111,2},{121,14} } );
const std::vector<std::pair<int,int> > D1_A0GAL( { {135,8},{151,6} } );
const std::vector<std::pair<int,int> > D1_A1GAL( { {157,16} } );
const std::vector<std::pair<int,int> > D1_A0GLO( { {181,14} } );
const std::vector<std::pair<int,int> > D1_A1GLO( { {195,8},{211,8} } );
const std::vector<std::pair<int, int> > D1_A0GPS({{97, 14}});
const std::vector<std::pair<int, int> > D1_A1GPS({{111, 2}, {121, 14}});
const std::vector<std::pair<int, int> > D1_A0GAL({{135, 8}, {151, 6}});
const std::vector<std::pair<int, int> > D1_A1GAL({{157, 16}});
const std::vector<std::pair<int, int> > D1_A0GLO({{181, 14}});
const std::vector<std::pair<int, int> > D1_A1GLO({{195, 8}, {211, 8}});
//SUBFRAME 5 PAGE 10
const std::vector<std::pair<int,int> > D1_DELTA_T_LS( { {51,2},{61,6} } );
const std::vector<std::pair<int,int> > D1_DELTA_T_LSF( { {67,8} } );
const std::vector<std::pair<int,int> > D1_WN_LSF( { {75,8} } );
const std::vector<std::pair<int,int> > D1_A0UTC( { {91,22},{121,10} } );
const std::vector<std::pair<int,int> > D1_A1UTC( { {131,12},{151,12} } );
const std::vector<std::pair<int,int> > D1_DN( { {163,8} } );
const std::vector<std::pair<int, int> > D1_DELTA_T_LS({{51, 2}, {61, 6}});
const std::vector<std::pair<int, int> > D1_DELTA_T_LSF({{67, 8}});
const std::vector<std::pair<int, int> > D1_WN_LSF({{75, 8}});
const std::vector<std::pair<int, int> > D1_A0UTC({{91, 22}, {121, 10}});
const std::vector<std::pair<int, int> > D1_A1UTC({{131, 12}, {151, 12}});
const std::vector<std::pair<int, int> > D1_DN({{163, 8}});
// D2 NAV Message Decoding Information
const std::vector<std::pair<int,int> > D2_PRE( { {1,11} } );
const std::vector<std::pair<int,int> > D2_FRAID( { {16,3} } );
const std::vector<std::pair<int,int> > D2_SOW( { {19,8},{31,12} } );
const std::vector<std::pair<int,int> > D2_PNUM( { {43,4} } );
const std::vector<std::pair<int, int> > D2_PRE({{1, 11}});
const std::vector<std::pair<int, int> > D2_FRAID({{16, 3}});
const std::vector<std::pair<int, int> > D2_SOW({{19, 8}, {31, 12}});
const std::vector<std::pair<int, int> > D2_PNUM({{43, 4}});
// D2 NAV, SUBFRAME 1, PAGE 1
const std::vector<std::pair<int,int> > D2_SAT_H1( { {47,1} } );
const std::vector<std::pair<int,int> > D2_AODC( { {48,5} } );
const std::vector<std::pair<int,int> > D2_URAI( { {61,4} } );
const std::vector<std::pair<int,int> > D2_WN( { {65,13} } );
const std::vector<std::pair<int,int> > D2_TOC( { {78,5},{91,12} } );
const std::vector<std::pair<int,int> > D2_TGD1( { {103,10} } );
const std::vector<std::pair<int,int> > D2_TGD2( { {121,10} } );
const std::vector<std::pair<int, int> > D2_SAT_H1({{47, 1}});
const std::vector<std::pair<int, int> > D2_AODC({{48, 5}});
const std::vector<std::pair<int, int> > D2_URAI({{61, 4}});
const std::vector<std::pair<int, int> > D2_WN({{65, 13}});
const std::vector<std::pair<int, int> > D2_TOC({{78, 5}, {91, 12}});
const std::vector<std::pair<int, int> > D2_TGD1({{103, 10}});
const std::vector<std::pair<int, int> > D2_TGD2({{121, 10}});
// D2 NAV, SUBFRAME 1, PAGE 2
const std::vector<std::pair<int,int> > D2_ALPHA0( { {47,6}, {61,2} } );
const std::vector<std::pair<int,int> > D2_ALPHA1( { {63,8} } );
const std::vector<std::pair<int,int> > D2_ALPHA2( { {71,8} } );
const std::vector<std::pair<int,int> > D2_ALPHA3( { {79,4}, {91,4} } );
const std::vector<std::pair<int,int> > D2_BETA0( { {95,8} } );
const std::vector<std::pair<int,int> > D2_BETA1( { {103,8} } );
const std::vector<std::pair<int,int> > D2_BETA2( { {111,2}, {121,6} } );
const std::vector<std::pair<int,int> > D2_BETA3( { {127,8} } );
const std::vector<std::pair<int, int> > D2_ALPHA0({{47, 6}, {61, 2}});
const std::vector<std::pair<int, int> > D2_ALPHA1({{63, 8}});
const std::vector<std::pair<int, int> > D2_ALPHA2({{71, 8}});
const std::vector<std::pair<int, int> > D2_ALPHA3({{79, 4}, {91, 4}});
const std::vector<std::pair<int, int> > D2_BETA0({{95, 8}});
const std::vector<std::pair<int, int> > D2_BETA1({{103, 8}});
const std::vector<std::pair<int, int> > D2_BETA2({{111, 2}, {121, 6}});
const std::vector<std::pair<int, int> > D2_BETA3({{127, 8}});
// D2 NAV, SUBFRAME 1, PAGE 3
const std::vector<std::pair<int,int> > D2_A0( { {101,12},{121,12} } );
const std::vector<std::pair<int,int> > D2_A1_MSB( { {133,4} } );
const std::vector<std::pair<int,int> > D2_A1_LSB( { {47,6}, {61, 12} } );
const std::vector<std::pair<int,int> > D2_A1( { {279,22} } );
const std::vector<std::pair<int, int> > D2_A0({{101, 12}, {121, 12}});
const std::vector<std::pair<int, int> > D2_A1_MSB({{133, 4}});
const std::vector<std::pair<int, int> > D2_A1_LSB({{47, 6}, {61, 12}});
const std::vector<std::pair<int, int> > D2_A1({{279, 22}});
// D2 NAV, SUBFRAME 1, PAGE 4
const std::vector<std::pair<int,int> > D2_A2( { {73,10}, {91,1} } );
const std::vector<std::pair<int,int> > D2_AODE( { {92,5} } );
const std::vector<std::pair<int,int> > D2_DELTA_N( { {97,16} } );
const std::vector<std::pair<int,int> > D2_CUC_MSB( { {121,14} } );
const std::vector<std::pair<int,int> > D2_CUC_LSB( { {47,4} } );
const std::vector<std::pair<int,int> > D2_CUC( { {283,18} } );
const std::vector<std::pair<int, int> > D2_A2({{73, 10}, {91, 1}});
const std::vector<std::pair<int, int> > D2_AODE({{92, 5}});
const std::vector<std::pair<int, int> > D2_DELTA_N({{97, 16}});
const std::vector<std::pair<int, int> > D2_CUC_MSB({{121, 14}});
const std::vector<std::pair<int, int> > D2_CUC_LSB({{47, 4}});
const std::vector<std::pair<int, int> > D2_CUC({{283, 18}});
// D2 NAV, SUBFRAME 1, PAGE 5
const std::vector<std::pair<int,int> > D2_M0( { {51,2}, {61,22}, {91,8} } );
const std::vector<std::pair<int,int> > D2_CUS( { {99,14}, {121, 4} } );
const std::vector<std::pair<int,int> > D2_E_MSB( { {125,10} } );
const std::vector<std::pair<int, int> > D2_M0({{51, 2}, {61, 22}, {91, 8}});
const std::vector<std::pair<int, int> > D2_CUS({{99, 14}, {121, 4}});
const std::vector<std::pair<int, int> > D2_E_MSB({{125, 10}});
// D2 NAV, SUBFRAME 1, PAGE 6
const std::vector<std::pair<int,int> > D2_E_LSB( { {47,6}, {61, 16} } );
const std::vector<std::pair<int,int> > D2_SQRT_A( { {77,6},{91,22}, {121,4} } );
const std::vector<std::pair<int,int> > D2_CIC_MSB( { {125,10} } );
const std::vector<std::pair<int,int> > D2_CIC_LSB( { {47,6}, {61,2} } );
const std::vector<std::pair<int,int> > D2_CIC( { {283,18} } );
const std::vector<std::pair<int, int> > D2_E_LSB({{47, 6}, {61, 16}});
const std::vector<std::pair<int, int> > D2_SQRT_A({{77, 6}, {91, 22}, {121, 4}});
const std::vector<std::pair<int, int> > D2_CIC_MSB({{125, 10}});
const std::vector<std::pair<int, int> > D2_CIC_LSB({{47, 6}, {61, 2}});
const std::vector<std::pair<int, int> > D2_CIC({{283, 18}});
// D2 NAV, SUBFRAME 1, PAGE 7
const std::vector<std::pair<int,int> > D2_CIS( { {63,18} } );
const std::vector<std::pair<int,int> > D2_TOE( { {81,2},{91,15} } );
const std::vector<std::pair<int,int> > D2_I0_MSB( { {106,7},{121,14} } );
const std::vector<std::pair<int,int> > D2_I0_LSB( { {47,6},{61,5} } );
const std::vector<std::pair<int,int> > D2_I0( { {269,32} } );
const std::vector<std::pair<int, int> > D2_CIS({{63, 18}});
const std::vector<std::pair<int, int> > D2_TOE({{81, 2}, {91, 15}});
const std::vector<std::pair<int, int> > D2_I0_MSB({{106, 7}, {121, 14}});
const std::vector<std::pair<int, int> > D2_I0_LSB({{47, 6}, {61, 5}});
const std::vector<std::pair<int, int> > D2_I0({{269, 32}});
// D2 NAV, SUBFRAME 1, PAGE 8
const std::vector<std::pair<int,int> > D2_CRC( { {66,17},{91,1} } );
const std::vector<std::pair<int,int> > D2_CRS( { {92,18} } );
const std::vector<std::pair<int,int> > D2_OMEGA_DOT_MSB( { {110,3},{121,16} } );
const std::vector<std::pair<int,int> > D2_OMEGA_DOT_LSB( { {47,5} } );
const std::vector<std::pair<int,int> > D2_OMEGA_DOT( { {277,24} } );
const std::vector<std::pair<int, int> > D2_CRC({{66, 17}, {91, 1}});
const std::vector<std::pair<int, int> > D2_CRS({{92, 18}});
const std::vector<std::pair<int, int> > D2_OMEGA_DOT_MSB({{110, 3}, {121, 16}});
const std::vector<std::pair<int, int> > D2_OMEGA_DOT_LSB({{47, 5}});
const std::vector<std::pair<int, int> > D2_OMEGA_DOT({{277, 24}});
// D2 NAV, SUBFRAME 1, PAGE 9
const std::vector<std::pair<int,int> > D2_OMEGA0( { {52,1},{61,22},{91,9} } );
const std::vector<std::pair<int,int> > D2_OMEGA_MSB( { {100,13},{121,14} } );
const std::vector<std::pair<int,int> > D2_OMEGA_LSB( { {47,5} } );
const std::vector<std::pair<int,int> > D2_OMEGA( { {269,32} } );
const std::vector<std::pair<int, int> > D2_OMEGA0({{52, 1}, {61, 22}, {91, 9}});
const std::vector<std::pair<int, int> > D2_OMEGA_MSB({{100, 13}, {121, 14}});
const std::vector<std::pair<int, int> > D2_OMEGA_LSB({{47, 5}});
const std::vector<std::pair<int, int> > D2_OMEGA({{269, 32}});
// D2 NAV, SUBFRAME 1, PAGE 10
const std::vector<std::pair<int,int> > D2_IDOT( { {52,1},{61,13} } );
const std::vector<std::pair<int, int> > D2_IDOT({{52, 1}, {61, 13}});
#endif /* GNSS_SDR_BEIDOU_B1I_H_ */

View File

@ -18,96 +18,96 @@
set(SYSTEM_PARAMETERS_SOURCES
gnss_satellite.cc
gnss_signal.cc
gps_navigation_message.cc
gps_ephemeris.cc
gps_iono.cc
gps_almanac.cc
gps_utc_model.cc
gps_acq_assist.cc
gnss_satellite.cc
gnss_signal.cc
gps_navigation_message.cc
gps_ephemeris.cc
gps_iono.cc
gps_almanac.cc
gps_utc_model.cc
gps_acq_assist.cc
agnss_ref_time.cc
agnss_ref_location.cc
galileo_utc_model.cc
galileo_ephemeris.cc
galileo_almanac.cc
galileo_utc_model.cc
galileo_ephemeris.cc
galileo_almanac.cc
galileo_almanac_helper.cc
galileo_iono.cc
galileo_navigation_message.cc
beidou_dnav_navigation_message.cc
beidou_dnav_ephemeris.cc
beidou_dnav_iono.cc
beidou_dnav_almanac.cc
beidou_dnav_utc_model.cc
sbas_ephemeris.cc
galileo_fnav_message.cc
gps_cnav_ephemeris.cc
gps_cnav_navigation_message.cc
gps_cnav_iono.cc
gps_cnav_utc_model.cc
rtcm.cc
glonass_gnav_ephemeris.cc
glonass_gnav_almanac.cc
glonass_gnav_utc_model.cc
glonass_gnav_navigation_message.cc
galileo_iono.cc
galileo_navigation_message.cc
beidou_dnav_navigation_message.cc
beidou_dnav_ephemeris.cc
beidou_dnav_iono.cc
beidou_dnav_almanac.cc
beidou_dnav_utc_model.cc
sbas_ephemeris.cc
galileo_fnav_message.cc
gps_cnav_ephemeris.cc
gps_cnav_navigation_message.cc
gps_cnav_iono.cc
gps_cnav_utc_model.cc
rtcm.cc
glonass_gnav_ephemeris.cc
glonass_gnav_almanac.cc
glonass_gnav_utc_model.cc
glonass_gnav_navigation_message.cc
)
set(SYSTEM_PARAMETERS_HEADERS
gnss_satellite.h
gnss_signal.h
gps_navigation_message.h
gps_ephemeris.h
gps_iono.h
gps_almanac.h
gps_utc_model.h
gps_acq_assist.h
gnss_satellite.h
gnss_signal.h
gps_navigation_message.h
gps_ephemeris.h
gps_iono.h
gps_almanac.h
gps_utc_model.h
gps_acq_assist.h
agnss_ref_time.h
agnss_ref_location.h
galileo_utc_model.h
galileo_ephemeris.h
galileo_almanac.h
galileo_utc_model.h
galileo_ephemeris.h
galileo_almanac.h
galileo_almanac_helper.h
galileo_iono.h
galileo_navigation_message.h
sbas_ephemeris.h
galileo_fnav_message.h
gps_cnav_ephemeris.h
gps_cnav_navigation_message.h
gps_cnav_iono.h
gps_cnav_utc_model.h
rtcm.h
glonass_gnav_ephemeris.h
glonass_gnav_almanac.h
glonass_gnav_utc_model.h
glonass_gnav_navigation_message.h
beidou_dnav_navigation_message.h
beidou_dnav_ephemeris.h
beidou_dnav_iono.h
beidou_dnav_almanac.h
beidou_dnav_utc_model.h
display.h
Galileo_E1.h
Galileo_E5a.h
GLONASS_L1_L2_CA.h
gnss_frequencies.h
gnss_obs_codes.h
gnss_synchro.h
GPS_CNAV.h
GPS_L1_CA.h
GPS_L2C.h
GPS_L5.h
Beidou_B1I.h
MATH_CONSTANTS.h
galileo_iono.h
galileo_navigation_message.h
sbas_ephemeris.h
galileo_fnav_message.h
gps_cnav_ephemeris.h
gps_cnav_navigation_message.h
gps_cnav_iono.h
gps_cnav_utc_model.h
rtcm.h
glonass_gnav_ephemeris.h
glonass_gnav_almanac.h
glonass_gnav_utc_model.h
glonass_gnav_navigation_message.h
beidou_dnav_navigation_message.h
beidou_dnav_ephemeris.h
beidou_dnav_iono.h
beidou_dnav_almanac.h
beidou_dnav_utc_model.h
display.h
Galileo_E1.h
Galileo_E5a.h
GLONASS_L1_L2_CA.h
gnss_frequencies.h
gnss_obs_codes.h
gnss_synchro.h
GPS_CNAV.h
GPS_L1_CA.h
GPS_L2C.h
GPS_L5.h
Beidou_B1I.h
MATH_CONSTANTS.h
)
include_directories(
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/PVT/libs
${CMAKE_SOURCE_DIR}/src/algorithms/libs/rtklib
${GLOG_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}
${CMAKE_SOURCE_DIR}/src/core/receiver
${CMAKE_SOURCE_DIR}/src/algorithms/PVT/libs
${CMAKE_SOURCE_DIR}/src/algorithms/libs/rtklib
${GLOG_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${GFlags_INCLUDE_DIRS}
)
list(SORT SYSTEM_PARAMETERS_HEADERS)

View File

@ -46,7 +46,7 @@
const double PI = 3.1415926535897932; //!< pi
const double PI_2 = 2.0 * PI; //!< 2 * pi
const double TWO_P3 = (8); //!< 2^3
const double TWO_P3 = (8); //!< 2^3
const double TWO_P4 = (16); //!< 2^4
const double TWO_P11 = (2048); //!< 2^11
const double TWO_P12 = (4096); //!< 2^12
@ -92,14 +92,14 @@ const double TWO_N44 = (5.684341886080802e-14); //!< 2^-44
const double TWO_N46 = (1.4210854715202e-014); //!< 2^-46
const double TWO_N48 = (3.552713678800501e-15); //!< 2^-46
const double TWO_N50 = (8.881784197001252e-016); //!< 2^-50
const double TWO_N51 = (4.44089209850063e-016); //!< 2^-51
const double TWO_N55 = (2.775557561562891e-017); //!< 2^-55
const double TWO_N57 = (6.938893903907228e-18); //!< 2^-57
const double TWO_N59 = (1.73472347597681e-018); //!< 2^-59
const double TWO_N60 = (8.673617379884036e-19); //!< 2^-60
const double TWO_N66 = (1.3552527156068805425093160010874271392822265625e-20); //!< 2^-66
const double TWO_N68 = (3.388131789017201e-21); //!< 2^-68
const double TWO_N50 = (8.881784197001252e-016); //!< 2^-50
const double TWO_N51 = (4.44089209850063e-016); //!< 2^-51
const double TWO_N55 = (2.775557561562891e-017); //!< 2^-55
const double TWO_N57 = (6.938893903907228e-18); //!< 2^-57
const double TWO_N59 = (1.73472347597681e-018); //!< 2^-59
const double TWO_N60 = (8.673617379884036e-19); //!< 2^-60
const double TWO_N66 = (1.3552527156068805425093160010874271392822265625e-20); //!< 2^-66
const double TWO_N68 = (3.388131789017201e-21); //!< 2^-68
const double PI_TWO_N19 = (5.992112452678286e-006); //!< Pi*2^-19

View File

@ -30,11 +30,9 @@
*/
#include "beidou_dnav_ephemeris.h"
#include <cmath>
#include "Beidou_B1I.h"
#include "gnss_satellite.h"
#include <cmath>
Beidou_Dnav_Ephemeris::Beidou_Dnav_Ephemeris()
{
@ -63,27 +61,27 @@ Beidou_Dnav_Ephemeris::Beidou_Dnav_Ephemeris()
d_AODE = 0;
d_TGD1 = 0;
d_TGD2 = 0;
d_AODC = 0; // Issue of Data, Clock
i_AODO = 0; // Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
d_AODC = 0; // Issue of Data, Clock
i_AODO = 0; // Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
d_AODC = 0;
b_fit_interval_flag = false; // indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
b_fit_interval_flag = false; // indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
d_spare1 = 0;
d_spare2 = 0;
i_sig_type = 0;
i_nav_type = 0;
d_A_f0 = 0; // Coefficient 0 of code phase offset model [s]
d_A_f1 = 0; // Coefficient 1 of code phase offset model [s/s]
d_A_f2 = 0; // Coefficient 2 of code phase offset model [s/s^2]
d_A_f0 = 0; // Coefficient 0 of code phase offset model [s]
d_A_f1 = 0; // Coefficient 1 of code phase offset model [s/s]
d_A_f2 = 0; // Coefficient 2 of code phase offset model [s/s^2]
b_integrity_status_flag = false;
b_alert_flag = false; // If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
b_antispoofing_flag = false; // If true, the AntiSpoofing mode is ON in that SV
auto gnss_sat = Gnss_Satellite();
std::string _system ("Beidou");
for(unsigned int i = 1; i < 36; i++)
std::string _system("Beidou");
for (unsigned int i = 1; i < 36; i++)
{
satelliteBlock[i] = gnss_sat.what_block(_system, i);
}
@ -102,7 +100,7 @@ Beidou_Dnav_Ephemeris::Beidou_Dnav_Ephemeris()
double Beidou_Dnav_Ephemeris::check_t(double time)
{
double corrTime;
double half_week = 302400.0; // seconds
double half_week = 302400.0; // seconds
corrTime = time;
if (time > half_week)
{
@ -166,9 +164,9 @@ double Beidou_Dnav_Ephemeris::sv_clock_relativistic_term(double transmitTime)
// --- Iteratively compute eccentric anomaly ----------------------------
for (int ii = 1; ii < 20; ii++)
{
E_old = E;
E = M + d_eccentricity * sin(E);
dE = fmod(E - E_old, 2.0 * BEIDOU_PI);
E_old = E;
E = M + d_eccentricity * sin(E);
dE = fmod(E - E_old, 2.0 * BEIDOU_PI);
if (fabs(dE) < 1e-12)
{
//Necessary precision is reached, exit from the loop
@ -225,9 +223,9 @@ double Beidou_Dnav_Ephemeris::satellitePosition(double transmitTime)
// --- Iteratively compute eccentric anomaly ----------------------------
for (int ii = 1; ii < 20; ii++)
{
E_old = E;
E = M + d_eccentricity * sin(E);
dE = fmod(E - E_old, 2.0 * BEIDOU_PI);
E_old = E;
E = M + d_eccentricity * sin(E);
dE = fmod(E - E_old, 2.0 * BEIDOU_PI);
if (fabs(dE) < 1e-12)
{
//Necessary precision is reached, exit from the loop
@ -247,16 +245,16 @@ double Beidou_Dnav_Ephemeris::satellitePosition(double transmitTime)
phi = fmod((phi), (2.0 * BEIDOU_PI));
// Correct argument of latitude
u = phi + d_Cuc * cos(2.0 * phi) + d_Cus * sin(2.0 * phi);
u = phi + d_Cuc * cos(2.0 * phi) + d_Cus * sin(2.0 * phi);
// Correct radius
r = a * (1.0 - d_eccentricity*cos(E)) + d_Crc * cos(2.0 * phi) + d_Crs * sin(2.0 * phi);
r = a * (1.0 - d_eccentricity * cos(E)) + d_Crc * cos(2.0 * phi) + d_Crs * sin(2.0 * phi);
// Correct inclination
i = d_i_0 + d_IDOT * tk + d_Cic * cos(2.0 * phi) + d_Cis * sin(2.0 * phi);
// Compute the angle between the ascending node and the Greenwich meridian
Omega = d_OMEGA0 + (d_OMEGA_DOT - BEIDOU_OMEGA_EARTH_DOT)*tk - BEIDOU_OMEGA_EARTH_DOT * d_Toe;
Omega = d_OMEGA0 + (d_OMEGA_DOT - BEIDOU_OMEGA_EARTH_DOT) * tk - BEIDOU_OMEGA_EARTH_DOT * d_Toe;
// Reduce to between 0 and 2*pi rad
Omega = fmod((Omega + 2.0 * BEIDOU_PI), (2.0 * BEIDOU_PI));
@ -268,7 +266,7 @@ double Beidou_Dnav_Ephemeris::satellitePosition(double transmitTime)
// Satellite's velocity. Can be useful for Vector Tracking loops
double Omega_dot = d_OMEGA_DOT - BEIDOU_OMEGA_EARTH_DOT;
d_satvel_X = - Omega_dot * (cos(u) * r + sin(u) * r * cos(i)) + d_satpos_X * cos(Omega) - d_satpos_Y * cos(i) * sin(Omega);
d_satvel_X = -Omega_dot * (cos(u) * r + sin(u) * r * cos(i)) + d_satpos_X * cos(Omega) - d_satpos_Y * cos(i) * sin(Omega);
d_satvel_Y = Omega_dot * (cos(u) * r * cos(Omega) - sin(u) * r * cos(i) * sin(Omega)) + d_satpos_X * sin(Omega) + d_satpos_Y * cos(i) * cos(Omega);
d_satvel_Z = d_satpos_Y * sin(i);

View File

@ -33,11 +33,10 @@
#define GNSS_SDR_BEIDOU_DNAV_EPHEMERIS_H_
#include <map>
#include <string>
#include "boost/assign.hpp"
#include <boost/serialization/nvp.hpp>
#include <map>
#include <string>
/*!
@ -56,45 +55,46 @@ private:
* \param[out] - corrected time, in seconds
*/
double check_t(double time);
public:
unsigned int i_satellite_PRN; // SV PRN NUMBER
double d_TOW; //!< Time of BEIDOU Week of the ephemeris set (taken from subframes TOW) [s]
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s]
double d_M_0; //!< Mean Anomaly at Reference Time [semi-circles]
double d_Cuc; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
double d_eccentricity; //!< Eccentricity [dimensionless]
double d_Cus; //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
double d_sqrt_A; //!< Square Root of the Semi-Major Axis [sqrt(m)]
double d_Toe; //!< Ephemeris data reference time of week (Ref. 20.3.3.4.3 IS-GPS-200E) [s]
double d_Toc; //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
double d_Cic; //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
double d_OMEGA0; //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
double d_Cis; //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
double d_i_0; //!< Inclination Angle at Reference Time [semi-circles]
double d_Crc; //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
double d_OMEGA; //!< Argument of Perigee [semi-cicles]
double d_OMEGA_DOT; //!< Rate of Right Ascension [semi-circles/s]
double d_IDOT; //!< Rate of Inclination Angle [semi-circles/s]
int i_BEIDOU_week; //!< BEIDOU week number, aka WN [week]
int i_SV_accuracy; //!< User Range Accuracy (URA) index of the SV (reference paragraph 6.2.1) for the standard positioning service user (Ref 20.3.3.3.1.3 IS-GPS-200E)
unsigned int i_satellite_PRN; // SV PRN NUMBER
double d_TOW; //!< Time of BEIDOU Week of the ephemeris set (taken from subframes TOW) [s]
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s]
double d_M_0; //!< Mean Anomaly at Reference Time [semi-circles]
double d_Cuc; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
double d_eccentricity; //!< Eccentricity [dimensionless]
double d_Cus; //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
double d_sqrt_A; //!< Square Root of the Semi-Major Axis [sqrt(m)]
double d_Toe; //!< Ephemeris data reference time of week (Ref. 20.3.3.4.3 IS-GPS-200E) [s]
double d_Toc; //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
double d_Cic; //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
double d_OMEGA0; //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
double d_Cis; //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
double d_i_0; //!< Inclination Angle at Reference Time [semi-circles]
double d_Crc; //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
double d_OMEGA; //!< Argument of Perigee [semi-cicles]
double d_OMEGA_DOT; //!< Rate of Right Ascension [semi-circles/s]
double d_IDOT; //!< Rate of Inclination Angle [semi-circles/s]
int i_BEIDOU_week; //!< BEIDOU week number, aka WN [week]
int i_SV_accuracy; //!< User Range Accuracy (URA) index of the SV (reference paragraph 6.2.1) for the standard positioning service user (Ref 20.3.3.3.1.3 IS-GPS-200E)
int i_SV_health;
double d_TGD1; //!< Estimated Group Delay Differential on B1I [s]
double d_TGD2; //!< Estimated Group Delay Differential on B2I [s]
double d_AODC; //!< Age of Data, Clock
double d_AODE; //!< Age of Data, Ephemeris
int i_AODO; //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
double d_TGD1; //!< Estimated Group Delay Differential on B1I [s]
double d_TGD2; //!< Estimated Group Delay Differential on B2I [s]
double d_AODC; //!< Age of Data, Clock
double d_AODE; //!< Age of Data, Ephemeris
int i_AODO; //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
int i_sig_type; //!< BDS: data source (0:unknown,1:B1I,2:B1Q,3:B2I,4:B2Q,5:B3I,6:B3Q) */
int i_nav_type; //!< BDS: nav type (0:unknown,1:IGSO/MEO,2:GEO) */
int i_sig_type; //!< BDS: data source (0:unknown,1:B1I,2:B1Q,3:B2I,4:B2Q,5:B3I,6:B3Q) */
int i_nav_type; //!< BDS: nav type (0:unknown,1:IGSO/MEO,2:GEO) */
bool b_fit_interval_flag;//!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
bool b_fit_interval_flag; //!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
double d_spare1;
double d_spare2;
double d_A_f0; //!< Coefficient 0 of code phase offset model [s]
double d_A_f1; //!< Coefficient 1 of code phase offset model [s/s]
double d_A_f2; //!< Coefficient 2 of code phase offset model [s/s^2]
double d_A_f0; //!< Coefficient 0 of code phase offset model [s]
double d_A_f1; //!< Coefficient 1 of code phase offset model [s/s]
double d_A_f2; //!< Coefficient 2 of code phase offset model [s/s^2]
/*! \brief If true, enhanced level of integrity assurance.
*
@ -111,22 +111,22 @@ public:
bool b_antispoofing_flag; //!< If true, the AntiSpoofing mode is ON in that SV
// clock terms derived from ephemeris data
double d_satClkDrift; //!< GPS clock error
double d_dtr; //!< relativistic clock correction term
double d_satClkDrift; //!< GPS clock error
double d_dtr; //!< relativistic clock correction term
// satellite positions
double d_satpos_X; //!< Earth-fixed coordinate x of the satellite [m]. Intersection of the IERS Reference Meridian (IRM) and the plane passing through the origin and normal to the Z-axis.
double d_satpos_Y; //!< Earth-fixed coordinate y of the satellite [m]. Completes a right-handed, Earth-Centered, Earth-Fixed orthogonal coordinate system.
double d_satpos_Z; //!< Earth-fixed coordinate z of the satellite [m]. The direction of the IERS (International Earth Rotation and Reference Systems Service) Reference Pole (IRP).
double d_satpos_X; //!< Earth-fixed coordinate x of the satellite [m]. Intersection of the IERS Reference Meridian (IRM) and the plane passing through the origin and normal to the Z-axis.
double d_satpos_Y; //!< Earth-fixed coordinate y of the satellite [m]. Completes a right-handed, Earth-Centered, Earth-Fixed orthogonal coordinate system.
double d_satpos_Z; //!< Earth-fixed coordinate z of the satellite [m]. The direction of the IERS (International Earth Rotation and Reference Systems Service) Reference Pole (IRP).
// Satellite velocity
double d_satvel_X; //!< Earth-fixed velocity coordinate x of the satellite [m]
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m]
double d_satvel_X; //!< Earth-fixed velocity coordinate x of the satellite [m]
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m]
std::map<int,std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
template<class Archive>
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.
@ -134,47 +134,49 @@ public:
void serialize(Archive& archive, const unsigned int version)
{
using boost::serialization::make_nvp;
if(version){};
if (version)
{
};
archive & make_nvp("i_satellite_PRN", i_satellite_PRN); // SV PRN NUMBER
archive & make_nvp("d_TOW", d_TOW); //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
archive & make_nvp("d_AODE", d_AODE);
archive & make_nvp("d_Crs", d_Crs); //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
archive & make_nvp("d_Delta_n", d_Delta_n); //!< Mean Motion Difference From Computed Value [semi-circles/s]
archive & make_nvp("d_M_0", d_M_0); //!< Mean Anomaly at Reference Time [semi-circles]
archive & make_nvp("d_Cuc", d_Cuc); //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
archive & make_nvp("d_e_eccentricity", d_eccentricity); //!< Eccentricity [dimensionless]
archive & make_nvp("d_Cus", d_Cus); //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
archive & make_nvp("d_sqrt_A", d_sqrt_A); //!< Square Root of the Semi-Major Axis [sqrt(m)]
archive & make_nvp("d_Toe", d_Toe); //!< Ephemeris data reference time of week (Ref. 20.3.3.4.3 IS-GPS-200E) [s]
archive & make_nvp("d_Toc", d_Toe); //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
archive & make_nvp("d_Cic", d_Cic); //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
archive & make_nvp("d_OMEGA0", d_OMEGA0); //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
archive & make_nvp("d_Cis", d_Cis); //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
archive & make_nvp("d_i_0", d_i_0); //!< Inclination Angle at Reference Time [semi-circles]
archive & make_nvp("d_Crc", d_Crc); //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
archive & make_nvp("d_OMEGA", d_OMEGA); //!< Argument of Perigee [semi-cicles]
archive & make_nvp("d_OMEGA_DOT", d_OMEGA_DOT); //!< Rate of Right Ascension [semi-circles/s]
archive & make_nvp("d_IDOT", d_IDOT); //!< Rate of Inclination Angle [semi-circles/s]
archive & make_nvp("i_BEIDOU_week", i_BEIDOU_week); //!< GPS week number, aka WN [week]
archive & make_nvp("i_SV_accuracy", i_SV_accuracy); //!< User Range Accuracy (URA) index of the SV (reference paragraph 6.2.1) for the standard positioning service user (Ref 20.3.3.3.1.3 IS-GPS-200E)
archive & make_nvp("i_SV_health", i_SV_health);
archive & make_nvp("d_AODC", d_AODC); //!< Issue of Data, Clock
archive & make_nvp("d_TGD1", d_TGD1); //!< Estimated Group Delay Differential: L1-L2 correction term only for the benefit of "L1 P(Y)" or "L2 P(Y)" s users [s]
archive & make_nvp("d_TGD2", d_TGD2); //!< Estimated Group Delay Differential: L1-L2 correction term only for the benefit of "L1 P(Y)" or "L2 P(Y)" s users [s]
archive & make_nvp("i_AODO", i_AODO); //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
archive& make_nvp("i_satellite_PRN", i_satellite_PRN); // SV PRN NUMBER
archive& make_nvp("d_TOW", d_TOW); //!< Time of GPS Week of the ephemeris set (taken from subframes TOW) [s]
archive& make_nvp("d_AODE", d_AODE);
archive& make_nvp("d_Crs", d_Crs); //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
archive& make_nvp("d_Delta_n", d_Delta_n); //!< Mean Motion Difference From Computed Value [semi-circles/s]
archive& make_nvp("d_M_0", d_M_0); //!< Mean Anomaly at Reference Time [semi-circles]
archive& make_nvp("d_Cuc", d_Cuc); //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
archive& make_nvp("d_e_eccentricity", d_eccentricity); //!< Eccentricity [dimensionless]
archive& make_nvp("d_Cus", d_Cus); //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
archive& make_nvp("d_sqrt_A", d_sqrt_A); //!< Square Root of the Semi-Major Axis [sqrt(m)]
archive& make_nvp("d_Toe", d_Toe); //!< Ephemeris data reference time of week (Ref. 20.3.3.4.3 IS-GPS-200E) [s]
archive& make_nvp("d_Toc", d_Toe); //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
archive& make_nvp("d_Cic", d_Cic); //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
archive& make_nvp("d_OMEGA0", d_OMEGA0); //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
archive& make_nvp("d_Cis", d_Cis); //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
archive& make_nvp("d_i_0", d_i_0); //!< Inclination Angle at Reference Time [semi-circles]
archive& make_nvp("d_Crc", d_Crc); //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
archive& make_nvp("d_OMEGA", d_OMEGA); //!< Argument of Perigee [semi-cicles]
archive& make_nvp("d_OMEGA_DOT", d_OMEGA_DOT); //!< Rate of Right Ascension [semi-circles/s]
archive& make_nvp("d_IDOT", d_IDOT); //!< Rate of Inclination Angle [semi-circles/s]
archive& make_nvp("i_BEIDOU_week", i_BEIDOU_week); //!< GPS week number, aka WN [week]
archive& make_nvp("i_SV_accuracy", i_SV_accuracy); //!< User Range Accuracy (URA) index of the SV (reference paragraph 6.2.1) for the standard positioning service user (Ref 20.3.3.3.1.3 IS-GPS-200E)
archive& make_nvp("i_SV_health", i_SV_health);
archive& make_nvp("d_AODC", d_AODC); //!< Issue of Data, Clock
archive& make_nvp("d_TGD1", d_TGD1); //!< Estimated Group Delay Differential: L1-L2 correction term only for the benefit of "L1 P(Y)" or "L2 P(Y)" s users [s]
archive& make_nvp("d_TGD2", d_TGD2); //!< Estimated Group Delay Differential: L1-L2 correction term only for the benefit of "L1 P(Y)" or "L2 P(Y)" s users [s]
archive& make_nvp("i_AODO", i_AODO); //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
archive & make_nvp("b_fit_interval_flag", b_fit_interval_flag);//!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
archive & make_nvp("d_spare1", d_spare1);
archive & make_nvp("d_spare2", d_spare2);
archive& make_nvp("b_fit_interval_flag", b_fit_interval_flag); //!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
archive& make_nvp("d_spare1", d_spare1);
archive& make_nvp("d_spare2", d_spare2);
archive & make_nvp("d_A_f0", d_A_f0); //!< Coefficient 0 of code phase offset model [s]
archive & make_nvp("d_A_f1", d_A_f1); //!< Coefficient 1 of code phase offset model [s/s]
archive & make_nvp("d_A_f2", d_A_f2); //!< Coefficient 2 of code phase offset model [s/s^2]
archive& make_nvp("d_A_f0", d_A_f0); //!< Coefficient 0 of code phase offset model [s]
archive& make_nvp("d_A_f1", d_A_f1); //!< Coefficient 1 of code phase offset model [s/s]
archive& make_nvp("d_A_f2", d_A_f2); //!< Coefficient 2 of code phase offset model [s/s^2]
archive & make_nvp("b_integrity_status_flag", b_integrity_status_flag);
archive & make_nvp("b_alert_flag", b_alert_flag); //!< If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
archive & make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV
archive& make_nvp("b_integrity_status_flag", b_integrity_status_flag);
archive& make_nvp("b_alert_flag", b_alert_flag); //!< If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
archive& make_nvp("b_antispoofing_flag", b_antispoofing_flag); //!< If true, the AntiSpoofing mode is ON in that SV
}
/*!

View File

@ -43,4 +43,3 @@ Beidou_Dnav_Iono::Beidou_Dnav_Iono()
d_beta2 = 0.0;
d_beta3 = 0.0;
}

View File

@ -44,20 +44,20 @@
class Beidou_Dnav_Iono
{
public:
bool valid; //!< Valid flag
bool valid; //!< Valid flag
// Ionospheric parameters
double d_alpha0; //!< Coefficient 0 of a cubic equation representing the amplitude of the vertical delay [s]
double d_alpha1; //!< Coefficient 1 of a cubic equation representing the amplitude of the vertical delay [s/semi-circle]
double d_alpha2; //!< Coefficient 2 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^2]
double d_alpha3; //!< Coefficient 3 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^3]
double d_beta0; //!< Coefficient 0 of a cubic equation representing the period of the model [s]
double d_beta1; //!< Coefficient 1 of a cubic equation representing the period of the model [s/semi-circle]
double d_beta2; //!< Coefficient 2 of a cubic equation representing the period of the model [s(semi-circle)^2]
double d_beta3; //!< Coefficient 3 of a cubic equation representing the period of the model [s(semi-circle)^3]
double d_alpha0; //!< Coefficient 0 of a cubic equation representing the amplitude of the vertical delay [s]
double d_alpha1; //!< Coefficient 1 of a cubic equation representing the amplitude of the vertical delay [s/semi-circle]
double d_alpha2; //!< Coefficient 2 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^2]
double d_alpha3; //!< Coefficient 3 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^3]
double d_beta0; //!< Coefficient 0 of a cubic equation representing the period of the model [s]
double d_beta1; //!< Coefficient 1 of a cubic equation representing the period of the model [s/semi-circle]
double d_beta2; //!< Coefficient 2 of a cubic equation representing the period of the model [s(semi-circle)^2]
double d_beta3; //!< Coefficient 3 of a cubic equation representing the period of the model [s(semi-circle)^3]
Beidou_Dnav_Iono(); //!< Default constructor
Beidou_Dnav_Iono(); //!< Default constructor
template<class Archive>
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.
@ -65,15 +65,17 @@ public:
void serialize(Archive& archive, const unsigned int version)
{
using boost::serialization::make_nvp;
if(version){};
archive & make_nvp("d_alpha0",d_alpha0);
archive & make_nvp("d_alpha1",d_alpha1);
archive & make_nvp("d_alpha2",d_alpha2);
archive & make_nvp("d_alpha3",d_alpha3);
archive & make_nvp("d_beta0",d_beta0);
archive & make_nvp("d_beta1",d_beta1);
archive & make_nvp("d_beta2",d_beta2);
archive & make_nvp("d_beta3",d_beta3);
if (version)
{
};
archive& make_nvp("d_alpha0", d_alpha0);
archive& make_nvp("d_alpha1", d_alpha1);
archive& make_nvp("d_alpha2", d_alpha2);
archive& make_nvp("d_alpha3", d_alpha3);
archive& make_nvp("d_beta0", d_beta0);
archive& make_nvp("d_beta1", d_beta1);
archive& make_nvp("d_beta2", d_beta2);
archive& make_nvp("d_beta3", d_beta3);
}
};

File diff suppressed because it is too large Load Diff

View File

@ -34,17 +34,16 @@
#define GNSS_SDR_BEIDOU_DNAV_NAVIGATION_MESSAGE_H_
#include "Beidou_B1I.h"
#include "beidou_dnav_almanac.h"
#include "beidou_dnav_ephemeris.h"
#include "beidou_dnav_iono.h"
#include "beidou_dnav_utc_model.h"
#include <bitset>
#include <map>
#include <string>
#include <utility>
#include <vector>
#include "beidou_dnav_almanac.h"
#include "beidou_dnav_ephemeris.h"
#include "beidou_dnav_iono.h"
#include "beidou_dnav_utc_model.h"
#include "Beidou_B1I.h"
/*!
@ -55,9 +54,9 @@
class Beidou_Dnav_Navigation_Message
{
private:
unsigned long int read_navigation_unsigned(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int,int>> parameter);
signed long int read_navigation_signed(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int,int>> parameter);
bool read_navigation_bool(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int,int>> parameter);
unsigned long int read_navigation_unsigned(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int, int>>& parameter);
signed long int read_navigation_signed(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int, int>>& parameter);
bool read_navigation_bool(std::bitset<BEIDOU_DNAV_SUBFRAME_DATA_BITS> bits, const std::vector<std::pair<int, int>>& parameter);
void print_beidou_word_bytes(unsigned int BEIDOU_word);
/*
* Accounts for the beginning or end of week crossover
@ -82,97 +81,97 @@ public:
bool flag_crc_test;
double d_previous_aode;
bool flag_d1_sf5_p7; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p8; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p9; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p10; //!< D1 NAV Message, Subframe 5, Page 10 decoded indicator
bool flag_d1_sf5_p7; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p8; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p9; //!< D1 NAV Message, Subframe 5, Page 09 decoded indicator
bool flag_d1_sf5_p10; //!< D1 NAV Message, Subframe 5, Page 10 decoded indicator
bool flag_sf1_p1; //!< D2 NAV Message, Subframe 1, Page 1 decoded indicator
bool flag_sf1_p2; //!< D2 NAV Message, Subframe 1, Page 2 decoded indicator
bool flag_sf1_p3; //!< D2 NAV Message, Subframe 1, Page 3 decoded indicator
bool flag_sf1_p4; //!< D2 NAV Message, Subframe 1, Page 4 decoded indicator
bool flag_sf1_p5; //!< D2 NAV Message, Subframe 1, Page 5 decoded indicator
bool flag_sf1_p6; //!< D2 NAV Message, Subframe 1, Page 6 decoded indicator
bool flag_sf1_p7; //!< D2 NAV Message, Subframe 1, Page 7 decoded indicator
bool flag_sf1_p8; //!< D2 NAV Message, Subframe 1, Page 8 decoded indicator
bool flag_sf1_p9; //!< D2 NAV Message, Subframe 1, Page 9 decoded indicator
bool flag_sf1_p10; //!< D2 NAV Message, Subframe 1, Page 10 decoded indicator
bool flag_sf1_p1; //!< D2 NAV Message, Subframe 1, Page 1 decoded indicator
bool flag_sf1_p2; //!< D2 NAV Message, Subframe 1, Page 2 decoded indicator
bool flag_sf1_p3; //!< D2 NAV Message, Subframe 1, Page 3 decoded indicator
bool flag_sf1_p4; //!< D2 NAV Message, Subframe 1, Page 4 decoded indicator
bool flag_sf1_p5; //!< D2 NAV Message, Subframe 1, Page 5 decoded indicator
bool flag_sf1_p6; //!< D2 NAV Message, Subframe 1, Page 6 decoded indicator
bool flag_sf1_p7; //!< D2 NAV Message, Subframe 1, Page 7 decoded indicator
bool flag_sf1_p8; //!< D2 NAV Message, Subframe 1, Page 8 decoded indicator
bool flag_sf1_p9; //!< D2 NAV Message, Subframe 1, Page 9 decoded indicator
bool flag_sf1_p10; //!< D2 NAV Message, Subframe 1, Page 10 decoded indicator
//broadcast orbit 1
double d_SOW; //!< Time of BeiDou Week of the ephemeris set (taken from subframes SOW) [s]
double d_SOW_SF1; //!< Time of BeiDou Week from HOW word of Subframe 1 [s]
double d_SOW_SF2; //!< Time of BeiDou Week from HOW word of Subframe 2 [s]
double d_SOW_SF3; //!< Time of BeiDou Week from HOW word of Subframe 3 [s]
double d_SOW_SF4; //!< Time of BeiDou Week from HOW word of Subframe 4 [s]
double d_SOW_SF5; //!< Time of BeiDou Week from HOW word of Subframe 5 [s]
double d_SOW; //!< Time of BeiDou Week of the ephemeris set (taken from subframes SOW) [s]
double d_SOW_SF1; //!< Time of BeiDou Week from HOW word of Subframe 1 [s]
double d_SOW_SF2; //!< Time of BeiDou Week from HOW word of Subframe 2 [s]
double d_SOW_SF3; //!< Time of BeiDou Week from HOW word of Subframe 3 [s]
double d_SOW_SF4; //!< Time of BeiDou Week from HOW word of Subframe 4 [s]
double d_SOW_SF5; //!< Time of BeiDou Week from HOW word of Subframe 5 [s]
double d_AODE;
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s]
double d_M_0; //!< Mean Anomaly at Reference Time [semi-circles]
double d_Crs; //!< Amplitude of the Sine Harmonic Correction Term to the Orbit Radius [m]
double d_Delta_n; //!< Mean Motion Difference From Computed Value [semi-circles/s]
double d_M_0; //!< Mean Anomaly at Reference Time [semi-circles]
//broadcast orbit 2
double d_Cuc; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
double d_eccentricity; //!< Eccentricity [dimensionless]
double d_Cus; //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
double d_sqrt_A; //!< Square Root of the Semi-Major Axis [sqrt(m)]
double d_Cuc; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
double d_eccentricity; //!< Eccentricity [dimensionless]
double d_Cus; //!< Amplitude of the Sine Harmonic Correction Term to the Argument of Latitude [rad]
double d_sqrt_A; //!< Square Root of the Semi-Major Axis [sqrt(m)]
//broadcast orbit 3
double d_Toe_sf2; //!< Ephemeris data reference time of week in subframe 2, D1 Message
double d_Toe_sf3; //!< Ephemeris data reference time of week in subframe 3, D1 Message
double d_Toe; //!< Ephemeris data reference time of week in subframe 1, D2 Message
double d_Toc; //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
double d_Cic; //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
double d_OMEGA0; //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
double d_Cis; //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
double d_Toe_sf2; //!< Ephemeris data reference time of week in subframe 2, D1 Message
double d_Toe_sf3; //!< Ephemeris data reference time of week in subframe 3, D1 Message
double d_Toe; //!< Ephemeris data reference time of week in subframe 1, D2 Message
double d_Toc; //!< clock data reference time (Ref. 20.3.3.3.3.1 IS-GPS-200E) [s]
double d_Cic; //!< Amplitude of the Cosine Harmonic Correction Term to the Angle of Inclination [rad]
double d_OMEGA0; //!< Longitude of Ascending Node of Orbit Plane at Weekly Epoch [semi-circles]
double d_Cis; //!< Amplitude of the Sine Harmonic Correction Term to the Angle of Inclination [rad]
//broadcast orbit 4
double d_i_0; //!< Inclination Angle at Reference Time [semi-circles]
double d_Crc; //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
double d_OMEGA; //!< Argument of Perigee [semi-cicles]
double d_OMEGA_DOT; //!< Rate of Right Ascension [semi-circles/s]
double d_i_0; //!< Inclination Angle at Reference Time [semi-circles]
double d_Crc; //!< Amplitude of the Cosine Harmonic Correction Term to the Orbit Radius [m]
double d_OMEGA; //!< Argument of Perigee [semi-cicles]
double d_OMEGA_DOT; //!< Rate of Right Ascension [semi-circles/s]
//broadcast orbit 5
double d_IDOT; //!< Rate of Inclination Angle [semi-circles/s]
int i_BEIDOU_week; //!< BeiDou week number, aka WN [week]
double d_IDOT; //!< Rate of Inclination Angle [semi-circles/s]
int i_BEIDOU_week; //!< BeiDou week number, aka WN [week]
//broadcast orbit 6
int i_SV_accuracy; //!< User Range Accuracy (URA) index of the SV
int i_SV_accuracy; //!< User Range Accuracy (URA) index of the SV
int i_SV_health;
double d_TGD1; //!< Estimated Group Delay Differential in B1 [s]
double d_TGD2; //!< Estimated Group Delay Differential in B2 [s]
double d_AODC; //!< Age of Data, Clock
double d_TGD1; //!< Estimated Group Delay Differential in B1 [s]
double d_TGD2; //!< Estimated Group Delay Differential in B2 [s]
double d_AODC; //!< Age of Data, Clock
//broadcast orbit 7
// int i_AODO; //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
// int i_AODO; //!< Age of Data Offset (AODO) term for the navigation message correction table (NMCT) contained in subframe 4 (reference paragraph 20.3.3.5.1.9) [s]
bool b_fit_interval_flag;//!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
bool b_fit_interval_flag; //!< indicates the curve-fit interval used by the CS (Block II/IIA/IIR/IIR-M/IIF) and SS (Block IIIA) in determining the ephemeris parameters, as follows: 0 = 4 hours, 1 = greater than 4 hours.
double d_spare1;
double d_spare2;
double d_A_f0; //!< Clock correction parameters. Coefficient 0 of code phase offset model [s]
double d_A_f1; //!< Clock correction parameters. Coefficient 1 of code phase offset model [s/s]
double d_A_f2; //!< Clock correction parameters. Coefficient 2 of code phase offset model [s/s^2]
double d_A_f0; //!< Clock correction parameters. Coefficient 0 of code phase offset model [s]
double d_A_f1; //!< Clock correction parameters. Coefficient 1 of code phase offset model [s/s]
double d_A_f2; //!< Clock correction parameters. Coefficient 2 of code phase offset model [s/s^2]
// D2 NAV Message Decoding
unsigned long int d_A_f1_msb_bits; //!< Clock correction parameters, D2 NAV MSB
unsigned long int d_A_f1_lsb_bits; //!< Clock correction parameters, D2 NAV LSB
unsigned long int d_Cuc_msb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_Cuc_lsb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_eccentricity_msb; //!< Eccentricity [dimensionless]
unsigned long int d_eccentricity_lsb; //!< Eccentricity [dimensionless]
unsigned long int d_Cic_msb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_Cic_lsb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_eccentricity_msb_bits; //!< Eccentricity [dimensionless]
unsigned long int d_A_f1_msb_bits; //!< Clock correction parameters, D2 NAV MSB
unsigned long int d_A_f1_lsb_bits; //!< Clock correction parameters, D2 NAV LSB
unsigned long int d_Cuc_msb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_Cuc_lsb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_eccentricity_msb; //!< Eccentricity [dimensionless]
unsigned long int d_eccentricity_lsb; //!< Eccentricity [dimensionless]
unsigned long int d_Cic_msb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_Cic_lsb_bits; //!< Amplitude of the Cosine Harmonic Correction Term to the Argument of Latitude [rad]
unsigned long int d_eccentricity_msb_bits; //!< Eccentricity [dimensionless]
unsigned long int d_eccentricity_lsb_bits;
unsigned long int d_i_0_msb_bits; //!< Inclination Angle at Reference Time [semi-circles]
unsigned long int d_i_0_lsb_bits; //!< Inclination Angle at Reference Time [semi-circles]
unsigned long int d_OMEGA_msb_bits; //!< Argument of Perigee [semi-cicles]
unsigned long int d_OMEGA_lsb_bits; //!< Argument of Perigee [semi-cicles]
unsigned long int d_OMEGA_DOT_msb_bits; //!< Rate of Right Ascension [semi-circles/s]
unsigned long int d_OMEGA_DOT_lsb_bits; //!< Rate of Right Ascension [semi-circles/s]
unsigned long int d_i_0_msb_bits; //!< Inclination Angle at Reference Time [semi-circles]
unsigned long int d_i_0_lsb_bits; //!< Inclination Angle at Reference Time [semi-circles]
unsigned long int d_OMEGA_msb_bits; //!< Argument of Perigee [semi-cicles]
unsigned long int d_OMEGA_lsb_bits; //!< Argument of Perigee [semi-cicles]
unsigned long int d_OMEGA_DOT_msb_bits; //!< Rate of Right Ascension [semi-circles/s]
unsigned long int d_OMEGA_DOT_lsb_bits; //!< Rate of Right Ascension [semi-circles/s]
// Almanac
double d_Toa; //!< Almanac reference time [s]
int i_WN_A; //!< Modulo 256 of the GPS week number to which the almanac reference time (d_Toa) is referenced
std::map<int,int> almanacHealth; //!< Map that stores the health information stored in the almanac
// Almanac
double d_Toa; //!< Almanac reference time [s]
int i_WN_A; //!< Modulo 256 of the GPS week number to which the almanac reference time (d_Toa) is referenced
std::map<int, int> almanacHealth; //!< Map that stores the health information stored in the almanac
std::map<int,std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
std::map<int, std::string> satelliteBlock; //!< Map that stores to which block the PRN belongs http://www.navcen.uscg.gov/?Do=constellationStatus
// Flags
@ -187,40 +186,40 @@ public:
* accompanying alert, is less than 1E-8 per hour.
*/
bool b_integrity_status_flag;
bool b_alert_flag; //!< If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
bool b_alert_flag; //!< If true, indicates that the SV URA may be worse than indicated in d_SV_accuracy, use that SV at our own risk.
bool b_antispoofing_flag; //!< If true, the AntiSpoofing mode is ON in that SV
// clock terms
//double d_master_clock; // GPS transmission time
double d_satClkCorr; // GPS clock error
double d_dtr; // relativistic clock correction term
double d_satClkCorr; // GPS clock error
double d_dtr; // relativistic clock correction term
double d_satClkDrift;
// satellite positions
double d_satpos_X; //!< Earth-fixed coordinate x of the satellite [m]. Intersection of the IERS Reference Meridian (IRM) and the plane passing through the origin and normal to the Z-axis.
double d_satpos_Y; //!< Earth-fixed coordinate y of the satellite [m]. Completes a right-handed, Earth-Centered, Earth-Fixed orthogonal coordinate system.
double d_satpos_Z; //!< Earth-fixed coordinate z of the satellite [m]. The direction of the IERS (International Earth Rotation and Reference Systems Service) Reference Pole (IRP).
double d_satpos_X; //!< Earth-fixed coordinate x of the satellite [m]. Intersection of the IERS Reference Meridian (IRM) and the plane passing through the origin and normal to the Z-axis.
double d_satpos_Y; //!< Earth-fixed coordinate y of the satellite [m]. Completes a right-handed, Earth-Centered, Earth-Fixed orthogonal coordinate system.
double d_satpos_Z; //!< Earth-fixed coordinate z of the satellite [m]. The direction of the IERS (International Earth Rotation and Reference Systems Service) Reference Pole (IRP).
// satellite identification info
int i_channel_ID;
unsigned int i_satellite_PRN;
// time synchro
double d_subframe_timestamp_ms; //[ms]
double d_subframe_timestamp_ms; //[ms]
// Ionospheric parameters
double d_alpha0; //!< Coefficient 0 of a cubic equation representing the amplitude of the vertical delay [s]
double d_alpha1; //!< Coefficient 1 of a cubic equation representing the amplitude of the vertical delay [s/semi-circle]
double d_alpha2; //!< Coefficient 2 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^2]
double d_alpha3; //!< Coefficient 3 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^3]
double d_beta0; //!< Coefficient 0 of a cubic equation representing the period of the model [s]
double d_beta1; //!< Coefficient 1 of a cubic equation representing the period of the model [s/semi-circle]
double d_beta2; //!< Coefficient 2 of a cubic equation representing the period of the model [s(semi-circle)^2]
double d_beta3; //!< Coefficient 3 of a cubic equation representing the period of the model [s(semi-circle)^3]
double d_alpha0; //!< Coefficient 0 of a cubic equation representing the amplitude of the vertical delay [s]
double d_alpha1; //!< Coefficient 1 of a cubic equation representing the amplitude of the vertical delay [s/semi-circle]
double d_alpha2; //!< Coefficient 2 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^2]
double d_alpha3; //!< Coefficient 3 of a cubic equation representing the amplitude of the vertical delay [s(semi-circle)^3]
double d_beta0; //!< Coefficient 0 of a cubic equation representing the period of the model [s]
double d_beta1; //!< Coefficient 1 of a cubic equation representing the period of the model [s/semi-circle]
double d_beta2; //!< Coefficient 2 of a cubic equation representing the period of the model [s(semi-circle)^2]
double d_beta3; //!< Coefficient 3 of a cubic equation representing the period of the model [s(semi-circle)^3]
// UTC parameters
double d_A1UTC; //!< 1st order term of a model that relates GPS and UTC time (ref. 20.3.3.5.2.4 IS-GPS-200E) [s/s]
double d_A0UTC; //!< Constant of a model that relates GPS and UTC time (ref. 20.3.3.5.2.4 IS-GPS-200E) [s]
double d_A1UTC; //!< 1st order term of a model that relates GPS and UTC time (ref. 20.3.3.5.2.4 IS-GPS-200E) [s/s]
double d_A0UTC; //!< Constant of a model that relates GPS and UTC time (ref. 20.3.3.5.2.4 IS-GPS-200E) [s]
double d_DeltaT_LS; //!< delta time due to leap seconds [s]. Number of leap seconds since 6-Jan-1980 as transmitted by the GPS almanac.
int i_WN_LSF; //!< Week number at the end of which the leap second becomes effective [weeks]
int i_DN; //!< Day number (DN) at the end of which the leap second becomes effective [days]
@ -242,13 +241,13 @@ public:
double d_OMEGA_DOT_ALMANAC;
double d_OMEGA_ALMANAC;
double d_M0_ALMANAC;
int almanac_WN;
int almanac_WN;
double d_toa2;
// Satellite velocity
double d_satvel_X; //!< Earth-fixed velocity coordinate x of the satellite [m]
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m]
double d_satvel_X; //!< Earth-fixed velocity coordinate x of the satellite [m]
double d_satvel_Y; //!< Earth-fixed velocity coordinate y of the satellite [m]
double d_satvel_Z; //!< Earth-fixed velocity coordinate z of the satellite [m]
// public functions
@ -273,12 +272,12 @@ public:
/*!
* \brief Decodes the BDS D1 NAV message
*/
int d1_subframe_decoder(std::string const &subframe);
int d1_subframe_decoder(std::string const& subframe);
/*!
* \brief Decodes the BDS D2 NAV message
*/
int d2_subframe_decoder(std::string const &subframe);
int d2_subframe_decoder(std::string const& subframe);
/*!
* \brief Computes the position of the satellite

View File

@ -49,4 +49,3 @@ Beidou_Dnav_Utc_Model::Beidou_Dnav_Utc_Model()
d_A0_GLO = 0;
d_A1_GLO = 0;
}

View File

@ -48,24 +48,24 @@ public:
bool valid;
// BeiDou UTC parameters
double d_A0_UTC; //!< BDT clock bias relative to UTC [s]
double d_A1_UTC; //!< BDT clock rate relative to UTC [s/s]
double d_A0_UTC; //!< BDT clock bias relative to UTC [s]
double d_A1_UTC; //!< BDT clock rate relative to UTC [s/s]
double d_DeltaT_LS; //!< Delta time due to leap seconds before the new leap second effective
int i_WN_LSF; //!< Week number of the new leap second
int i_DN; //!< Day number of week of the new leap second
double d_DeltaT_LSF; //!< Delta time due to leap seconds after the new leap second effective [s]
// BeiDou to GPS time corrections
double d_A0_GPS; //!< BDT clock bias relative to GPS time [s]
double d_A1_GPS; //!< BDT clock rate relative to GPS time [s/s]
double d_A0_GPS; //!< BDT clock bias relative to GPS time [s]
double d_A1_GPS; //!< BDT clock rate relative to GPS time [s/s]
// BeiDou to Galileo time corrections
double d_A0_GAL; //!< BDT clock bias relative to GAL time [s]
double d_A1_GAL; //!< BDT clock rate relative to GAL time [s/s]
double d_A0_GAL; //!< BDT clock bias relative to GAL time [s]
double d_A1_GAL; //!< BDT clock rate relative to GAL time [s/s]
// BeiDou to GLONASS time corrections
double d_A0_GLO; //!< BDT clock bias relative to GLO time [s]
double d_A1_GLO; //!< BDT clock rate relative to GLO time [s/s]
double d_A0_GLO; //!< BDT clock bias relative to GLO time [s]
double d_A1_GLO; //!< BDT clock rate relative to GLO time [s/s]
Beidou_Dnav_Utc_Model();
@ -93,7 +93,6 @@ public:
archive& make_nvp("d_A0_GPS", d_A0_GLO);
archive& make_nvp("d_A0_GPS", d_A1_GLO);
}
};
#endif

View File

@ -616,55 +616,55 @@ std::string Gnss_Satellite::what_block(const std::string& system_, uint32_t PRN_
block_ = std::string("Unknown(Simulated)");
}
}
if (system_.compare("Beidou") == 0)
if (system_ == "Beidou")
{
// Check https://en.wikipedia.org/wiki/List_of_BeiDou_satellites
switch ( PRN_ )
{
case 19:
block_ = std::string("BEIDOU-3 M1"); //!<Slot B-7; launched 2017/11/05
break;
case 20:
block_ = std::string("BEIDOU-3 M2"); //!<Slot B-5; launched 2017/11/05
break;
case 21:
block_ = std::string("BEIDOU 3M5"); //!<Slot B-?; launched 2018/02/12
break;
case 22:
block_ = std::string("BEIDOU 3M6"); //!<Slot B-6; launched 2018/02/12
break;
case 23:
block_ = std::string("BEIDOU 3M9"); //!<Slot C-7; launched 2018/07/29
break;
case 24:
block_ = std::string("BEIDOU 3M10"); //!<Slot C-1; launched 2018/07/29
break;
case 25:
block_ = std::string("BEIDOU 3M12"); //!<Slot C-8; launched 2018/08/24
break;
case 26:
block_ = std::string("BEIDOU 3M11"); //!<Slot C-2; launched 2018/08/24
break;
case 27:
block_ = std::string("BEIDOU 3M3"); //!<Slot A-?; launched 2018/01/11
break;
case 28:
block_ = std::string("BEIDOU 3M4"); //!<Slot A-?; launched 2018/01/11
break;
case 29:
block_ = std::string("BEIDOU 3M7"); //!<Slot A-?; launched 2018/03/29
break;
case 30:
block_ = std::string("BEIDOU 3M8"); //!<Slot A-?; launched 2018/03/29
break;
case 32:
block_ = std::string("BEIDOU 3M13"); //!<Slot B-1?; launched 2018/09/19
break;
case 33:
block_ = std::string("BEIDOU 3M14"); //!<Slot B-3; launched 2018/09/19
break;
default:
block_ = std::string("Unknown(Simulated)");
switch (PRN_)
{
case 19:
block_ = std::string("BEIDOU-3 M1"); //!<Slot B-7; launched 2017/11/05
break;
case 20:
block_ = std::string("BEIDOU-3 M2"); //!<Slot B-5; launched 2017/11/05
break;
case 21:
block_ = std::string("BEIDOU 3M5"); //!<Slot B-?; launched 2018/02/12
break;
case 22:
block_ = std::string("BEIDOU 3M6"); //!<Slot B-6; launched 2018/02/12
break;
case 23:
block_ = std::string("BEIDOU 3M9"); //!<Slot C-7; launched 2018/07/29
break;
case 24:
block_ = std::string("BEIDOU 3M10"); //!<Slot C-1; launched 2018/07/29
break;
case 25:
block_ = std::string("BEIDOU 3M12"); //!<Slot C-8; launched 2018/08/24
break;
case 26:
block_ = std::string("BEIDOU 3M11"); //!<Slot C-2; launched 2018/08/24
break;
case 27:
block_ = std::string("BEIDOU 3M3"); //!<Slot A-?; launched 2018/01/11
break;
case 28:
block_ = std::string("BEIDOU 3M4"); //!<Slot A-?; launched 2018/01/11
break;
case 29:
block_ = std::string("BEIDOU 3M7"); //!<Slot A-?; launched 2018/03/29
break;
case 30:
block_ = std::string("BEIDOU 3M8"); //!<Slot A-?; launched 2018/03/29
break;
case 32:
block_ = std::string("BEIDOU 3M13"); //!<Slot B-1?; launched 2018/09/19
break;
case 33:
block_ = std::string("BEIDOU 3M14"); //!<Slot B-3; launched 2018/09/19
break;
default:
block_ = std::string("Unknown(Simulated)");
}
}
return block_;

View File

@ -119,7 +119,7 @@ DECLARE_string(log_dir);
#include "unit-tests/signal-processing-blocks/sources/gnss_sdr_valve_test.cc"
#include "unit-tests/signal-processing-blocks/sources/unpack_2bit_samples_test.cc"
// #include "unit-tests/signal-processing-blocks/acquisition/glonass_l2_ca_pcps_acquisition_test.cc"
#include "unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc"
// #include "unit-tests/signal-processing-blocks/acquisition/beidou_b1i_pcps_acquisition_test.cc"
#if OPENCL_BLOCKS_TEST
#include "unit-tests/signal-processing-blocks/acquisition/gps_l1_ca_pcps_opencl_acquisition_gsoc2013_test.cc"

View File

@ -31,27 +31,27 @@
*/
#include <chrono>
#include <boost/filesystem.hpp>
#include <boost/make_shared.hpp>
#include <glog/logging.h>
#include <gnuradio/top_block.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/analog/sig_source_waveform.h>
#include <gnuradio/analog/sig_source_c.h>
#include <gnuradio/msg_queue.h>
#include <gnuradio/blocks/null_sink.h>
#include <gtest/gtest.h>
#include "Beidou_B1I.h"
#include "acquisition_dump_reader.h"
#include "beidou_b1i_pcps_acquisition.h"
#include "gnss_block_factory.h"
#include "gnss_block_interface.h"
#include "in_memory_configuration.h"
#include "gnss_sdr_valve.h"
#include "gnss_synchro.h"
#include "gnuplot_i.h"
#include "in_memory_configuration.h"
#include "test_flags.h"
#include "acquisition_dump_reader.h"
#include "beidou_b1i_pcps_acquisition.h"
#include "../../../../core/system_parameters/Beidou_B1I.h"
#include <boost/filesystem.hpp>
#include <boost/make_shared.hpp>
#include <glog/logging.h>
#include <gnuradio/analog/sig_source_c.h>
#include <gnuradio/analog/sig_source_waveform.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/null_sink.h>
#include <gnuradio/msg_queue.h>
#include <gnuradio/top_block.h>
#include <gtest/gtest.h>
#include <chrono>
// ######## GNURADIO BLOCK MESSAGE RECEVER #########

View File

@ -31,7 +31,6 @@
#include "file_signal_source.h"
#include "in_memory_configuration.h"
#include <gnuradio/blocks/null_sink.h>
#include <gnuradio/msg_queue.h>
#include <gnuradio/top_block.h>
#include <gtest/gtest.h>

View File

@ -70,7 +70,7 @@
#define FIVE_SECONDS 5000000 // five seconds in microseconds
void send_tracking_gps_input_samples(FILE *rx_signal_file,
int num_remaining_samples, const gr::top_block_sptr& top_block)
int num_remaining_samples, const gr::top_block_sptr &top_block)
{
int num_samples_transferred = 0; // number of samples that have been transferred to the DMA so far
static int flowgraph_stopped = 0; // flag to indicate if the flowgraph is stopped already

View File

@ -34,15 +34,15 @@ if ~exist('dll_pll_veml_read_tracking_dump.m', 'file')
addpath('./libs')
end
samplingFreq = 25000000; %[Hz]
coherent_integration_time_ms = 1; %[ms]
channels = 10; % Number of channels
samplingFreq = 5000000; %[Hz]
coherent_integration_time_ms = 20; %[ms]
channels = 5; % Number of channels
first_channel = 0; % Number of the first channel
path = '/home/dmiralles/Documents/gnss-sdr/';%#'; %% CHANGE THIS PATH
path = '/dump_dir/'; %% CHANGE THIS PATH
for N=1:1:channels
tracking_log_path = [path 'epl_tracking_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE track_ch_ BY YOUR dump_filename
tracking_log_path = [path 'track_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE track_ch_ BY YOUR dump_filename
GNSS_tracking(N) = dll_pll_veml_read_tracking_dump(tracking_log_path);
end

View File

@ -38,7 +38,7 @@ samplingFreq = 6625000; %[Hz]
channels = 5;
first_channel = 0;
path = '/home/sergi/gnss/gnss-sdr/install/'; %% CHANGE THIS PATH
path = '/archive/'; %% CHANGE THIS PATH
for N=1:1:channels
tracking_log_path = [path 'epl_tracking_ch_' num2str(N+first_channel-1) '.dat']; %% CHANGE epl_tracking_ch_ BY YOUR dump_filename
@ -65,7 +65,7 @@ for N=1:1:channels
trackResults(N).Q_L = zeros(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
settings.numberOfChannels = channels;
settings.msToProcess = length(GNSS_tracking(N).E);

View File

@ -29,10 +29,10 @@
clearvars;
close all;
addpath('./libs');
samplingFreq = 25000000; %[Hz]
channels=10;
path='/home/dmiralles/Documents/gnss-sdr/';
observables_log_path=[path 'observables.dat'];
samplingFreq = 6625000; %[Hz]
channels=5;
path='/archive/';
observables_log_path=[path 'glo_observables.dat'];
GNSS_observables= read_hybrid_observables_dump(channels,observables_log_path);
%%

Binary file not shown.