mirror of
https://github.com/gnss-sdr/gnss-sdr
synced 2025-01-27 17:34:53 +00:00
Refactoring code. Adding new experimental tests and new common TX time observables algorithm
This commit is contained in:
parent
cec063f360
commit
807ca24fc2
@ -7,7 +7,8 @@
|
||||
|
||||
;######### GLOBAL OPTIONS ##################
|
||||
;internal_fs_hz: Internal signal sampling frequency after the signal conditioning stage [Hz].
|
||||
GNSS-SDR.internal_fs_hz=4000000
|
||||
;#GNSS-SDR.internal_fs_hz=2048000
|
||||
GNSS-SDR.internal_fs_hz=2600000
|
||||
|
||||
|
||||
;######### SIGNAL_SOURCE CONFIG ############
|
||||
@ -15,7 +16,8 @@ GNSS-SDR.internal_fs_hz=4000000
|
||||
SignalSource.implementation=File_Signal_Source
|
||||
|
||||
;#filename: path to file with the captured GNSS signal samples to be processed
|
||||
SignalSource.filename=/datalogger/signals/gnss-sim/signal_out.bin ; <- PUT YOUR FILE HERE
|
||||
;#SignalSource.filename=/home/javier/Descargas/rtlsdr_tcxo_l1/rtlsdr_tcxo_l1.bin ; <- PUT YOUR FILE HERE
|
||||
SignalSource.filename=/home/javier/git/gnss-sdr/build/signal_out.bin ; <- PUT YOUR FILE HERE
|
||||
|
||||
;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version.
|
||||
SignalSource.item_type=byte
|
||||
@ -53,7 +55,7 @@ SignalConditioner.implementation=Signal_Conditioner
|
||||
;######### DATA_TYPE_ADAPTER CONFIG ############
|
||||
;## Changes the type of input data. Please disable it in this version.
|
||||
;#implementation: [Pass_Through] disables this block
|
||||
DataTypeAdapter.implementation=Ibyte_To_Cshort
|
||||
DataTypeAdapter.implementation=Ibyte_To_Complex
|
||||
DataTypeAdapter.dump=false
|
||||
;#dump_filename: Log path and filename.
|
||||
DataTypeAdapter.dump_filename=../data/DataTypeAdapter.dat
|
||||
@ -81,10 +83,10 @@ InputFilter.dump_filename=../data/input_filter.dat
|
||||
;#These function calculates the optimal (in the Chebyshev/minimax sense) FIR filter inpulse reponse given a set of band edges, the desired reponse on those bands, and the weight given to the error in those bands.
|
||||
|
||||
;#input_item_type: Type and resolution for input signal samples. Use only gr_complex in this version.
|
||||
InputFilter.input_item_type=cshort
|
||||
InputFilter.input_item_type=gr_complex
|
||||
|
||||
;#outut_item_type: Type and resolution for output filtered signal samples. Use only gr_complex in this version.
|
||||
InputFilter.output_item_type=cshort
|
||||
InputFilter.output_item_type=gr_complex
|
||||
|
||||
;#taps_item_type: Type and resolution for the taps of the filter. Use only float in this version.
|
||||
InputFilter.taps_item_type=float
|
||||
@ -127,7 +129,7 @@ InputFilter.grid_density=16
|
||||
;#The following options are used only in Freq_Xlating_Fir_Filter implementation.
|
||||
;#InputFilter.IF is the intermediate frequency (in Hz) shifted down to zero Hz
|
||||
|
||||
InputFilter.sampling_frequency=4000000
|
||||
InputFilter.sampling_frequency=2600000
|
||||
InputFilter.IF=0
|
||||
|
||||
|
||||
@ -135,26 +137,8 @@ InputFilter.IF=0
|
||||
;######### RESAMPLER CONFIG ############
|
||||
;## Resamples the input data.
|
||||
|
||||
;#implementation: Use [Pass_Through] or [Direct_Resampler]
|
||||
;#[Pass_Through] disables this block
|
||||
;#[Direct_Resampler] enables a resampler that implements a nearest neigbourhood interpolation
|
||||
;Resampler.implementation=Direct_Resampler
|
||||
Resampler.implementation=Pass_Through
|
||||
|
||||
;#dump: Dump the resamplered data to a file.
|
||||
Resampler.dump=false
|
||||
;#dump_filename: Log path and filename.
|
||||
Resampler.dump_filename=../data/resampler.dat
|
||||
|
||||
;#item_type: Type and resolution for each of the signal samples.
|
||||
Resampler.item_type=cshort
|
||||
|
||||
;#sample_freq_in: the sample frequency of the input signal
|
||||
Resampler.sample_freq_in=4000000
|
||||
|
||||
;#sample_freq_out: the desired sample frequency of the output signal
|
||||
Resampler.sample_freq_out=4000000
|
||||
|
||||
Resampler.item_type = gr_complex;
|
||||
|
||||
;######### CHANNELS GLOBAL CONFIG ############
|
||||
;#count: Number of available GPS satellite channels.
|
||||
@ -167,7 +151,7 @@ Channels.in_acquisition=1
|
||||
|
||||
;#IMPORTANT: When cshort is used as input type for Acq and Trk, please set the Channel type to cshort here
|
||||
;#item_type: Type and resolution for each of the signal samples.
|
||||
Channel.item_type=cshort
|
||||
Channel.item_type=gr_complex
|
||||
;#signal:
|
||||
;#if the option is disabled by default is assigned "1C" GPS L1 C/A
|
||||
Channel1.signal=1C
|
||||
@ -194,7 +178,7 @@ Acquisition_1C.dump=false
|
||||
;#filename: Log path and filename
|
||||
Acquisition_1C.dump_filename=./acq_dump.dat
|
||||
;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version.
|
||||
Acquisition_1C.item_type=cshort
|
||||
Acquisition_1C.item_type=gr_complex
|
||||
;#if: Signal intermediate frequency in [Hz]
|
||||
Acquisition_1C.if=0
|
||||
;#sampled_ms: Signal block duration for the acquisition signal detection [ms]
|
||||
@ -205,7 +189,7 @@ Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
|
||||
;#notice that this affects the Acquisition threshold range!
|
||||
Acquisition_1C.use_CFAR_algorithm=false;
|
||||
;#threshold: Acquisition threshold
|
||||
Acquisition_1C.threshold=11
|
||||
Acquisition_1C.threshold=15
|
||||
;#pfa: Acquisition false alarm probability. This option overrides the threshold option. Only use with implementations: [GPS_L1_CA_PCPS_Acquisition] or [Galileo_E1_PCPS_Ambiguous_Acquisition]
|
||||
;Acquisition_1C.pfa=0.01
|
||||
;#doppler_max: Maximum expected Doppler shift [Hz]
|
||||
@ -221,7 +205,7 @@ Acquisition_1B.dump=false
|
||||
;#filename: Log path and filename
|
||||
Acquisition_1B.dump_filename=./acq_dump.dat
|
||||
;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version.
|
||||
Acquisition_1B.item_type=cshort
|
||||
Acquisition_1B.item_type=gr_complex
|
||||
;#if: Signal intermediate frequency in [Hz]
|
||||
Acquisition_1B.if=0
|
||||
;#sampled_ms: Signal block duration for the acquisition signal detection [ms]
|
||||
@ -240,9 +224,9 @@ Acquisition_1B.doppler_step=125
|
||||
;######### TRACKING GPS CONFIG ############
|
||||
|
||||
;#implementation: Selected tracking algorithm: [GPS_L1_CA_DLL_PLL_Tracking] or [GPS_L1_CA_DLL_PLL_C_Aid_Tracking] or [GPS_L1_CA_TCP_CONNECTOR_Tracking] or [Galileo_E1_DLL_PLL_VEML_Tracking]
|
||||
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_C_Aid_Tracking
|
||||
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
|
||||
;#item_type: Type and resolution for each of the signal samples. Use only [gr_complex] in this version.
|
||||
Tracking_1C.item_type=cshort
|
||||
Tracking_1C.item_type=gr_complex
|
||||
|
||||
;#sampling_frequency: Signal Intermediate Frequency in [Hz]
|
||||
Tracking_1C.if=0
|
||||
@ -254,7 +238,7 @@ Tracking_1C.dump=false
|
||||
Tracking_1C.dump_filename=../data/epl_tracking_ch_
|
||||
|
||||
;#pll_bw_hz: PLL loop filter bandwidth [Hz]
|
||||
Tracking_1C.pll_bw_hz=15.0;
|
||||
Tracking_1C.pll_bw_hz=20.0;
|
||||
|
||||
;#dll_bw_hz: DLL loop filter bandwidth [Hz]
|
||||
Tracking_1C.dll_bw_hz=1.5;
|
||||
@ -267,7 +251,7 @@ Tracking_1C.order=3;
|
||||
;#implementation: Selected tracking algorithm: [GPS_L1_CA_DLL_PLL_Tracking] or [GPS_L1_CA_DLL_PLL_C_Aid_Tracking] or [GPS_L1_CA_TCP_CONNECTOR_Tracking] or [Galileo_E1_DLL_PLL_VEML_Tracking]
|
||||
Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking
|
||||
;#item_type: Type and resolution for each of the signal samples.
|
||||
Tracking_1B.item_type=cshort
|
||||
Tracking_1B.item_type=gr_complex
|
||||
|
||||
;#sampling_frequency: Signal Intermediate Frequency in [Hz]
|
||||
Tracking_1B.if=0
|
||||
|
@ -74,7 +74,7 @@ DataTypeAdapter0.item_type=gr_complex
|
||||
InputFilter0.implementation=Freq_Xlating_Fir_Filter
|
||||
|
||||
;#dump: Dump the filtered data to a file.
|
||||
InputFilter0.dump=false
|
||||
InputFilter0.dump=true
|
||||
|
||||
;#dump_filename: Log path and filename.
|
||||
InputFilter0.dump_filename=../data/input_filter_ch0.dat
|
||||
@ -267,13 +267,13 @@ Resampler2.implementation=Pass_Through
|
||||
|
||||
;######### CHANNELS GLOBAL CONFIG ############
|
||||
;#count: Number of available GPS satellite channels.
|
||||
Channels_1C.count=0
|
||||
Channels_2S.count=11
|
||||
Channels_1C.count=11
|
||||
Channels_2S.count=0
|
||||
|
||||
;#GPS.prns=7,8
|
||||
|
||||
;#in_acquisition: Number of channels simultaneously acquiring for the whole receiver
|
||||
Channels.in_acquisition=10
|
||||
Channels.in_acquisition=1
|
||||
|
||||
;# signal:
|
||||
;# "1C" GPS L1 C/A
|
||||
@ -283,23 +283,26 @@ Channels.in_acquisition=10
|
||||
;# CHANNEL NUMBERING ORDER: GPS L1 C/A, GPS L2 L2C (M), GALILEO E1 B, GALILEO E5a
|
||||
|
||||
;# CHANNEL CONNECTION
|
||||
Channel0.RF_channel_ID=1
|
||||
Channel1.RF_channel_ID=1
|
||||
Channel2.RF_channel_ID=1
|
||||
Channel3.RF_channel_ID=1
|
||||
Channel4.RF_channel_ID=1
|
||||
Channel5.RF_channel_ID=1
|
||||
Channel6.RF_channel_ID=1
|
||||
Channel7.RF_channel_ID=1
|
||||
Channel8.RF_channel_ID=1
|
||||
Channel9.RF_channel_ID=1
|
||||
Channel10.RF_channel_ID=0
|
||||
Channel0.RF_channel_ID=0
|
||||
Channel1.RF_channel_ID=0
|
||||
Channel2.RF_channel_ID=0
|
||||
Channel3.RF_channel_ID=0
|
||||
Channel4.RF_channel_ID=0
|
||||
Channel5.RF_channel_ID=0
|
||||
Channel6.RF_channel_ID=0
|
||||
Channel7.RF_channel_ID=0
|
||||
Channel8.RF_channel_ID=0
|
||||
Channel9.RF_channel_ID=0
|
||||
Channel10.RF_channel_ID=1
|
||||
Channel11.RF_channel_ID=1
|
||||
Channel12.RF_channel_ID=0
|
||||
Channel12.RF_channel_ID=1
|
||||
Channel13.RF_channel_ID=1
|
||||
Channel14.RF_channel_ID=1
|
||||
Channel15.RF_channel_ID=1
|
||||
|
||||
Channel16.RF_channel_ID=1
|
||||
Channel17.RF_channel_ID=1
|
||||
Channel18.RF_channel_ID=1
|
||||
Channel19.RF_channel_ID=1
|
||||
|
||||
|
||||
;######### ACQUISITION GENERIC CONFIG ######
|
||||
@ -349,7 +352,7 @@ Tracking_1C.early_late_space_chips=0.5;
|
||||
Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking
|
||||
Tracking_2S.item_type=gr_complex
|
||||
Tracking_2S.if=0
|
||||
Tracking_2S.dump=true
|
||||
Tracking_2S.dump=false
|
||||
Tracking_2S.dump_filename=./tracking_ch_
|
||||
Tracking_2S.pll_bw_hz=2.0;
|
||||
Tracking_2S.dll_bw_hz=0.25;
|
||||
@ -370,9 +373,9 @@ TelemetryDecoder_2S.decimation_factor=1;
|
||||
;######### OBSERVABLES CONFIG ############
|
||||
;#implementation: Use [GPS_L1_CA_Observables] for GPS L1 C/A.
|
||||
Observables.implementation=Hybrid_Observables
|
||||
|
||||
Observables.averaging_depth = 100
|
||||
;#dump: Enable or disable the Observables internal binary data file logging [true] or [false]
|
||||
Observables.dump=true
|
||||
Observables.dump=false
|
||||
|
||||
;#dump_filename: Log path and filename.
|
||||
Observables.dump_filename=./observables.dat
|
||||
@ -383,13 +386,13 @@ Observables.dump_filename=./observables.dat
|
||||
PVT.implementation=Hybrid_PVT
|
||||
|
||||
;#averaging_depth: Number of PVT observations in the moving average algorithm
|
||||
PVT.averaging_depth=10
|
||||
PVT.averaging_depth=5
|
||||
|
||||
;#flag_average: Enables the PVT averaging between output intervals (arithmetic mean) [true] or [false]
|
||||
PVT.flag_averaging=false
|
||||
|
||||
;#output_rate_ms: Period between two PVT outputs. Notice that the minimum period is equal to the tracking integration time (for GPS CA L1 is 1ms) [ms]
|
||||
PVT.output_rate_ms=1
|
||||
PVT.output_rate_ms=100
|
||||
|
||||
;#display_rate_ms: Position console print (std::out) interval [ms]. Notice that output_rate_ms<=display_rate_ms.
|
||||
PVT.display_rate_ms=100
|
||||
|
@ -266,13 +266,13 @@ Resampler2.implementation=Pass_Through
|
||||
|
||||
;######### CHANNELS GLOBAL CONFIG ############
|
||||
;#count: Number of available GPS satellite channels.
|
||||
Channels_1C.count=8
|
||||
Channels_2S.count=8
|
||||
Channels_1C.count=10
|
||||
Channels_2S.count=4
|
||||
|
||||
;#GPS.prns=7,8
|
||||
|
||||
;#in_acquisition: Number of channels simultaneously acquiring for the whole receiver
|
||||
Channels.in_acquisition=8
|
||||
Channels.in_acquisition=1
|
||||
|
||||
;# signal:
|
||||
;# "1C" GPS L1 C/A
|
||||
@ -290,15 +290,18 @@ Channel4.RF_channel_ID=0
|
||||
Channel5.RF_channel_ID=0
|
||||
Channel6.RF_channel_ID=0
|
||||
Channel7.RF_channel_ID=0
|
||||
Channel8.RF_channel_ID=1
|
||||
Channel9.RF_channel_ID=1
|
||||
Channel8.RF_channel_ID=0
|
||||
Channel9.RF_channel_ID=0
|
||||
Channel10.RF_channel_ID=1
|
||||
Channel11.RF_channel_ID=1
|
||||
Channel12.RF_channel_ID=1
|
||||
Channel13.RF_channel_ID=1
|
||||
Channel14.RF_channel_ID=1
|
||||
Channel15.RF_channel_ID=1
|
||||
|
||||
Channel16.RF_channel_ID=1
|
||||
Channel17.RF_channel_ID=1
|
||||
Channel18.RF_channel_ID=1
|
||||
Channel19.RF_channel_ID=1
|
||||
|
||||
|
||||
;######### ACQUISITION GENERIC CONFIG ######
|
||||
@ -316,32 +319,19 @@ Acquisition_1C.doppler_step=250
|
||||
Acquisition_1C.bit_transition_flag=false
|
||||
Acquisition_1C.max_dwells=1
|
||||
|
||||
;# GPS L2C M
|
||||
Acquisition_2S.dump=false
|
||||
Acquisition_2S.dump_filename=./acq_dump.dat
|
||||
Acquisition_2S.item_type=gr_complex
|
||||
Acquisition_2S.if=0
|
||||
Acquisition_2S.coherent_integration_time_ms=1
|
||||
Acquisition_2S.implementation=GPS_L2_M_PCPS_Acquisition
|
||||
Acquisition_2S.threshold=0.0005
|
||||
Acquisition_2S.threshold=0.00074
|
||||
;Acquisition_2S.pfa=0.001
|
||||
Acquisition_2S.doppler_max=5000
|
||||
Acquisition_2S.doppler_step=100
|
||||
Acquisition_2S.bit_transition_flag=false
|
||||
Acquisition_2S.doppler_min=-5000
|
||||
Acquisition_2S.doppler_step=60
|
||||
Acquisition_2S.max_dwells=1
|
||||
|
||||
;# channel specific config
|
||||
|
||||
Acquisition_2S1.dump=false
|
||||
Acquisition_2S1.dump_filename=./acq_dump.dat
|
||||
Acquisition_2S1.item_type=gr_complex
|
||||
Acquisition_2S1.if=0
|
||||
Acquisition_2S1.coherent_integration_time_ms=1
|
||||
Acquisition_2S1.implementation=GPS_L2_M_PCPS_Acquisition
|
||||
Acquisition_2S1.threshold=0.0005
|
||||
Acquisition_2S1.doppler_max=5000
|
||||
Acquisition_2S1.doppler_step=100
|
||||
Acquisition_2S1.bit_transition_flag=false
|
||||
Acquisition_2S1.max_dwells=1
|
||||
|
||||
|
||||
;######### TRACKING CONFIG ############
|
||||
|
||||
@ -349,7 +339,7 @@ Acquisition_2S1.max_dwells=1
|
||||
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
|
||||
Tracking_1C.item_type=gr_complex
|
||||
Tracking_1C.if=0
|
||||
Tracking_1C.dump=true
|
||||
Tracking_1C.dump=false
|
||||
Tracking_1C.dump_filename=../data/epl_tracking_ch_
|
||||
Tracking_1C.pll_bw_hz=40.0;
|
||||
Tracking_1C.dll_bw_hz=3.0;
|
||||
@ -361,24 +351,13 @@ Tracking_1C.early_late_space_chips=0.5;
|
||||
Tracking_2S.implementation=GPS_L2_M_DLL_PLL_Tracking
|
||||
Tracking_2S.item_type=gr_complex
|
||||
Tracking_2S.if=0
|
||||
Tracking_2S.dump=true
|
||||
Tracking_2S.dump_filename=../data/epl_tracking_ch_
|
||||
Tracking_2S.dump=false
|
||||
Tracking_2S.dump_filename=./tracking_ch_
|
||||
Tracking_2S.pll_bw_hz=2.0;
|
||||
Tracking_2S.dll_bw_hz=0.5;
|
||||
Tracking_2S.dll_bw_hz=0.25;
|
||||
Tracking_2S.order=2;
|
||||
Tracking_2S.early_late_space_chips=0.5;
|
||||
|
||||
;######### GPS L2C SPECIFIC CHANNEL TRACKING CONFIG ############
|
||||
Tracking_2S1.implementation=GPS_L2_M_DLL_PLL_Tracking
|
||||
Tracking_2S1.item_type=gr_complex
|
||||
Tracking_2S1.if=0
|
||||
Tracking_2S1.dump=true
|
||||
Tracking_2S1.dump_filename=../data/epl_tracking_ch_
|
||||
Tracking_2S1.pll_bw_hz=2.0;
|
||||
Tracking_2S1.dll_bw_hz=0.5;
|
||||
Tracking_2S1.order=2;
|
||||
Tracking_2S1.early_late_space_chips=0.5;
|
||||
|
||||
|
||||
;######### TELEMETRY DECODER CONFIG ############
|
||||
TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder
|
||||
@ -393,9 +372,9 @@ TelemetryDecoder_2S.decimation_factor=1;
|
||||
;######### OBSERVABLES CONFIG ############
|
||||
;#implementation: Use [GPS_L1_CA_Observables] for GPS L1 C/A.
|
||||
Observables.implementation=Hybrid_Observables
|
||||
|
||||
Observables.averaging_depth = 5
|
||||
;#dump: Enable or disable the Observables internal binary data file logging [true] or [false]
|
||||
Observables.dump=false
|
||||
Observables.dump=true
|
||||
|
||||
;#dump_filename: Log path and filename.
|
||||
Observables.dump_filename=./observables.dat
|
||||
@ -406,16 +385,16 @@ Observables.dump_filename=./observables.dat
|
||||
PVT.implementation=Hybrid_PVT
|
||||
|
||||
;#averaging_depth: Number of PVT observations in the moving average algorithm
|
||||
PVT.averaging_depth=10
|
||||
PVT.averaging_depth=5
|
||||
|
||||
;#flag_average: Enables the PVT averaging between output intervals (arithmetic mean) [true] or [false]
|
||||
PVT.flag_averaging=true
|
||||
PVT.flag_averaging=false
|
||||
|
||||
;#output_rate_ms: Period between two PVT outputs. Notice that the minimum period is equal to the tracking integration time (for GPS CA L1 is 1ms) [ms]
|
||||
PVT.output_rate_ms=100
|
||||
PVT.output_rate_ms=1
|
||||
|
||||
;#display_rate_ms: Position console print (std::out) interval [ms]. Notice that output_rate_ms<=display_rate_ms.
|
||||
PVT.display_rate_ms=500
|
||||
PVT.display_rate_ms=100
|
||||
|
||||
;# KML, GeoJSON, NMEA and RTCM output configuration
|
||||
|
||||
|
@ -409,7 +409,7 @@ bool hybrid_pvt_cc::observables_pairCompare_min(const std::pair<int,Gnss_Synchro
|
||||
void hybrid_pvt_cc::print_receiver_status(Gnss_Synchro** channels_synchronization_data)
|
||||
{
|
||||
// Print the current receiver status using std::cout every second
|
||||
int current_rx_seg = floor(channels_synchronization_data[0][0].Tracking_timestamp_secs);
|
||||
int current_rx_seg = floor((double)channels_synchronization_data[0][0].Tracking_sample_counter/(double)channels_synchronization_data[0][0].fs);
|
||||
if ( current_rx_seg != d_last_status_print_seg)
|
||||
{
|
||||
d_last_status_print_seg = current_rx_seg;
|
||||
@ -456,7 +456,7 @@ int hybrid_pvt_cc::general_work (int noutput_items __attribute__((unused)), gr_v
|
||||
{
|
||||
// store valid observables in a map.
|
||||
gnss_observables_map.insert(std::pair<int,Gnss_Synchro>(i, in[i][0]));
|
||||
d_rx_time = in[i][0].RX_time; // hybrid rx time, all the channels have the same RX timestamp (common RX time pseudoranges, not corrected by delta t)
|
||||
d_rx_time = in[i][0].RX_time;
|
||||
if(d_ls_pvt->gps_ephemeris_map.size() > 0)
|
||||
{
|
||||
std::map<int,Gps_Ephemeris>::iterator tmp_eph_iter = d_ls_pvt->gps_ephemeris_map.find(in[i][0].PRN);
|
||||
@ -528,6 +528,7 @@ int hybrid_pvt_cc::general_work (int noutput_items __attribute__((unused)), gr_v
|
||||
if (pvt_result == true)
|
||||
{
|
||||
// correct the observable to account for the receiver clock offset
|
||||
|
||||
for (std::map<int,Gnss_Synchro>::iterator it = gnss_observables_map.begin(); it != gnss_observables_map.end(); ++it)
|
||||
{
|
||||
it->second.Pseudorange_m = it->second.Pseudorange_m - d_ls_pvt->d_rx_dt_s * GPS_C_m_s;
|
||||
|
@ -72,6 +72,160 @@ hybrid_ls_pvt::~hybrid_ls_pvt()
|
||||
}
|
||||
|
||||
|
||||
gtime_t hybrid_ls_pvt::epoch2time(const double *ep)
|
||||
{
|
||||
const int doy[]={1,32,60,91,121,152,182,213,244,274,305,335};
|
||||
gtime_t time={0};
|
||||
int days,sec,year=(int)ep[0],mon=(int)ep[1],day=(int)ep[2];
|
||||
|
||||
if (year<1970||2099<year||mon<1||12<mon) return time;
|
||||
|
||||
/* leap year if year%4==0 in 1901-2099 */
|
||||
days=(year-1970)*365+(year-1969)/4+doy[mon-1]+day-2+(year%4==0&&mon>=3?1:0);
|
||||
sec=(int)floor(ep[5]);
|
||||
time.time=(time_t)days*86400+(int)ep[3]*3600+(int)ep[4]*60+sec;
|
||||
time.sec=ep[5]-sec;
|
||||
return time;
|
||||
}
|
||||
|
||||
gtime_t hybrid_ls_pvt::gpst2time(int week, double sec)
|
||||
{
|
||||
const static double gpst0[]={1980,1, 6,0,0,0}; /* gps time reference */
|
||||
gtime_t t=epoch2time(gpst0);
|
||||
|
||||
if (sec<-1E9||1E9<sec) sec=0.0;
|
||||
t.time+=86400*7*week+(int)sec;
|
||||
t.sec=sec-(int)sec;
|
||||
return t;
|
||||
}
|
||||
|
||||
void hybrid_ls_pvt::time2str(gtime_t t, char *s, int n)
|
||||
{
|
||||
double ep[6];
|
||||
|
||||
if (n<0) n=0; else if (n>12) n=12;
|
||||
if (1.0-t.sec<0.5/pow(10.0,n)) {t.time++; t.sec=0.0;};
|
||||
time2epoch(t,ep);
|
||||
sprintf(s,"%04.0f/%02.0f/%02.0f %02.0f:%02.0f:%0*.*f",ep[0],ep[1],ep[2],
|
||||
ep[3],ep[4],n<=0?2:n+3,n<=0?0:n,ep[5]);
|
||||
}
|
||||
|
||||
double hybrid_ls_pvt::time2gpst(gtime_t t, int *week)
|
||||
{
|
||||
const static double gpst0[]={1980,1, 6,0,0,0}; /* gps time reference */
|
||||
gtime_t t0=epoch2time(gpst0);
|
||||
time_t sec=t.time-t0.time;
|
||||
int w=(int)(sec/(86400*7));
|
||||
|
||||
if (week) *week=w;
|
||||
return (double)(sec-w*86400*7)+t.sec;
|
||||
}
|
||||
|
||||
void hybrid_ls_pvt::time2epoch(gtime_t t, double *ep)
|
||||
{
|
||||
const int mday[]={ /* # of days in a month */
|
||||
31,28,31,30,31,30,31,31,30,31,30,31,31,28,31,30,31,30,31,31,30,31,30,31,
|
||||
31,29,31,30,31,30,31,31,30,31,30,31,31,28,31,30,31,30,31,31,30,31,30,31
|
||||
};
|
||||
int days,sec,mon,day;
|
||||
|
||||
/* leap year if year%4==0 in 1901-2099 */
|
||||
days=(int)(t.time/86400);
|
||||
sec=(int)(t.time-(time_t)days*86400);
|
||||
for (day=days%1461,mon=0;mon<48;mon++) {
|
||||
if (day>=mday[mon]) day-=mday[mon]; else break;
|
||||
}
|
||||
ep[0]=1970+days/1461*4+mon/12; ep[1]=mon%12+1; ep[2]=day+1;
|
||||
ep[3]=sec/3600; ep[4]=sec%3600/60; ep[5]=sec%60+t.sec;
|
||||
}
|
||||
|
||||
char* hybrid_ls_pvt::time_str(gtime_t t, int n)
|
||||
{
|
||||
static char buff[64];
|
||||
time2str(t,buff,n);
|
||||
return buff;
|
||||
}
|
||||
|
||||
|
||||
/* time difference -------------------------------------------------------------
|
||||
* difference between gtime_t structs
|
||||
* args : gtime_t t1,t2 I gtime_t structs
|
||||
* return : time difference (t1-t2) (s)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
double hybrid_ls_pvt::timediff(gtime_t t1, gtime_t t2)
|
||||
{
|
||||
return difftime(t1.time,t2.time)+t1.sec-t2.sec;
|
||||
}
|
||||
|
||||
/* add time --------------------------------------------------------------------
|
||||
* add time to gtime_t struct
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* double sec I time to add (s)
|
||||
* return : gtime_t struct (t+sec)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t hybrid_ls_pvt::timeadd(gtime_t t, double sec)
|
||||
{
|
||||
double tt;
|
||||
|
||||
t.sec+=sec; tt=floor(t.sec); t.time+=(int)tt; t.sec-=tt;
|
||||
return t;
|
||||
}
|
||||
|
||||
|
||||
gtime_t hybrid_ls_pvt::utc2gpst(gtime_t t)
|
||||
{
|
||||
const int MAXLEAPS=64;
|
||||
static double leaps[MAXLEAPS+1][7]={ /* leap seconds (y,m,d,h,m,s,utc-gpst) */
|
||||
{2017,1,1,0,0,0,-18},
|
||||
{2015,7,1,0,0,0,-17},
|
||||
{2012,7,1,0,0,0,-16},
|
||||
{2009,1,1,0,0,0,-15},
|
||||
{2006,1,1,0,0,0,-14},
|
||||
{1999,1,1,0,0,0,-13},
|
||||
{1997,7,1,0,0,0,-12},
|
||||
{1996,1,1,0,0,0,-11},
|
||||
{1994,7,1,0,0,0,-10},
|
||||
{1993,7,1,0,0,0, -9},
|
||||
{1992,7,1,0,0,0, -8},
|
||||
{1991,1,1,0,0,0, -7},
|
||||
{1990,1,1,0,0,0, -6},
|
||||
{1988,1,1,0,0,0, -5},
|
||||
{1985,7,1,0,0,0, -4},
|
||||
{1983,7,1,0,0,0, -3},
|
||||
{1982,7,1,0,0,0, -2},
|
||||
{1981,7,1,0,0,0, -1},
|
||||
{0}
|
||||
};
|
||||
int i;
|
||||
for (i=0;leaps[i][0]>0;i++) {
|
||||
if (timediff(t,epoch2time(leaps[i]))>=0.0) return timeadd(t,-leaps[i][6]);
|
||||
}
|
||||
return t;
|
||||
}
|
||||
|
||||
gtime_t hybrid_ls_pvt::timeget(void)
|
||||
{
|
||||
static double timeoffset_=0.0; /* time offset (s) */
|
||||
double ep[6]={0};
|
||||
|
||||
struct timeval tv;
|
||||
struct tm *tt;
|
||||
|
||||
if (!gettimeofday(&tv,NULL)&&(tt=gmtime(&tv.tv_sec))) {
|
||||
ep[0]=tt->tm_year+1900; ep[1]=tt->tm_mon+1; ep[2]=tt->tm_mday;
|
||||
ep[3]=tt->tm_hour; ep[4]=tt->tm_min; ep[5]=tt->tm_sec+tv.tv_usec*1E-6;
|
||||
}
|
||||
return timeadd(epoch2time(ep),timeoffset_);
|
||||
}
|
||||
|
||||
int hybrid_ls_pvt::adjgpsweek(int week)
|
||||
{
|
||||
int w;
|
||||
(void)time2gpst(utc2gpst(timeget()),&w);
|
||||
if (w<1560) w=1560; /* use 2009/12/1 if time is earlier than 2009/12/1 */
|
||||
return week+(w-week+512)/1024*1024;
|
||||
}
|
||||
|
||||
bool hybrid_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_observables_map, double Rx_time, bool flag_averaging)
|
||||
{
|
||||
std::map<int,Gnss_Synchro>::iterator gnss_observables_iter;
|
||||
@ -99,6 +253,7 @@ bool hybrid_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_observables_map, dou
|
||||
// ********************************************************************************
|
||||
int valid_obs = 0; //valid observations counter
|
||||
|
||||
|
||||
for(gnss_observables_iter = gnss_observables_map.begin();
|
||||
gnss_observables_iter != gnss_observables_map.end();
|
||||
gnss_observables_iter++)
|
||||
@ -181,8 +336,9 @@ bool hybrid_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_observables_map, dou
|
||||
|
||||
// 3- compute the current ECEF position for this SV using corrected TX time and obtain clock bias including relativistic effect
|
||||
TX_time_corrected_s = Tx_time - SV_clock_bias_s;
|
||||
double dtr = gps_ephemeris_iter->second.satellitePosition(TX_time_corrected_s);
|
||||
//std::cout<<"L1 Tx_time: "<<Tx_time<<" SV_clock_bias_s: "<<SV_clock_bias_s<<" dtr: "<<dtr<<std::endl;
|
||||
//compute satellite position, clock bias + relativistic correction
|
||||
double dts = gps_ephemeris_iter->second.satellitePosition(TX_time_corrected_s);
|
||||
|
||||
//store satellite positions in a matrix
|
||||
satpos.resize(3, valid_obs + 1);
|
||||
satpos(0, valid_obs) = gps_ephemeris_iter->second.d_satpos_X;
|
||||
@ -190,8 +346,14 @@ bool hybrid_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_observables_map, dou
|
||||
satpos(2, valid_obs) = gps_ephemeris_iter->second.d_satpos_Z;
|
||||
|
||||
// 4- fill the observations vector with the corrected pseudoranges
|
||||
// compute code bias: TGD for single frequency
|
||||
// See IS-GPS-200E section 20.3.3.3.3.2
|
||||
double sqrt_Gamma=GPS_L1_FREQ_HZ/GPS_L2_FREQ_HZ;
|
||||
double Gamma=sqrt_Gamma*sqrt_Gamma;
|
||||
double P1_P2=(1.0-Gamma)*(gps_ephemeris_iter->second.d_TGD* GPS_C_m_s);
|
||||
double Code_bias_m= P1_P2/(1.0-Gamma);
|
||||
obs.resize(valid_obs + 1, 1);
|
||||
obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + dtr * GPS_C_m_s - d_rx_dt_s * GPS_C_m_s;
|
||||
obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + dts * GPS_C_m_s-Code_bias_m-d_rx_dt_s * GPS_C_m_s;
|
||||
d_visible_satellites_IDs[valid_obs] = gps_ephemeris_iter->second.i_satellite_PRN;
|
||||
d_visible_satellites_CN0_dB[valid_obs] = gnss_observables_iter->second.CN0_dB_hz;
|
||||
|
||||
@ -203,6 +365,19 @@ bool hybrid_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_observables_map, dou
|
||||
<< " [m] Z=" << gps_ephemeris_iter->second.d_satpos_Z
|
||||
<< " [m] PR_obs=" << obs(valid_obs) << " [m]";
|
||||
|
||||
//*** debug
|
||||
if (valid_obs==0)
|
||||
{
|
||||
gtime_t rx_time=gpst2time(adjgpsweek(gps_ephemeris_iter->second.i_GPS_week),Rx_time);
|
||||
gtime_t tx_time=gpst2time(adjgpsweek(gps_ephemeris_iter->second.i_GPS_week),Tx_time);
|
||||
printf("RINEX RX TIME: %s,%f, TX TIME: %s,%f\n\r",time_str(rx_time,3),rx_time.sec,time_str(tx_time,3),tx_time.sec);
|
||||
}
|
||||
std::flush(std::cout);
|
||||
gtime_t tx_time_corr=gpst2time(adjgpsweek(gps_ephemeris_iter->second.i_GPS_week),TX_time_corrected_s);
|
||||
printf("SAT TX TIME [%i]: %s,%f PR:%f dt:%f\n\r",valid_obs,time_str(tx_time_corr,3),tx_time_corr.sec, obs(valid_obs),dts);
|
||||
std::flush(std::cout);
|
||||
//*** end debug
|
||||
|
||||
valid_obs++;
|
||||
// compute the UTC time for this SV (just to print the associated UTC timestamp)
|
||||
GPS_week = gps_ephemeris_iter->second.i_GPS_week;
|
||||
|
@ -43,11 +43,106 @@
|
||||
#include "gnss_synchro.h"
|
||||
|
||||
|
||||
typedef struct { /* time struct */
|
||||
time_t time; /* time (s) expressed by standard time_t */
|
||||
double sec; /* fraction of second under 1 s */
|
||||
} gtime_t;
|
||||
|
||||
/*!
|
||||
* \brief This class implements a simple PVT Least Squares solution
|
||||
*/
|
||||
class hybrid_ls_pvt : public Ls_Pvt
|
||||
{
|
||||
private:
|
||||
/* convert calendar day/time to time -------------------------------------------
|
||||
* convert calendar day/time to gtime_t struct
|
||||
* args : double *ep I day/time {year,month,day,hour,min,sec}
|
||||
* return : gtime_t struct
|
||||
* notes : proper in 1970-2037 or 1970-2099 (64bit time_t)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t epoch2time(const double *ep);
|
||||
|
||||
/* gps time to time ------------------------------------------------------------
|
||||
* convert week and tow in gps time to gtime_t struct
|
||||
* args : int week I week number in gps time
|
||||
* double sec I time of week in gps time (s)
|
||||
* return : gtime_t struct
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t gpst2time(int week, double sec);
|
||||
|
||||
/* get time string -------------------------------------------------------------
|
||||
* get time string
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* int n I number of decimals
|
||||
* return : time string
|
||||
* notes : not reentrant, do not use multiple in a function
|
||||
*-----------------------------------------------------------------------------*/
|
||||
char *time_str(gtime_t t, int n);
|
||||
|
||||
/* time to string --------------------------------------------------------------
|
||||
* convert gtime_t struct to string
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* char *s O string ("yyyy/mm/dd hh:mm:ss.ssss")
|
||||
* int n I number of decimals
|
||||
* return : none
|
||||
*-----------------------------------------------------------------------------*/
|
||||
void time2str(gtime_t t, char *s, int n);
|
||||
|
||||
/* time to calendar day/time ---------------------------------------------------
|
||||
* convert gtime_t struct to calendar day/time
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* double *ep O day/time {year,month,day,hour,min,sec}
|
||||
* return : none
|
||||
* notes : proper in 1970-2037 or 1970-2099 (64bit time_t)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
void time2epoch(gtime_t t, double *ep);
|
||||
|
||||
/* adjust gps week number ------------------------------------------------------
|
||||
* adjust gps week number using cpu time
|
||||
* args : int week I not-adjusted gps week number
|
||||
* return : adjusted gps week number
|
||||
*-----------------------------------------------------------------------------*/
|
||||
int adjgpsweek(int week);
|
||||
|
||||
/* time to gps time ------------------------------------------------------------
|
||||
* convert gtime_t struct to week and tow in gps time
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* int *week IO week number in gps time (NULL: no output)
|
||||
* return : time of week in gps time (s)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
double time2gpst(gtime_t t, int *week);
|
||||
|
||||
/* utc to gpstime --------------------------------------------------------------
|
||||
* convert utc to gpstime considering leap seconds
|
||||
* args : gtime_t t I time expressed in utc
|
||||
* return : time expressed in gpstime
|
||||
* notes : ignore slight time offset under 100 ns
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t utc2gpst(gtime_t t);
|
||||
|
||||
/* time difference -------------------------------------------------------------
|
||||
* difference between gtime_t structs
|
||||
* args : gtime_t t1,t2 I gtime_t structs
|
||||
* return : time difference (t1-t2) (s)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
double timediff(gtime_t t1, gtime_t t2);
|
||||
|
||||
/* add time --------------------------------------------------------------------
|
||||
* add time to gtime_t struct
|
||||
* args : gtime_t t I gtime_t struct
|
||||
* double sec I time to add (s)
|
||||
* return : gtime_t struct (t+sec)
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t timeadd(gtime_t t, double sec);
|
||||
|
||||
/* get current time in utc -----------------------------------------------------
|
||||
* get current time in utc
|
||||
* args : none
|
||||
* return : current time in utc
|
||||
*-----------------------------------------------------------------------------*/
|
||||
gtime_t timeget();
|
||||
|
||||
|
||||
public:
|
||||
hybrid_ls_pvt(int nchannels,std::string dump_filename, bool flag_dump_to_file);
|
||||
~hybrid_ls_pvt();
|
||||
|
@ -162,6 +162,7 @@ void pcps_acquisition_cc::set_local_code(std::complex<float> * code)
|
||||
// Here we want to create a buffer that looks like this:
|
||||
// [ 0 0 0 ... 0 c_0 c_1 ... c_L]
|
||||
// where c_i is the local code and there are L zeros and L chips
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
if( d_bit_transition_flag )
|
||||
{
|
||||
int offset = d_fft_size/2;
|
||||
@ -216,6 +217,7 @@ void pcps_acquisition_cc::init()
|
||||
|
||||
void pcps_acquisition_cc::set_state(int state)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_state = state;
|
||||
if (d_state == 1)
|
||||
{
|
||||
@ -236,6 +238,42 @@ void pcps_acquisition_cc::set_state(int state)
|
||||
}
|
||||
|
||||
|
||||
void pcps_acquisition_cc::send_positive_acquisition()
|
||||
{
|
||||
// 6.1- Declare positive acquisition using a message port
|
||||
//0=STOP_CHANNEL 1=ACQ_SUCCEES 2=ACQ_FAIL
|
||||
DLOG(INFO) << "positive acquisition"
|
||||
<< "satellite " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN
|
||||
<< "sample_stamp " << d_sample_counter
|
||||
<< "test statistics value " << d_test_statistics
|
||||
<< "test statistics threshold " << d_threshold
|
||||
<< "code phase " << d_gnss_synchro->Acq_delay_samples
|
||||
<< "doppler " << d_gnss_synchro->Acq_doppler_hz
|
||||
<< "magnitude " << d_mag
|
||||
<< "input signal power " << d_input_power;
|
||||
|
||||
this->message_port_pub(pmt::mp("events"), pmt::from_long(1));
|
||||
|
||||
}
|
||||
|
||||
void pcps_acquisition_cc::send_negative_acquisition()
|
||||
{
|
||||
// 6.2- Declare negative acquisition using a message port
|
||||
//0=STOP_CHANNEL 1=ACQ_SUCCEES 2=ACQ_FAIL
|
||||
DLOG(INFO) << "negative acquisition"
|
||||
<< "satellite " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN
|
||||
<< "sample_stamp " << d_sample_counter
|
||||
<< "test statistics value " << d_test_statistics
|
||||
<< "test statistics threshold " << d_threshold
|
||||
<< "code phase " << d_gnss_synchro->Acq_delay_samples
|
||||
<< "doppler " << d_gnss_synchro->Acq_doppler_hz
|
||||
<< "magnitude " << d_mag
|
||||
<< "input signal power " << d_input_power;
|
||||
|
||||
this->message_port_pub(pmt::mp("events"), pmt::from_long(2));
|
||||
|
||||
}
|
||||
|
||||
int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
gr_vector_int &ninput_items, gr_vector_const_void_star &input_items,
|
||||
gr_vector_void_star &output_items __attribute__((unused)))
|
||||
@ -251,8 +289,6 @@ int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
* 6. Declare positive or negative acquisition using a message port
|
||||
*/
|
||||
|
||||
int acquisition_message = -1; //0=STOP_CHANNEL 1=ACQ_SUCCEES 2=ACQ_FAIL
|
||||
|
||||
switch (d_state)
|
||||
{
|
||||
case 0:
|
||||
@ -267,15 +303,12 @@ int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
d_mag = 0.0;
|
||||
d_input_power = 0.0;
|
||||
d_test_statistics = 0.0;
|
||||
|
||||
d_state = 1;
|
||||
}
|
||||
|
||||
d_sample_counter += d_fft_size * ninput_items[0]; // sample counter
|
||||
consume_each(ninput_items[0]);
|
||||
|
||||
//DLOG(INFO) << "Consumed " << ninput_items[0] << " items";
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
@ -293,16 +326,14 @@ int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
|
||||
d_input_power = 0.0;
|
||||
d_mag = 0.0;
|
||||
|
||||
d_sample_counter += d_fft_size; // sample counter
|
||||
|
||||
d_well_count++;
|
||||
|
||||
DLOG(INFO) << "Channel: " << d_channel
|
||||
DLOG(INFO)<< "Channel: " << d_channel
|
||||
<< " , doing acquisition of satellite: " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN
|
||||
<< " ,sample stamp: " << d_sample_counter << ", threshold: "
|
||||
<< d_threshold << ", doppler_max: " << d_doppler_max
|
||||
<< ", doppler_step: " << d_doppler_step;
|
||||
<< ", doppler_step: " << d_doppler_step<<std::endl;
|
||||
|
||||
if (d_use_CFAR_algorithm_flag == true)
|
||||
{
|
||||
@ -404,11 +435,15 @@ int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
{
|
||||
if (d_test_statistics > d_threshold)
|
||||
{
|
||||
d_state = 2; // Positive acquisition
|
||||
d_state = 0; // Positive acquisition
|
||||
d_active = false;
|
||||
send_positive_acquisition();
|
||||
}
|
||||
else if (d_well_count == d_max_dwells)
|
||||
{
|
||||
d_state = 3; // Negative acquisition
|
||||
d_state = 0;
|
||||
d_active = false;
|
||||
send_negative_acquisition();
|
||||
}
|
||||
}
|
||||
else
|
||||
@ -417,69 +452,23 @@ int pcps_acquisition_cc::general_work(int noutput_items,
|
||||
{
|
||||
if (d_test_statistics > d_threshold)
|
||||
{
|
||||
d_state = 2; // Positive acquisition
|
||||
d_state = 0; // Positive acquisition
|
||||
d_active = false;
|
||||
send_positive_acquisition();
|
||||
}
|
||||
else
|
||||
{
|
||||
d_state = 3; // Negative acquisition
|
||||
d_state = 0; // Negative acquisition
|
||||
d_active = false;
|
||||
send_negative_acquisition();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
consume_each(1);
|
||||
|
||||
DLOG(INFO) << "Done. Consumed 1 item.";
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case 2:
|
||||
{
|
||||
// 6.1- Declare positive acquisition using a message port
|
||||
DLOG(INFO) << "positive acquisition";
|
||||
DLOG(INFO) << "satellite " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN;
|
||||
DLOG(INFO) << "sample_stamp " << d_sample_counter;
|
||||
DLOG(INFO) << "test statistics value " << d_test_statistics;
|
||||
DLOG(INFO) << "test statistics threshold " << d_threshold;
|
||||
DLOG(INFO) << "code phase " << d_gnss_synchro->Acq_delay_samples;
|
||||
DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz;
|
||||
DLOG(INFO) << "magnitude " << d_mag;
|
||||
DLOG(INFO) << "input signal power " << d_input_power;
|
||||
|
||||
d_active = false;
|
||||
d_state = 0;
|
||||
d_sample_counter += d_fft_size * ninput_items[0]; // sample counter
|
||||
consume_each(ninput_items[0]);
|
||||
|
||||
acquisition_message = 1;
|
||||
this->message_port_pub(pmt::mp("events"), pmt::from_long(acquisition_message));
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case 3:
|
||||
{
|
||||
// 6.2- Declare negative acquisition using a message port
|
||||
DLOG(INFO) << "negative acquisition";
|
||||
DLOG(INFO) << "satellite " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN;
|
||||
DLOG(INFO) << "sample_stamp " << d_sample_counter;
|
||||
DLOG(INFO) << "test statistics value " << d_test_statistics;
|
||||
DLOG(INFO) << "test statistics threshold " << d_threshold;
|
||||
DLOG(INFO) << "code phase " << d_gnss_synchro->Acq_delay_samples;
|
||||
DLOG(INFO) << "doppler " << d_gnss_synchro->Acq_doppler_hz;
|
||||
DLOG(INFO) << "magnitude " << d_mag;
|
||||
DLOG(INFO) << "input signal power " << d_input_power;
|
||||
|
||||
d_active = false;
|
||||
d_state = 0;
|
||||
|
||||
d_sample_counter += d_fft_size * ninput_items[0]; // sample counter
|
||||
consume_each(ninput_items[0]);
|
||||
acquisition_message = 2;
|
||||
this->message_port_pub(pmt::mp("events"), pmt::from_long(acquisition_message));
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return noutput_items;
|
||||
|
@ -95,6 +95,8 @@ private:
|
||||
|
||||
void update_local_carrier(gr_complex* carrier_vector, int correlator_length_samples, float freq);
|
||||
|
||||
void send_negative_acquisition();
|
||||
void send_positive_acquisition();
|
||||
long d_fs_in;
|
||||
long d_freq;
|
||||
int d_samples_per_ms;
|
||||
@ -143,6 +145,7 @@ public:
|
||||
*/
|
||||
void set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_gnss_synchro = p_gnss_synchro;
|
||||
}
|
||||
|
||||
@ -172,6 +175,7 @@ public:
|
||||
*/
|
||||
void set_active(bool active)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_active = active;
|
||||
}
|
||||
|
||||
@ -188,6 +192,7 @@ public:
|
||||
*/
|
||||
void set_channel(unsigned int channel)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_channel = channel;
|
||||
}
|
||||
|
||||
@ -198,6 +203,7 @@ public:
|
||||
*/
|
||||
void set_threshold(float threshold)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_threshold = threshold;
|
||||
}
|
||||
|
||||
@ -207,6 +213,7 @@ public:
|
||||
*/
|
||||
void set_doppler_max(unsigned int doppler_max)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_doppler_max = doppler_max;
|
||||
}
|
||||
|
||||
@ -216,6 +223,7 @@ public:
|
||||
*/
|
||||
void set_doppler_step(unsigned int doppler_step)
|
||||
{
|
||||
gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
|
||||
d_doppler_step = doppler_step;
|
||||
}
|
||||
|
||||
|
@ -59,7 +59,7 @@ HybridObservables::HybridObservables(ConfigurationInterface* configuration,
|
||||
{
|
||||
default_depth = 100;
|
||||
}
|
||||
unsigned int history_deep = configuration->property(role + ".averaging_depth", default_depth);
|
||||
unsigned int history_deep = configuration->property(role + ".history_depth", default_depth);
|
||||
observables_ = hybrid_make_observables_cc(in_streams_, dump_, dump_filename_, history_deep);
|
||||
DLOG(INFO) << "pseudorange(" << observables_->unique_id() << ")";
|
||||
}
|
||||
|
@ -100,14 +100,7 @@ hybrid_observables_cc::~hybrid_observables_cc()
|
||||
|
||||
bool Hybrid_pairCompare_gnss_synchro_d_TOW_at_current_symbol(const std::pair<int,Gnss_Synchro>& a, const std::pair<int,Gnss_Synchro>& b)
|
||||
{
|
||||
if (a.second.d_TOW_at_current_symbol==b.second.d_TOW_at_current_symbol)
|
||||
{
|
||||
return (a.second.Prn_timestamp_ms/1000.0) > (b.second.Prn_timestamp_ms/1000.0);
|
||||
|
||||
}else{
|
||||
return (a.second.d_TOW_at_current_symbol) < (b.second.d_TOW_at_current_symbol);
|
||||
}
|
||||
|
||||
return (a.second.TOW_at_current_symbol_s) < (b.second.TOW_at_current_symbol_s);
|
||||
}
|
||||
|
||||
|
||||
@ -148,7 +141,7 @@ int hybrid_observables_cc::general_work (int noutput_items,
|
||||
d_carrier_doppler_queue_hz[i].push_back(current_gnss_synchro[i].Carrier_Doppler_hz);
|
||||
d_acc_carrier_phase_queue_rads[i].push_back(current_gnss_synchro[i].Carrier_phase_rads);
|
||||
// save TOW history
|
||||
d_symbol_TOW_queue_s[i].push_back(current_gnss_synchro[i].d_TOW_at_current_symbol);
|
||||
d_symbol_TOW_queue_s[i].push_back(current_gnss_synchro[i].TOW_at_current_symbol_s);
|
||||
if (d_carrier_doppler_queue_hz[i].size() > history_deep)
|
||||
{
|
||||
d_carrier_doppler_queue_hz[i].pop_front();
|
||||
@ -185,22 +178,27 @@ int hybrid_observables_cc::general_work (int noutput_items,
|
||||
*/
|
||||
// what is the most recent symbol TOW in the current set? -> this will be the reference symbol
|
||||
gnss_synchro_iter = max_element(current_gnss_synchro_map.begin(), current_gnss_synchro_map.end(), Hybrid_pairCompare_gnss_synchro_d_TOW_at_current_symbol);
|
||||
double d_TOW_reference = gnss_synchro_iter->second.d_TOW_at_current_symbol;
|
||||
double d_TOW_reference = gnss_synchro_iter->second.TOW_at_current_symbol_s;
|
||||
double d_ref_PRN_phase_samples = gnss_synchro_iter->second.Code_phase_samples;
|
||||
//std::cout<<"OBS SV REF SAT: "<<gnss_synchro_iter->second.PRN<<std::endl;
|
||||
double d_ref_PRN_rx_time_ms = gnss_synchro_iter->second.Prn_timestamp_ms;
|
||||
unsigned long int d_ref_PRN_sample_counter = gnss_synchro_iter->second.Tracking_sample_counter;
|
||||
|
||||
// Now compute RX time differences due to the PRN alignment in the correlators
|
||||
double traveltime_ms;
|
||||
double pseudorange_m;
|
||||
double delta_rx_time_ms;
|
||||
int delta_sample_counter;
|
||||
double delta_sample_counter_s;
|
||||
double delta_PRN_phase_s;
|
||||
|
||||
for(gnss_synchro_iter = current_gnss_synchro_map.begin(); gnss_synchro_iter != current_gnss_synchro_map.end(); gnss_synchro_iter++)
|
||||
{
|
||||
|
||||
delta_rx_time_ms = gnss_synchro_iter->second.Prn_timestamp_ms - d_ref_PRN_rx_time_ms;
|
||||
delta_sample_counter = (gnss_synchro_iter->second.Tracking_sample_counter - d_ref_PRN_sample_counter);
|
||||
delta_sample_counter_s=(double)delta_sample_counter/(double)gnss_synchro_iter->second.fs;
|
||||
delta_PRN_phase_s = (gnss_synchro_iter->second.Code_phase_samples - d_ref_PRN_phase_samples)/(double)gnss_synchro_iter->second.fs;
|
||||
//compute the pseudorange (no rx time offset correction)
|
||||
traveltime_ms = (d_TOW_reference - gnss_synchro_iter->second.d_TOW_at_current_symbol) * 1000.0
|
||||
+ delta_rx_time_ms
|
||||
traveltime_ms = (d_TOW_reference - gnss_synchro_iter->second.TOW_at_current_symbol_s) * 1000.0
|
||||
+ delta_sample_counter_s*1000.0 + delta_PRN_phase_s*1000.0
|
||||
+ GPS_STARTOFFSET_ms;
|
||||
//convert to meters
|
||||
pseudorange_m = traveltime_ms * GPS_C_m_ms; // [m]
|
||||
@ -228,7 +226,7 @@ int hybrid_observables_cc::general_work (int noutput_items,
|
||||
acc_phase_vec_rads = arma::vec(std::vector<double>(d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].begin(), d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
dopper_vec_hz = arma::vec(std::vector<double>(d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].begin(), d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
|
||||
desired_symbol_TOW[0] = symbol_TOW_vec_s[history_deep - 1] + delta_rx_time_ms / 1000.0;
|
||||
desired_symbol_TOW[0] = symbol_TOW_vec_s[history_deep - 1] + delta_sample_counter_s+delta_PRN_phase_s;
|
||||
// arma::interp1(symbol_TOW_vec_s,dopper_vec_hz,desired_symbol_TOW,dopper_vec_interp_hz);
|
||||
// arma::interp1(symbol_TOW_vec_s,acc_phase_vec_rads,desired_symbol_TOW,acc_phase_vec_interp_rads);
|
||||
// Curve fitting to quadratic function
|
||||
@ -260,7 +258,7 @@ int hybrid_observables_cc::general_work (int noutput_items,
|
||||
{
|
||||
tmp_double = current_gnss_synchro[i].RX_time;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].d_TOW_at_current_symbol;
|
||||
tmp_double = current_gnss_synchro[i].TOW_at_current_symbol_s;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Carrier_Doppler_hz;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
|
@ -0,0 +1,289 @@
|
||||
/*!
|
||||
* \file hybrid_observables_cc.cc
|
||||
* \brief Implementation of the pseudorange computation block for Galileo E1
|
||||
* \author Mara Branzanti 2013. mara.branzanti(at)gmail.com
|
||||
* \author Javier Arribas 2013. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2015 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#include "hybrid_observables_cc.h"
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <utility>
|
||||
#include <armadillo>
|
||||
#include <gnuradio/io_signature.h>
|
||||
#include <glog/logging.h>
|
||||
#include "gnss_synchro.h"
|
||||
#include "Galileo_E1.h"
|
||||
#include "GPS_L1_CA.h"
|
||||
|
||||
|
||||
|
||||
using google::LogMessage;
|
||||
|
||||
|
||||
hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history)
|
||||
{
|
||||
return hybrid_observables_cc_sptr(new hybrid_observables_cc(nchannels, dump, dump_filename, deep_history));
|
||||
}
|
||||
|
||||
|
||||
hybrid_observables_cc::hybrid_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history) :
|
||||
gr::block("hybrid_observables_cc", gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)),
|
||||
gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)))
|
||||
{
|
||||
// initialize internal vars
|
||||
d_dump = dump;
|
||||
d_nchannels = nchannels;
|
||||
d_dump_filename = dump_filename;
|
||||
history_deep = deep_history;
|
||||
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
d_acc_carrier_phase_queue_rads.push_back(std::deque<double>(d_nchannels));
|
||||
d_carrier_doppler_queue_hz.push_back(std::deque<double>(d_nchannels));
|
||||
d_symbol_TOW_queue_s.push_back(std::deque<double>(d_nchannels));
|
||||
}
|
||||
|
||||
// ############# ENABLE DATA FILE LOG #################
|
||||
if (d_dump == true)
|
||||
{
|
||||
if (d_dump_file.is_open() == false)
|
||||
{
|
||||
try
|
||||
{
|
||||
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit );
|
||||
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
|
||||
LOG(INFO) << "Observables dump enabled Log file: " << d_dump_filename.c_str();
|
||||
}
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
LOG(WARNING) << "Exception opening observables dump file " << e.what();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
hybrid_observables_cc::~hybrid_observables_cc()
|
||||
{
|
||||
d_dump_file.close();
|
||||
}
|
||||
|
||||
|
||||
bool Hybrid_pairCompare_gnss_synchro_d_TOW_at_current_symbol(const std::pair<int,Gnss_Synchro>& a, const std::pair<int,Gnss_Synchro>& b)
|
||||
{
|
||||
return (a.second.TOW_at_current_symbol_s) < (b.second.TOW_at_current_symbol_s);
|
||||
}
|
||||
|
||||
|
||||
int hybrid_observables_cc::general_work (int noutput_items,
|
||||
gr_vector_int &ninput_items,
|
||||
gr_vector_const_void_star &input_items,
|
||||
gr_vector_void_star &output_items)
|
||||
{
|
||||
Gnss_Synchro **in = (Gnss_Synchro **) &input_items[0]; // Get the input pointer
|
||||
Gnss_Synchro **out = (Gnss_Synchro **) &output_items[0]; // Get the output pointer
|
||||
|
||||
Gnss_Synchro current_gnss_synchro[d_nchannels];
|
||||
std::map<int,Gnss_Synchro> current_gnss_synchro_map;
|
||||
std::map<int,Gnss_Synchro>::iterator gnss_synchro_iter;
|
||||
|
||||
if (d_nchannels != ninput_items.size())
|
||||
{
|
||||
LOG(WARNING) << "The Observables block is not well connected";
|
||||
}
|
||||
|
||||
/*
|
||||
* 1. Read the GNSS SYNCHRO objects from available channels
|
||||
*/
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
//Copy the telemetry decoder data to local copy
|
||||
current_gnss_synchro[i] = in[i][0];
|
||||
/*
|
||||
* 1.2 Assume no valid pseudoranges
|
||||
*/
|
||||
current_gnss_synchro[i].Flag_valid_pseudorange = false;
|
||||
current_gnss_synchro[i].Pseudorange_m = 0.0;
|
||||
if (current_gnss_synchro[i].Flag_valid_word)
|
||||
{
|
||||
//record the word structure in a map for pseudorange computation
|
||||
current_gnss_synchro_map.insert(std::pair<int, Gnss_Synchro>(current_gnss_synchro[i].Channel_ID, current_gnss_synchro[i]));
|
||||
//################### SAVE DOPPLER AND ACC CARRIER PHASE HISTORIC DATA FOR INTERPOLATION IN OBSERVABLE MODULE #######
|
||||
d_carrier_doppler_queue_hz[i].push_back(current_gnss_synchro[i].Carrier_Doppler_hz);
|
||||
d_acc_carrier_phase_queue_rads[i].push_back(current_gnss_synchro[i].Carrier_phase_rads);
|
||||
// save TOW history
|
||||
d_symbol_TOW_queue_s[i].push_back(current_gnss_synchro[i].TOW_at_current_symbol_s);
|
||||
if (d_carrier_doppler_queue_hz[i].size() > history_deep)
|
||||
{
|
||||
d_carrier_doppler_queue_hz[i].pop_front();
|
||||
}
|
||||
if (d_acc_carrier_phase_queue_rads[i].size() > history_deep)
|
||||
{
|
||||
d_acc_carrier_phase_queue_rads[i].pop_front();
|
||||
}
|
||||
if (d_symbol_TOW_queue_s[i].size() > history_deep)
|
||||
{
|
||||
d_symbol_TOW_queue_s[i].pop_front();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Clear the observables history for this channel
|
||||
if (d_symbol_TOW_queue_s[i].size() > 0)
|
||||
{
|
||||
d_symbol_TOW_queue_s[i].clear();
|
||||
d_carrier_doppler_queue_hz[i].clear();
|
||||
d_acc_carrier_phase_queue_rads[i].clear();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* 2. Compute RAW pseudoranges using COMMON RECEPTION TIME algorithm. Use only the valid channels (channels that are tracking a satellite)
|
||||
*/
|
||||
if(current_gnss_synchro_map.size() > 0)
|
||||
{
|
||||
/*
|
||||
* 2.1 Use CURRENT set of measurements and find the nearest satellite
|
||||
* common RX time algorithm
|
||||
*/
|
||||
// what is the most recent symbol TOW in the current set? -> this will be the reference symbol
|
||||
gnss_synchro_iter = max_element(current_gnss_synchro_map.begin(), current_gnss_synchro_map.end(), Hybrid_pairCompare_gnss_synchro_d_TOW_at_current_symbol);
|
||||
double d_TOW_reference = gnss_synchro_iter->second.TOW_at_current_symbol_s;
|
||||
double d_ref_PRN_phase_samples = gnss_synchro_iter->second.Code_phase_samples;
|
||||
//std::cout<<"OBS SV REF SAT: "<<gnss_synchro_iter->second.PRN<<std::endl;
|
||||
unsigned long int d_ref_PRN_sample_counter = gnss_synchro_iter->second.Tracking_sample_counter;
|
||||
|
||||
// Now compute RX time differences due to the PRN alignment in the correlators
|
||||
double traveltime_ms;
|
||||
double pseudorange_m;
|
||||
int delta_sample_counter;
|
||||
double delta_sample_counter_s;
|
||||
double delta_PRN_phase_s;
|
||||
|
||||
for(gnss_synchro_iter = current_gnss_synchro_map.begin(); gnss_synchro_iter != current_gnss_synchro_map.end(); gnss_synchro_iter++)
|
||||
{
|
||||
|
||||
delta_sample_counter = (gnss_synchro_iter->second.Tracking_sample_counter - d_ref_PRN_sample_counter);
|
||||
delta_sample_counter_s=(double)delta_sample_counter/(double)gnss_synchro_iter->second.fs;
|
||||
delta_PRN_phase_s = (gnss_synchro_iter->second.Code_phase_samples - d_ref_PRN_phase_samples)/(double)gnss_synchro_iter->second.fs;
|
||||
//compute the pseudorange (no rx time offset correction)
|
||||
traveltime_ms = (d_TOW_reference - gnss_synchro_iter->second.TOW_at_current_symbol_s) * 1000.0
|
||||
+ delta_sample_counter_s*1000.0 + delta_PRN_phase_s*1000.0
|
||||
+ GPS_STARTOFFSET_ms;
|
||||
//convert to meters
|
||||
pseudorange_m = traveltime_ms * GPS_C_m_ms; // [m]
|
||||
//std::cout<<"["<<gnss_synchro_iter->second.PRN<<"] delta_rx_t: "<<delta_rx_time_ms
|
||||
// <<" [ms] delta_TOW_ms: "<<(d_TOW_reference - gnss_synchro_iter->second.d_TOW_at_current_symbol) * 1000.0
|
||||
// <<" Pr: "<<pseudorange_m<<" [m]"
|
||||
// <<std::endl;
|
||||
// update the pseudorange object
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID] = gnss_synchro_iter->second;
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID].Pseudorange_m = pseudorange_m;
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID].Flag_valid_pseudorange = true;
|
||||
// Save the estimated RX time (no RX clock offset correction yet!)
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID].RX_time = d_TOW_reference + GPS_STARTOFFSET_ms / 1000.0;
|
||||
|
||||
if (d_symbol_TOW_queue_s[gnss_synchro_iter->second.Channel_ID].size() >= history_deep)
|
||||
{
|
||||
arma::vec symbol_TOW_vec_s;
|
||||
arma::vec dopper_vec_hz;
|
||||
arma::vec dopper_vec_interp_hz;
|
||||
arma::vec acc_phase_vec_rads;
|
||||
arma::vec acc_phase_vec_interp_rads;
|
||||
arma::vec desired_symbol_TOW(1);
|
||||
// compute interpolated observation values for Doppler and Accumulate carrier phase
|
||||
symbol_TOW_vec_s = arma::vec(std::vector<double>(d_symbol_TOW_queue_s[gnss_synchro_iter->second.Channel_ID].begin(), d_symbol_TOW_queue_s[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
acc_phase_vec_rads = arma::vec(std::vector<double>(d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].begin(), d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
dopper_vec_hz = arma::vec(std::vector<double>(d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].begin(), d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
|
||||
desired_symbol_TOW[0] = symbol_TOW_vec_s[history_deep - 1] + delta_sample_counter_s+delta_PRN_phase_s;
|
||||
// arma::interp1(symbol_TOW_vec_s,dopper_vec_hz,desired_symbol_TOW,dopper_vec_interp_hz);
|
||||
// arma::interp1(symbol_TOW_vec_s,acc_phase_vec_rads,desired_symbol_TOW,acc_phase_vec_interp_rads);
|
||||
// Curve fitting to quadratic function
|
||||
arma::mat A = arma::ones<arma::mat> (history_deep, 2);
|
||||
A.col(1) = symbol_TOW_vec_s;
|
||||
|
||||
arma::mat coef_acc_phase(1,3);
|
||||
arma::mat pinv_A = arma::pinv(A.t() * A) * A.t();
|
||||
coef_acc_phase = pinv_A * acc_phase_vec_rads;
|
||||
arma::mat coef_doppler(1,3);
|
||||
coef_doppler = pinv_A * dopper_vec_hz;
|
||||
arma::vec acc_phase_lin;
|
||||
arma::vec carrier_doppler_lin;
|
||||
acc_phase_lin = coef_acc_phase[0] + coef_acc_phase[1] * desired_symbol_TOW[0];
|
||||
carrier_doppler_lin = coef_doppler[0] + coef_doppler[1] * desired_symbol_TOW[0];
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID].Carrier_phase_rads = acc_phase_lin[0];
|
||||
current_gnss_synchro[gnss_synchro_iter->second.Channel_ID].Carrier_Doppler_hz = carrier_doppler_lin[0];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if(d_dump == true)
|
||||
{
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
tmp_double = current_gnss_synchro[i].RX_time;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].TOW_at_current_symbol_s;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Carrier_Doppler_hz;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Carrier_phase_rads/GPS_TWO_PI;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Pseudorange_m;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].PRN;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
}
|
||||
catch (const std::ifstream::failure& e)
|
||||
{
|
||||
LOG(WARNING) << "Exception writing observables dump file " << e.what();
|
||||
}
|
||||
}
|
||||
|
||||
consume_each(1); //one by one
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
*out[i] = current_gnss_synchro[i];
|
||||
}
|
||||
if (noutput_items == 0)
|
||||
{
|
||||
LOG(WARNING) << "noutput_items = 0";
|
||||
}
|
||||
return 1;
|
||||
}
|
@ -0,0 +1,76 @@
|
||||
/*!
|
||||
* \file hybrid_observables_cc.h
|
||||
* \brief Interface of the observables computation block for Galileo E1
|
||||
* \author Mara Branzanti 2013. mara.branzanti(at)gmail.com
|
||||
* \author Javier Arribas 2013. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2015 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
|
||||
#ifndef GNSS_SDR_HYBRID_OBSERVABLES_CC_H
|
||||
#define GNSS_SDR_HYBRID_OBSERVABLES_CC_H
|
||||
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <gnuradio/block.h>
|
||||
|
||||
|
||||
class hybrid_observables_cc;
|
||||
|
||||
typedef boost::shared_ptr<hybrid_observables_cc> hybrid_observables_cc_sptr;
|
||||
|
||||
hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int n_channels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
|
||||
/*!
|
||||
* \brief This class implements a block that computes Galileo observables
|
||||
*/
|
||||
class hybrid_observables_cc : public gr::block
|
||||
{
|
||||
public:
|
||||
~hybrid_observables_cc ();
|
||||
int general_work (int noutput_items, gr_vector_int &ninput_items,
|
||||
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
|
||||
|
||||
private:
|
||||
friend hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
hybrid_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
|
||||
//Tracking observable history
|
||||
std::vector<std::deque<double>> d_acc_carrier_phase_queue_rads;
|
||||
std::vector<std::deque<double>> d_carrier_doppler_queue_hz;
|
||||
std::vector<std::deque<double>> d_symbol_TOW_queue_s;
|
||||
|
||||
// class private vars
|
||||
bool d_dump;
|
||||
unsigned int d_nchannels;
|
||||
unsigned int history_deep;
|
||||
std::string d_dump_filename;
|
||||
std::ofstream d_dump_file;
|
||||
};
|
||||
|
||||
#endif
|
@ -0,0 +1,365 @@
|
||||
/*!
|
||||
* \file hybrid_observables_cc.cc
|
||||
* \brief Implementation of the pseudorange computation block for Galileo E1
|
||||
* \author Mara Branzanti 2013. mara.branzanti(at)gmail.com
|
||||
* \author Javier Arribas 2013. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2015 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#include "hybrid_observables_cc.h"
|
||||
#include <algorithm>
|
||||
#include <cmath>
|
||||
#include <iostream>
|
||||
#include <map>
|
||||
#include <vector>
|
||||
#include <utility>
|
||||
#include <armadillo>
|
||||
#include <gnuradio/io_signature.h>
|
||||
#include <glog/logging.h>
|
||||
#include "Galileo_E1.h"
|
||||
#include "GPS_L1_CA.h"
|
||||
|
||||
|
||||
|
||||
using google::LogMessage;
|
||||
|
||||
|
||||
hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history)
|
||||
{
|
||||
return hybrid_observables_cc_sptr(new hybrid_observables_cc(nchannels, dump, dump_filename, deep_history));
|
||||
}
|
||||
|
||||
|
||||
hybrid_observables_cc::hybrid_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history) :
|
||||
gr::block("hybrid_observables_cc", gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)),
|
||||
gr::io_signature::make(nchannels, nchannels, sizeof(Gnss_Synchro)))
|
||||
{
|
||||
// initialize internal vars
|
||||
d_dump = dump;
|
||||
d_nchannels = nchannels;
|
||||
d_dump_filename = dump_filename;
|
||||
history_deep = deep_history;
|
||||
d_last_ref_TOW=0;
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
d_gnss_synchro_history_queue.push_back(std::deque<Gnss_Synchro>());
|
||||
}
|
||||
|
||||
// ############# ENABLE DATA FILE LOG #################
|
||||
if (d_dump == true)
|
||||
{
|
||||
if (d_dump_file.is_open() == false)
|
||||
{
|
||||
try
|
||||
{
|
||||
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit );
|
||||
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
|
||||
LOG(INFO) << "Observables dump enabled Log file: " << d_dump_filename.c_str();
|
||||
}
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
LOG(WARNING) << "Exception opening observables dump file " << e.what();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
hybrid_observables_cc::~hybrid_observables_cc()
|
||||
{
|
||||
d_dump_file.close();
|
||||
}
|
||||
|
||||
|
||||
bool Hybrid_pairCompare_gnss_synchro_sample_counter(const std::pair<int,Gnss_Synchro>& a, const std::pair<int,Gnss_Synchro>& b)
|
||||
{
|
||||
return (a.second.Tracking_sample_counter) < (b.second.Tracking_sample_counter);
|
||||
}
|
||||
|
||||
bool Hybrid_pairCompare_gnss_synchro_d_TOW(const std::pair<int,Gnss_Synchro>& a, const std::pair<int,Gnss_Synchro>& b)
|
||||
{
|
||||
return (a.second.TOW_at_current_symbol_s) < (b.second.TOW_at_current_symbol_s);
|
||||
}
|
||||
bool Hybrid_valueCompare_gnss_synchro_d_TOW(const Gnss_Synchro& a, double b)
|
||||
{
|
||||
return (a.TOW_at_current_symbol_s) < (b);
|
||||
}
|
||||
|
||||
int hybrid_observables_cc::general_work (int noutput_items,
|
||||
gr_vector_int &ninput_items,
|
||||
gr_vector_const_void_star &input_items,
|
||||
gr_vector_void_star &output_items)
|
||||
{
|
||||
Gnss_Synchro **in = (Gnss_Synchro **) &input_items[0]; // Get the input pointer
|
||||
Gnss_Synchro **out = (Gnss_Synchro **) &output_items[0]; // Get the output pointer
|
||||
|
||||
Gnss_Synchro current_gnss_synchro[d_nchannels];
|
||||
|
||||
if (d_nchannels != ninput_items.size())
|
||||
{
|
||||
LOG(WARNING) << "The Observables block is not well connected";
|
||||
}
|
||||
|
||||
bool valid_observables=false;
|
||||
/*
|
||||
* 1. Read the GNSS SYNCHRO objects from available channels.
|
||||
* Multi-rate GNURADIO Block. Read how many input items are avaliable in each channel
|
||||
* Record all synchronization data into queues
|
||||
*/
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
|
||||
//TODO: optimize this: Copy the telemetry decoder data to local copy
|
||||
current_gnss_synchro[i] = in[i][0];
|
||||
/*
|
||||
* 1.2 Assume no valid pseudoranges
|
||||
*/
|
||||
current_gnss_synchro[i].Flag_valid_pseudorange = false;
|
||||
current_gnss_synchro[i].Pseudorange_m = 0.0;
|
||||
|
||||
|
||||
for (int j=0;j<ninput_items[i];j++)
|
||||
{
|
||||
/*
|
||||
* 1.2 Assume no valid pseudoranges
|
||||
*/
|
||||
if (in[i][j].Flag_valid_word)
|
||||
{
|
||||
valid_observables=true;
|
||||
d_gnss_synchro_history_queue[i].push_back(in[i][j]);
|
||||
if (d_gnss_synchro_history_queue[i].size() > history_deep)
|
||||
{
|
||||
d_gnss_synchro_history_queue[i].pop_front();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// Clear the observables history for this channel
|
||||
if (d_gnss_synchro_history_queue[i].size() > 0)
|
||||
{
|
||||
d_gnss_synchro_history_queue[i].clear();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* 2. Compute RAW pseudoranges using COMMON TRANSMISSION TIME algorithm. Use only the valid channels (channels that are tracking a satellite)
|
||||
*/
|
||||
if(valid_observables==true)
|
||||
{
|
||||
std::map<int,Gnss_Synchro> current_gnss_synchro_map;
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
if (d_gnss_synchro_history_queue[i].size() > 0)
|
||||
{
|
||||
//record the word structure in a map for pseudorange computation
|
||||
current_gnss_synchro_map.insert(std::pair<int, Gnss_Synchro>(
|
||||
d_gnss_synchro_history_queue[i].back().Channel_ID,
|
||||
d_gnss_synchro_history_queue[i].back()));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
std::map<int,Gnss_Synchro>::iterator gnss_synchro_map_iter;
|
||||
std::deque<Gnss_Synchro>::iterator gnss_synchro_deque_iter;
|
||||
//find the most distant satellite (minimum tow) to be the common TX time
|
||||
gnss_synchro_map_iter = min_element(current_gnss_synchro_map.begin(), current_gnss_synchro_map.end(), Hybrid_pairCompare_gnss_synchro_d_TOW);
|
||||
double TOW_reference_s = gnss_synchro_map_iter->second.TOW_at_current_symbol_s;
|
||||
//todo: Use also the Week number to avoid week rollover problems!
|
||||
if (TOW_reference_s!=d_last_ref_TOW)
|
||||
{
|
||||
d_last_ref_TOW=TOW_reference_s;
|
||||
//shift channels history to match the reference TOW
|
||||
current_gnss_synchro_map.clear();
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
if (d_gnss_synchro_history_queue[i].size() > 0)
|
||||
{
|
||||
gnss_synchro_deque_iter = std::lower_bound(d_gnss_synchro_history_queue[i].begin(),
|
||||
d_gnss_synchro_history_queue[i].end(),
|
||||
TOW_reference_s,
|
||||
Hybrid_valueCompare_gnss_synchro_d_TOW);
|
||||
//check TOW difference less than a threshold
|
||||
if (fabs(gnss_synchro_deque_iter->TOW_at_current_symbol_s-TOW_reference_s)<1e-4)
|
||||
{
|
||||
//record the word structure in a map for pseudorange computation
|
||||
current_gnss_synchro_map.insert(std::pair<int, Gnss_Synchro>(gnss_synchro_deque_iter->Channel_ID,*gnss_synchro_deque_iter));
|
||||
|
||||
//discard other elements
|
||||
int distance=std::distance(d_gnss_synchro_history_queue[i].begin(), gnss_synchro_deque_iter);
|
||||
|
||||
|
||||
}else{
|
||||
std::cout<<"not found valid TOW in history for SV "
|
||||
<<gnss_synchro_deque_iter->Signal
|
||||
<<" "<<gnss_synchro_deque_iter->PRN
|
||||
<<" Diff tow: "<<gnss_synchro_deque_iter->TOW_at_current_symbol_s-TOW_reference_s
|
||||
<<std::endl;
|
||||
|
||||
int n=0;
|
||||
for(std::deque<Gnss_Synchro>::iterator tmp_iter = d_gnss_synchro_history_queue[i].begin(); tmp_iter != d_gnss_synchro_history_queue[i].end(); tmp_iter++)
|
||||
{
|
||||
|
||||
std::cout<<"TOW History difference ["<<n
|
||||
<<"]="<<tmp_iter->TOW_at_current_symbol_s-TOW_reference_s<<std::endl;
|
||||
n++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Find the nearest satellite at common transmission time: the one who has the minimum PRN timestamp
|
||||
gnss_synchro_map_iter = min_element(current_gnss_synchro_map.begin(), current_gnss_synchro_map.end(), Hybrid_pairCompare_gnss_synchro_sample_counter);
|
||||
//std::cout<<"OBS SV REF SAT: "<<gnss_synchro_map_iter->second.Signal<< " "<<gnss_synchro_map_iter->second.PRN<<" TOW Ref: "<<TOW_reference_s<<std::endl;
|
||||
unsigned long int ref_sample_counter = gnss_synchro_map_iter->second.Tracking_sample_counter;
|
||||
double ref_code_phase_samples = gnss_synchro_map_iter->second.Code_phase_samples;
|
||||
// Now compute RX time differences due to the PRN alignment in the correlators
|
||||
int delta_rx_time_samples;
|
||||
|
||||
double delta_rx_time_s;
|
||||
double traveltime_ms;
|
||||
double pseudorange_m;
|
||||
|
||||
for(gnss_synchro_map_iter = current_gnss_synchro_map.begin(); gnss_synchro_map_iter != current_gnss_synchro_map.end(); gnss_synchro_map_iter++)
|
||||
{
|
||||
|
||||
//compute the pseudorange (no rx time offset correction)
|
||||
|
||||
delta_rx_time_samples = gnss_synchro_map_iter->second.Tracking_sample_counter-ref_sample_counter;
|
||||
delta_rx_time_s = ((double)delta_rx_time_samples + gnss_synchro_map_iter->second.Code_phase_samples-ref_code_phase_samples)/((double)gnss_synchro_map_iter->second.fs);
|
||||
|
||||
traveltime_ms = delta_rx_time_s*1000.0 + GPS_STARTOFFSET_ms;
|
||||
|
||||
//convert to meters
|
||||
pseudorange_m = traveltime_ms * GPS_C_m_ms; // [m]
|
||||
|
||||
// update the pseudorange object
|
||||
current_gnss_synchro[gnss_synchro_map_iter->second.Channel_ID] = gnss_synchro_map_iter->second;
|
||||
current_gnss_synchro[gnss_synchro_map_iter->second.Channel_ID].Pseudorange_m = pseudorange_m;
|
||||
current_gnss_synchro[gnss_synchro_map_iter->second.Channel_ID].Flag_valid_pseudorange = true;
|
||||
// Save the estimated RX time (no RX clock offset correction yet!)
|
||||
current_gnss_synchro[gnss_synchro_map_iter->second.Channel_ID].RX_time = TOW_reference_s + GPS_STARTOFFSET_ms / 1000.0;
|
||||
|
||||
//std::cout<<gnss_synchro_map_iter->second.Signal<<" ["<<gnss_synchro_map_iter->second.PRN
|
||||
// <<"] delta_TOW: "<<(gnss_synchro_map_iter->second.TOW_at_current_symbol_s-TOW_reference_s)*1000.0
|
||||
// <<" [ms] delta_Prn_timestamp : "<<delta_rx_time_s*1000.0
|
||||
// <<" [ms] Pr: "<<pseudorange_m<<" [m]"
|
||||
// <<std::endl;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// if (d_Prn_timestamp_queue_s[gnss_synchro_iter->second.Channel_ID].size() >= history_deep)
|
||||
// {
|
||||
// arma::vec d_Prn_timestamp_vec_s;
|
||||
// arma::vec symbol_TOW_vec_s;
|
||||
// arma::vec dopper_vec_hz;
|
||||
// arma::vec dopper_vec_interp_hz;
|
||||
// arma::vec acc_phase_vec_rads;
|
||||
// arma::vec acc_phase_vec_interp_rads;
|
||||
// arma::vec desired_Prn_timestamp_s(1);
|
||||
// arma::vec TOW_at_rx_time_interp_s;
|
||||
//
|
||||
// // compute interpolated observation values
|
||||
// d_Prn_timestamp_vec_s = arma::vec(std::vector<double>(d_Prn_timestamp_queue_s[gnss_synchro_iter->second.Channel_ID].begin(), d_Prn_timestamp_queue_s[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
// symbol_TOW_vec_s = arma::vec(std::vector<double>(d_symbol_TOW_queue_s[gnss_synchro_iter->second.Channel_ID].begin(), d_symbol_TOW_queue_s[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
// acc_phase_vec_rads = arma::vec(std::vector<double>(d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].begin(), d_acc_carrier_phase_queue_rads[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
// dopper_vec_hz = arma::vec(std::vector<double>(d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].begin(), d_carrier_doppler_queue_hz[gnss_synchro_iter->second.Channel_ID].end()));
|
||||
//
|
||||
// desired_Prn_timestamp_s[0]=d_ref_PRN_rx_time_s;
|
||||
//
|
||||
// if (ref_channel_id != gnss_synchro_iter->second.Channel_ID)
|
||||
// {
|
||||
// // Interpolatio/Extrapoladion using Curve fitting to quadratic function
|
||||
// //arma::interp1(d_Prn_timestamp_vec_s,symbol_TOW_vec_s,desired_Prn_timestamp_s,TOW_at_rx_time_interp_s); //no extrapolation support !
|
||||
//
|
||||
// arma::vec p1 = arma::polyfit(d_Prn_timestamp_vec_s,symbol_TOW_vec_s,1);
|
||||
//
|
||||
// TOW_at_rx_time_interp_s = arma::polyval(p1,desired_Prn_timestamp_s);
|
||||
//
|
||||
// //compute the pseudorange (no rx time offset correction)
|
||||
// traveltime_ms = (TOW_reference_s - TOW_at_rx_time_interp_s[0]) * 1000.0
|
||||
// + GPS_STARTOFFSET_ms;
|
||||
//
|
||||
// //std::cout<<gnss_synchro_iter->second.Signal<<"["<<gnss_synchro_iter->second.PRN<<"] TOW_at_rx_time_interp_s: "<<TOW_at_rx_time_interp_s[0]
|
||||
// // <<" [s] delta_TOW_s: "<<(TOW_reference_s - gnss_synchro_iter->second.d_TOW_at_current_symbol_s)
|
||||
// // <<" [s] delta_TOW_at_rx_time: "<<(TOW_reference_s - TOW_at_rx_time_interp_s[0])
|
||||
// // <<" Pr: "<<pseudorange_m<<" [m]"
|
||||
// // <<std::endl;
|
||||
// }else{
|
||||
// //std::cout<<"REF channel "<<ref_channel_id<<" PRN"<<gnss_synchro_iter->second.PRN<<std::endl;
|
||||
// traveltime_ms = GPS_STARTOFFSET_ms;
|
||||
// }
|
||||
// }
|
||||
|
||||
|
||||
if(d_dump == true)
|
||||
{
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
tmp_double = current_gnss_synchro[i].RX_time;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].TOW_at_current_symbol_s;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Carrier_Doppler_hz;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Carrier_phase_rads/GPS_TWO_PI;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].Pseudorange_m;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_gnss_synchro[i].PRN;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
}
|
||||
catch (const std::ifstream::failure& e)
|
||||
{
|
||||
LOG(WARNING) << "Exception writing observables dump file " << e.what();
|
||||
}
|
||||
}
|
||||
|
||||
for (unsigned int i = 0; i < d_nchannels; i++)
|
||||
{
|
||||
*out[i] = current_gnss_synchro[i];
|
||||
}
|
||||
if (noutput_items == 0)
|
||||
{
|
||||
LOG(WARNING) << "noutput_items = 0";
|
||||
}
|
||||
|
||||
//Multi-rate consume!
|
||||
for (unsigned int i=0; i<d_nchannels;i++)
|
||||
{
|
||||
consume(i,ninput_items[i]); //which input, how many items
|
||||
}
|
||||
return 1;
|
||||
}
|
@ -0,0 +1,75 @@
|
||||
/*!
|
||||
* \file hybrid_observables_cc.h
|
||||
* \brief Interface of the observables computation block for Galileo E1
|
||||
* \author Mara Branzanti 2013. mara.branzanti(at)gmail.com
|
||||
* \author Javier Arribas 2013. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2015 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
|
||||
#ifndef GNSS_SDR_HYBRID_OBSERVABLES_CC_H
|
||||
#define GNSS_SDR_HYBRID_OBSERVABLES_CC_H
|
||||
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <gnuradio/block.h>
|
||||
#include "gnss_synchro.h"
|
||||
|
||||
|
||||
class hybrid_observables_cc;
|
||||
|
||||
typedef boost::shared_ptr<hybrid_observables_cc> hybrid_observables_cc_sptr;
|
||||
|
||||
hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int n_channels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
|
||||
/*!
|
||||
* \brief This class implements a block that computes Galileo observables
|
||||
*/
|
||||
class hybrid_observables_cc : public gr::block
|
||||
{
|
||||
public:
|
||||
~hybrid_observables_cc ();
|
||||
int general_work (int noutput_items, gr_vector_int &ninput_items,
|
||||
gr_vector_const_void_star &input_items, gr_vector_void_star &output_items);
|
||||
|
||||
private:
|
||||
friend hybrid_observables_cc_sptr
|
||||
hybrid_make_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
hybrid_observables_cc(unsigned int nchannels, bool dump, std::string dump_filename, unsigned int deep_history);
|
||||
|
||||
//Tracking observable history
|
||||
std::vector<std::deque<Gnss_Synchro>> d_gnss_synchro_history_queue;
|
||||
|
||||
double d_last_ref_TOW;
|
||||
bool d_dump;
|
||||
unsigned int d_nchannels;
|
||||
unsigned int history_deep;
|
||||
std::string d_dump_filename;
|
||||
std::ofstream d_dump_file;
|
||||
};
|
||||
|
||||
#endif
|
@ -158,7 +158,6 @@ galileo_e1b_telemetry_decoder_cc::galileo_e1b_telemetry_decoder_cc(
|
||||
d_stat = 0;
|
||||
d_preamble_index = 0;
|
||||
|
||||
d_preamble_time_seconds = 0;
|
||||
d_flag_frame_sync = false;
|
||||
|
||||
d_flag_parity = false;
|
||||
@ -370,11 +369,11 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items __attribut
|
||||
d_CRC_error_counter = 0;
|
||||
d_flag_preamble = true; //valid preamble indicator (initialized to false every work())
|
||||
d_preamble_index = d_sample_counter; //record the preamble sample stamp (t_P)
|
||||
d_preamble_time_seconds = in[0][0].Tracking_timestamp_secs; // - d_preamble_duration_seconds; //record the PRN start sample index associated to the preamble
|
||||
if (!d_flag_frame_sync)
|
||||
{
|
||||
d_flag_frame_sync = true;
|
||||
LOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]";
|
||||
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at "
|
||||
<< in[0][0].Tracking_sample_counter << " [samples]";
|
||||
}
|
||||
}
|
||||
else
|
||||
@ -456,29 +455,28 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items __attribut
|
||||
current_synchro_data.Flag_valid_word = false;
|
||||
}
|
||||
|
||||
current_synchro_data.d_TOW_at_current_symbol = d_TOW_at_current_symbol;
|
||||
current_synchro_data.TOW_at_current_symbol_s = d_TOW_at_current_symbol;
|
||||
//todo: move to observables: current_synchro_data.d_TOW_hybrid_at_current_symbol = current_synchro_data.d_TOW_at_current_symbol - delta_t; //delta_t = t_gal - t_gps ----> t_gps = t_gal -delta_t
|
||||
current_synchro_data.Prn_timestamp_ms = in[0][0].Tracking_timestamp_secs * 1000.0;
|
||||
|
||||
if(d_dump == true)
|
||||
{
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_synchro_data.Prn_timestamp_ms;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
double tmp_double;
|
||||
unsigned long int tmp_ulong_int;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_ulong_int = current_synchro_data.Tracking_sample_counter;
|
||||
d_dump_file.write((char*)&tmp_ulong_int, sizeof(unsigned long int));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
catch (const std::ifstream::failure& e)
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
LOG(WARNING) << "Exception writing observables dump file " << e.what();
|
||||
}
|
||||
}
|
||||
//todo: implement averaging
|
||||
d_average_count++;
|
||||
|
||||
if (d_average_count == d_decimation_output_factor)
|
||||
|
@ -117,8 +117,6 @@ private:
|
||||
int d_average_count;
|
||||
int d_decimation_output_factor;
|
||||
|
||||
double d_preamble_time_seconds;
|
||||
|
||||
double d_TOW_at_Preamble;
|
||||
double d_TOW_at_current_symbol;
|
||||
|
||||
|
@ -241,7 +241,6 @@ galileo_e5a_telemetry_decoder_cc::galileo_e5a_telemetry_decoder_cc(
|
||||
d_state = 0;
|
||||
d_preamble_lock = false;
|
||||
d_preamble_index = 0;
|
||||
d_preamble_time_seconds = 0;
|
||||
d_flag_frame_sync = false;
|
||||
d_current_symbol = 0;
|
||||
d_prompt_counter = 0;
|
||||
@ -444,12 +443,11 @@ int galileo_e5a_telemetry_decoder_cc::general_work (int noutput_items __attribut
|
||||
{
|
||||
d_CRC_error_counter = 0;
|
||||
d_flag_preamble = true; //valid preamble indicator (initialized to false every work())
|
||||
d_preamble_time_seconds = in[0][0].Tracking_timestamp_secs - (static_cast<double>(GALILEO_FNAV_CODES_PER_PAGE+GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD); //record the PRN start sample index associated to the preamble start.
|
||||
if (!d_flag_frame_sync)
|
||||
{
|
||||
d_flag_frame_sync = true;
|
||||
LOG(INFO) <<" Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]";
|
||||
}
|
||||
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at "
|
||||
<< in[0][0].Tracking_sample_counter << " [samples]"; }
|
||||
d_symbol_counter = 0; // d_page_symbols start right after preamble and finish at the end of next preamble.
|
||||
}
|
||||
else
|
||||
@ -535,23 +533,23 @@ int galileo_e5a_telemetry_decoder_cc::general_work (int noutput_items __attribut
|
||||
current_synchro_data.Flag_valid_word = false;
|
||||
}
|
||||
|
||||
current_synchro_data.d_TOW_at_current_symbol = d_TOW_at_current_symbol;
|
||||
current_synchro_data.Prn_timestamp_ms = in[0][0].Tracking_timestamp_secs * 1000.0;
|
||||
current_synchro_data.TOW_at_current_symbol_s = d_TOW_at_current_symbol;
|
||||
|
||||
if(d_dump == true)
|
||||
{
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_synchro_data.Prn_timestamp_ms;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
double tmp_double;
|
||||
unsigned long int tmp_ulong_int;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_ulong_int = current_synchro_data.Tracking_sample_counter;
|
||||
d_dump_file.write((char*)&tmp_ulong_int, sizeof(unsigned long int));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
catch (const std::ifstream::failure& e)
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
LOG(WARNING) << "Exception writing observables dump file " << e.what();
|
||||
}
|
||||
|
@ -116,8 +116,6 @@ private:
|
||||
Gnss_Satellite d_satellite;
|
||||
int d_channel;
|
||||
|
||||
double d_preamble_time_seconds;
|
||||
|
||||
double d_TOW_at_Preamble;
|
||||
double d_TOW_at_current_symbol;
|
||||
|
||||
|
@ -95,7 +95,6 @@ gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
|
||||
d_symbol_accumulator = 0;
|
||||
d_symbol_accumulator_counter = 0;
|
||||
d_frame_bit_index = 0;
|
||||
d_preamble_time_seconds = 0;
|
||||
d_flag_frame_sync = false;
|
||||
d_GPS_frame_4bytes = 0;
|
||||
d_prev_GPS_frame_4bytes = 0;
|
||||
@ -180,8 +179,8 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
{
|
||||
d_GPS_FSM.Event_gps_word_preamble();
|
||||
//record the preamble sample stamp
|
||||
d_preamble_time_seconds = in[0][0].Tracking_timestamp_secs; // record the preamble sample stamp
|
||||
DLOG(INFO) << "Preamble detection for SAT " << this->d_satellite << "in[0][0].Tracking_timestamp_secs=" << round(in[0][0].Tracking_timestamp_secs * 1000.0);
|
||||
d_preamble_time_samples = in[0][0].Tracking_sample_counter; // record the preamble sample stamp
|
||||
DLOG(INFO) << "Preamble detection for SAT " << this->d_satellite << "in[0][0].Tracking_sample_counter=" << in[0][0].Tracking_sample_counter;
|
||||
//sync the symbol to bits integrator
|
||||
d_symbol_accumulator = 0;
|
||||
d_symbol_accumulator_counter = 0;
|
||||
@ -190,17 +189,17 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
}
|
||||
else if (d_stat == 1) //check 6 seconds of preamble separation
|
||||
{
|
||||
preamble_diff_ms = round((in[0][0].Tracking_timestamp_secs - d_preamble_time_seconds) * 1000.0);
|
||||
preamble_diff_ms = round((((double)in[0][0].Tracking_sample_counter - d_preamble_time_samples)/(double)in[0][0].fs) * 1000.0);
|
||||
if (abs(preamble_diff_ms - GPS_SUBFRAME_MS) < 1)
|
||||
{
|
||||
DLOG(INFO) << "Preamble confirmation for SAT " << this->d_satellite << "in[0][0].Tracking_timestamp_secs=" << round(in[0][0].Tracking_timestamp_secs * 1000.0);
|
||||
DLOG(INFO) << "Preamble confirmation for SAT " << this->d_satellite;
|
||||
d_GPS_FSM.Event_gps_word_preamble();
|
||||
d_flag_preamble = true;
|
||||
d_preamble_time_seconds = in[0][0].Tracking_timestamp_secs; // record the PRN start sample index associated to the preamble
|
||||
d_preamble_time_samples = in[0][0].Tracking_sample_counter; // record the PRN start sample index associated to the preamble
|
||||
if (!d_flag_frame_sync)
|
||||
{
|
||||
// send asynchronous message to tracking to inform of frame sync and extend correlation time
|
||||
pmt::pmt_t value = pmt::from_double(d_preamble_time_seconds - 0.001);
|
||||
pmt::pmt_t value = pmt::from_double((double)d_preamble_time_samples/(double)in[0][0].fs - 0.001);
|
||||
this->message_port_pub(pmt::mp("preamble_timestamp_s"), value);
|
||||
d_flag_frame_sync = true;
|
||||
if (corr_value < 0)
|
||||
@ -212,7 +211,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
{
|
||||
flag_PLL_180_deg_phase_locked = false;
|
||||
}
|
||||
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]";
|
||||
DLOG(INFO) << " Frame sync SAT " << this->d_satellite << " with preamble start at " << (double)d_preamble_time_samples/(double)in[0][0].fs << " [s]";
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -221,7 +220,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
{
|
||||
if (d_stat == 1)
|
||||
{
|
||||
preamble_diff_ms = round((in[0][0].Tracking_timestamp_secs - d_preamble_time_seconds) * 1000.0);
|
||||
preamble_diff_ms = round((((double)in[0][0].Tracking_sample_counter - (double)d_preamble_time_samples)/(double)in[0][0].fs) * 1000.0);
|
||||
if (preamble_diff_ms > GPS_SUBFRAME_MS+1)
|
||||
{
|
||||
DLOG(INFO) << "Lost of frame sync SAT " << this->d_satellite << " preamble_diff= " << preamble_diff_ms;
|
||||
@ -274,7 +273,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
if (gps_l1_ca_telemetry_decoder_cc::gps_word_parityCheck(d_GPS_frame_4bytes))
|
||||
{
|
||||
memcpy(&d_GPS_FSM.d_GPS_frame_4bytes, &d_GPS_frame_4bytes, sizeof(char)*4);
|
||||
d_GPS_FSM.d_preamble_time_ms = d_preamble_time_seconds * 1000.0;
|
||||
//d_GPS_FSM.d_preamble_time_ms = d_preamble_time_seconds * 1000.0;
|
||||
d_GPS_FSM.Event_gps_word_valid();
|
||||
// send TLM data to PVT using asynchronous message queues
|
||||
if (d_GPS_FSM.d_flag_new_subframe == true)
|
||||
@ -350,9 +349,9 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
d_TOW_at_current_symbol = d_TOW_at_current_symbol + GPS_L1_CA_CODE_PERIOD;
|
||||
}
|
||||
|
||||
current_synchro_data.d_TOW_at_current_symbol = d_TOW_at_current_symbol;
|
||||
current_synchro_data.Flag_valid_word = flag_TOW_set;//(d_flag_frame_sync == true and d_flag_parity == true and flag_TOW_set == true);
|
||||
current_synchro_data.Prn_timestamp_ms = in[0][0].Tracking_timestamp_secs * 1000.0;
|
||||
current_synchro_data.TOW_at_current_symbol_s = d_TOW_at_current_symbol;
|
||||
current_synchro_data.Flag_valid_word = flag_TOW_set;
|
||||
|
||||
|
||||
if (flag_PLL_180_deg_phase_locked == true)
|
||||
{
|
||||
@ -366,10 +365,11 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
unsigned long int tmp_ulong_int;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_synchro_data.Prn_timestamp_ms;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_ulong_int = current_synchro_data.Tracking_sample_counter;
|
||||
d_dump_file.write((char*)&tmp_ulong_int, sizeof(unsigned long int));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
@ -379,8 +379,6 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items __attribute_
|
||||
}
|
||||
}
|
||||
|
||||
//todo: implement averaging
|
||||
|
||||
d_average_count++;
|
||||
if (d_average_count == d_decimation_output_factor)
|
||||
{
|
||||
|
@ -119,7 +119,7 @@ private:
|
||||
Gnss_Satellite d_satellite;
|
||||
int d_channel;
|
||||
|
||||
double d_preamble_time_seconds;
|
||||
unsigned long int d_preamble_time_samples;
|
||||
|
||||
long double d_TOW_at_Preamble;
|
||||
long double d_TOW_at_current_symbol;
|
||||
|
@ -154,7 +154,7 @@ int gps_l2c_telemetry_decoder_cc::general_work (int noutput_items __attribute__(
|
||||
//* delay by the formulae:
|
||||
//* \code
|
||||
//* symbolTime_ms = msg->tow * 6000 + *pdelay * 20
|
||||
d_TOW_at_current_symbol=((double)msg.tow) * 6.0 + ((double)delay) * GPS_L2_M_PERIOD +11.5*GPS_L2_M_PERIOD;
|
||||
d_TOW_at_current_symbol=((double)msg.tow) * 6.0 + ((double)delay) * GPS_L2_M_PERIOD +12*GPS_L2_M_PERIOD;
|
||||
d_flag_valid_word=true;
|
||||
}
|
||||
else
|
||||
@ -165,8 +165,7 @@ int gps_l2c_telemetry_decoder_cc::general_work (int noutput_items __attribute__(
|
||||
d_flag_valid_word=false;
|
||||
}
|
||||
}
|
||||
current_synchro_data.d_TOW_at_current_symbol = d_TOW_at_current_symbol;
|
||||
current_synchro_data.Prn_timestamp_ms = in[0].Tracking_timestamp_secs * 1000.0;
|
||||
current_synchro_data.TOW_at_current_symbol_s = d_TOW_at_current_symbol;
|
||||
current_synchro_data.Flag_valid_word=d_flag_valid_word;
|
||||
|
||||
// if (flag_PLL_180_deg_phase_locked == true)
|
||||
@ -180,13 +179,14 @@ int gps_l2c_telemetry_decoder_cc::general_work (int noutput_items __attribute__(
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
try
|
||||
{
|
||||
double tmp_double;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = current_synchro_data.Prn_timestamp_ms;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
double tmp_double;
|
||||
unsigned long int tmp_ulong_int;
|
||||
tmp_double = d_TOW_at_current_symbol;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
tmp_ulong_int = current_synchro_data.Tracking_sample_counter;
|
||||
d_dump_file.write((char*)&tmp_ulong_int, sizeof(unsigned long int));
|
||||
tmp_double = d_TOW_at_Preamble;
|
||||
d_dump_file.write((char*)&tmp_double, sizeof(double));
|
||||
}
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
|
@ -103,7 +103,7 @@ int sbas_l1_telemetry_decoder_cc::general_work (int noutput_items __attribute__(
|
||||
Gnss_Synchro *out = (Gnss_Synchro *) output_items[0]; // output
|
||||
|
||||
// store the time stamp of the first sample in the processed sample block
|
||||
double sample_stamp = in[0].Tracking_timestamp_secs;
|
||||
double sample_stamp = in[0].Tracking_sample_counter/in[0].fs;
|
||||
|
||||
// copy correlation samples into samples vector
|
||||
for (int i = 0; i < noutput_items; i++)
|
||||
|
@ -238,7 +238,6 @@ GpsL1CaSubframeFsm::GpsL1CaSubframeFsm()
|
||||
d_nav.reset();
|
||||
i_channel_ID = 0;
|
||||
i_satellite_PRN = 0;
|
||||
d_preamble_time_ms = 0;
|
||||
d_subframe_ID=0;
|
||||
d_flag_new_subframe=false;
|
||||
initiate(); //start the FSM
|
||||
@ -266,7 +265,6 @@ void GpsL1CaSubframeFsm::gps_subframe_to_nav_msg()
|
||||
<< Gnss_Satellite(std::string("GPS"), i_satellite_PRN) << std::endl;
|
||||
d_nav.i_satellite_PRN = i_satellite_PRN;
|
||||
d_nav.i_channel_ID = i_channel_ID;
|
||||
d_nav.d_subframe_timestamp_ms = this->d_preamble_time_ms;
|
||||
|
||||
d_flag_new_subframe=true;
|
||||
}
|
||||
|
@ -83,7 +83,7 @@ public:
|
||||
int d_subframe_ID;
|
||||
bool d_flag_new_subframe;
|
||||
char d_GPS_frame_4bytes[GPS_WORD_LENGTH];
|
||||
double d_preamble_time_ms;
|
||||
//double d_preamble_time_ms;
|
||||
|
||||
void gps_word_to_subframe(int position); //!< inserts the word in the correct position of the subframe
|
||||
|
||||
|
@ -289,8 +289,9 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items __attri
|
||||
int acq_to_trk_delay_samples;
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_current_prn_length_samples - std::fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_current_prn_length_samples));
|
||||
samples_offset = std::round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
d_sample_counter = d_sample_counter + samples_offset; //count for the processed samples
|
||||
d_pull_in = false;
|
||||
@ -335,7 +336,6 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items __attri
|
||||
//Code phase accumulator
|
||||
double code_error_filt_secs;
|
||||
code_error_filt_secs = (Galileo_E1_CODE_PERIOD * code_error_filt_chips) / Galileo_E1_CODE_CHIP_RATE_HZ; //[seconds]
|
||||
//code_error_filt_secs=T_prn_seconds*code_error_filt_chips*T_chip_seconds*static_cast<float>(d_fs_in); //[seconds]
|
||||
d_acc_code_phase_secs = d_acc_code_phase_secs + code_error_filt_secs;
|
||||
|
||||
// ################## CARRIER AND CODE NCO BUFFER ALIGNEMENT #######################
|
||||
@ -349,8 +349,7 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items __attri
|
||||
T_prn_seconds = T_chip_seconds * Galileo_E1_B_CODE_LENGTH_CHIPS;
|
||||
T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
|
||||
K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
|
||||
d_current_prn_length_samples = std::round(K_blk_samples); //round to a discrete samples
|
||||
//d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample
|
||||
d_current_prn_length_samples = round(K_blk_samples); //round to a discrete samples
|
||||
|
||||
// ####### CN0 ESTIMATION AND LOCK DETECTORS ######
|
||||
if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES)
|
||||
@ -393,7 +392,8 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items __attri
|
||||
current_synchro_data.Prompt_I = static_cast<double>((*d_Prompt).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((*d_Prompt).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
//compute remnant code phase samples AFTER the Tracking timestamp
|
||||
d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
@ -409,13 +409,15 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items __attri
|
||||
*d_Prompt = gr_complex(0,0);
|
||||
*d_Late = gr_complex(0,0);
|
||||
// GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
}
|
||||
//assign the GNURadio block output data
|
||||
current_synchro_data.System = {'E'};
|
||||
std::string str_aux = "1B";
|
||||
const char * str = str_aux.c_str(); // get a C style null terminated string
|
||||
std::memcpy((void*)current_synchro_data.Signal, str, 3);
|
||||
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
|
@ -284,7 +284,8 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attr
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_current_prn_length_samples - fmod((float)acq_to_trk_delay_samples, (float)d_current_prn_length_samples);
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
d_sample_counter = d_sample_counter + samples_offset; //count for the processed samples
|
||||
d_pull_in = false;
|
||||
@ -402,10 +403,9 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attr
|
||||
current_synchro_data.Prompt_I = (double)(*d_Prompt).real();
|
||||
current_synchro_data.Prompt_Q = (double)(*d_Prompt).imag();
|
||||
// Tracking_timestamp_secs is aligned with the PRN start sample
|
||||
//current_synchro_data.Tracking_timestamp_secs = ((double)d_sample_counter + (double)d_next_prn_length_samples + (double)d_next_rem_code_phase_samples)/(double)d_fs_in;
|
||||
current_synchro_data.Tracking_timestamp_secs = ((double)d_sample_counter + (double)d_rem_code_phase_samples)/(double)d_fs_in;
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample
|
||||
// This tracking block aligns the Tracking_timestamp_secs with the start sample of the PRN, thus, Code_phase_secs=0
|
||||
current_synchro_data.Carrier_phase_rads = (double)d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = (double)d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = (double)d_CN0_SNV_dB_Hz;
|
||||
@ -417,8 +417,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attr
|
||||
*d_Early = gr_complex(0,0);
|
||||
*d_Prompt = gr_complex(0,0);
|
||||
*d_Late = gr_complex(0,0);
|
||||
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
//! When tracking is disabled an array of 1's is sent to maintain the TCP connection
|
||||
boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> tx_variables_array = {{1,1,1,1,1,1,1,1,1,1,1,1,0}};
|
||||
d_tcp_com.send_receive_tcp_packet_galileo_e1(tx_variables_array, &tcp_data);
|
||||
@ -429,6 +428,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attr
|
||||
const char * str = str_aux.c_str(); // get a C style null terminated string
|
||||
std::memcpy((void*)current_synchro_data.Signal, str, 3);
|
||||
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
|
@ -399,9 +399,7 @@ int Galileo_E5a_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute
|
||||
d_Prompt = gr_complex(0,0);
|
||||
d_Late = gr_complex(0,0);
|
||||
d_Prompt_data = gr_complex(0,0);
|
||||
current_synchro_data.Tracking_timestamp_secs = static_cast<double>(d_sample_counter) / static_cast<double>(d_fs_in);
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter;
|
||||
break;
|
||||
}
|
||||
case 1:
|
||||
@ -419,10 +417,10 @@ int Galileo_E5a_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute
|
||||
// make an output to not stop the rest of the processing blocks
|
||||
current_synchro_data.Prompt_I = 0.0;
|
||||
current_synchro_data.Prompt_Q = 0.0;
|
||||
current_synchro_data.Tracking_timestamp_secs = static_cast<double>(d_sample_counter) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter;
|
||||
current_synchro_data.Carrier_phase_rads = 0.0;
|
||||
current_synchro_data.CN0_dB_hz = 0.0;
|
||||
*out[0] = current_synchro_data;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
consume_each(samples_offset); //shift input to perform alignment with local replica
|
||||
return 1;
|
||||
break;
|
||||
@ -625,9 +623,8 @@ int Galileo_E5a_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute
|
||||
{
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_Prompt_data).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_Prompt_data).imag());
|
||||
// Tracking_timestamp_secs is aligned with the PRN start sample
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_current_prn_length_samples) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
// This tracking block aligns the Tracking_timestamp_secs with the start sample of the PRN, thus, Code_phase_secs=0
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -638,16 +635,19 @@ int Galileo_E5a_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute
|
||||
// make an output to not stop the rest of the processing blocks
|
||||
current_synchro_data.Prompt_I = 0.0;
|
||||
current_synchro_data.Prompt_Q = 0.0;
|
||||
current_synchro_data.Tracking_timestamp_secs = static_cast<double>(d_sample_counter) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter;
|
||||
current_synchro_data.Carrier_phase_rads = 0.0;
|
||||
current_synchro_data.CN0_dB_hz = 0.0;
|
||||
|
||||
}
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
{
|
||||
// MULTIPLEXED FILE RECORDING - Record results to file
|
||||
|
@ -339,12 +339,13 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work (int noutput_items __attri
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_correlation_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
d_sample_counter += samples_offset; // count for the processed samples
|
||||
d_pull_in = false;
|
||||
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
consume_each(samples_offset); // shift input to perform alignment with local replica
|
||||
return 1;
|
||||
@ -537,8 +538,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work (int noutput_items __attri
|
||||
// ########### Output the tracking data to navigation and PVT ##########
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -556,8 +557,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work (int noutput_items __attri
|
||||
{
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;// todo: project the carrier doppler
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -571,9 +572,10 @@ int gps_l1_ca_dll_pll_c_aid_tracking_cc::general_work (int noutput_items __attri
|
||||
}
|
||||
|
||||
current_synchro_data.System = {'G'};
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
}
|
||||
//assign the GNURadio block output data
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
if(d_dump)
|
||||
{
|
||||
|
@ -332,12 +332,13 @@ int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::general_work (int noutput_items __
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_correlation_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
d_sample_counter += samples_offset; // count for the processed samples
|
||||
d_pull_in = false;
|
||||
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
consume_each(samples_offset); // shift input to perform alignment with local replica
|
||||
multicorrelator_fpga_8sc.set_initial_sample(samples_offset);
|
||||
@ -532,8 +533,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::general_work (int noutput_items __
|
||||
// ########### Output the tracking data to navigation and PVT ##########
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -551,8 +552,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::general_work (int noutput_items __
|
||||
{
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;// todo: project the carrier doppler
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -566,8 +567,9 @@ int gps_l1_ca_dll_pll_c_aid_tracking_fpga_sc::general_work (int noutput_items __
|
||||
}
|
||||
|
||||
current_synchro_data.System = {'G'};
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
}
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
if(d_dump)
|
||||
{
|
||||
|
@ -343,12 +343,13 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work (int noutput_items __attri
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_correlation_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
d_sample_counter += samples_offset; // count for the processed samples
|
||||
d_pull_in = false;
|
||||
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * samples_offset / GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_cycles * GPS_TWO_PI;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
consume_each(samples_offset); // shift input to perform alignment with local replica
|
||||
return 1;
|
||||
@ -541,7 +542,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work (int noutput_items __attri
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -559,8 +561,8 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work (int noutput_items __attri
|
||||
{
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs_16sc[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs_16sc[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;// todo: project the carrier doppler
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -574,8 +576,9 @@ int gps_l1_ca_dll_pll_c_aid_tracking_sc::general_work (int noutput_items __attri
|
||||
}
|
||||
|
||||
current_synchro_data.System = {'G'};
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + d_correlation_length_samples + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
}
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
if(d_dump)
|
||||
{
|
||||
|
@ -308,13 +308,14 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute__
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_current_prn_length_samples - fmod(static_cast<float>(acq_to_trk_delay_samples), static_cast<float>(d_current_prn_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
d_sample_counter = d_sample_counter + samples_offset; // count for the processed samples
|
||||
d_pull_in = false;
|
||||
// take into account the carrier cycles accumulated in the pull in signal alignment
|
||||
d_acc_carrier_phase_rad -= d_carrier_phase_step_rad * samples_offset;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
consume_each(samples_offset); // shift input to perform alignment with local replica
|
||||
return 1;
|
||||
@ -345,13 +346,16 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute__
|
||||
code_error_chips = dll_nc_e_minus_l_normalized(d_correlator_outs[0], d_correlator_outs[2]); // [chips/Ti] //early and late
|
||||
// Code discriminator filter
|
||||
code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); // [chips/second]
|
||||
double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GPS_L1_CA_CODE_RATE_HZ; // [seconds]
|
||||
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
|
||||
double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
|
||||
double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips*T_chip_seconds); //[seconds]
|
||||
//double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GPS_L1_CA_CODE_RATE_HZ; // [seconds]
|
||||
|
||||
// ################## CARRIER AND CODE NCO BUFFER ALIGNEMENT #######################
|
||||
// keep alignment parameters for the next input buffer
|
||||
// Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation
|
||||
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
|
||||
double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
|
||||
//double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
|
||||
//double T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
|
||||
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
|
||||
double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
|
||||
d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
|
||||
@ -407,8 +411,8 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute__
|
||||
// ########### Output the tracking data to navigation and PVT ##########
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter + d_current_prn_length_samples) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -422,11 +426,12 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items __attribute__
|
||||
d_correlator_outs[n] = gr_complex(0,0);
|
||||
}
|
||||
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter + d_current_prn_length_samples) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter =d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.System = {'G'};
|
||||
}
|
||||
|
||||
//assign the GNURadio block output data
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
if(d_dump)
|
||||
{
|
||||
|
@ -317,10 +317,9 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work (int noutput_items __attribu
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_correlation_length_samples - fmod(static_cast<double>(acq_to_trk_delay_samples), static_cast<double>(d_correlation_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
d_sample_counter += samples_offset; //count for the processed samples
|
||||
d_pull_in = false;
|
||||
consume_each(samples_offset); //shift input to perform alignment with local replica
|
||||
@ -436,10 +435,8 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work (int noutput_items __attribu
|
||||
// ########### Output the tracking data to navigation and PVT ##########
|
||||
current_synchro_data.Prompt_I = static_cast<double>((d_correlator_outs[1]).real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>((d_correlator_outs[1]).imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!)
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + old_d_rem_code_phase_samples) / static_cast<double>(d_fs_in);
|
||||
// This tracking block aligns the Tracking_timestamp_secs with the start sample of the PRN, thus, Code_phase_secs=0
|
||||
current_synchro_data.Code_phase_secs = 0;
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = GPS_TWO_PI * d_acc_carrier_phase_cycles;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -456,10 +453,11 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work (int noutput_items __attribu
|
||||
}
|
||||
|
||||
current_synchro_data.System = {'G'};
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
}
|
||||
|
||||
//assign the GNURadio block output data
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
|
@ -201,15 +201,6 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
|
||||
|
||||
long int acq_trk_diff_samples;
|
||||
float acq_trk_diff_seconds;
|
||||
// jarribas: this patch correct a situation where the tracking sample counter
|
||||
// is equal to 0 (remains in the initial state) at the first acquisition to tracking transition
|
||||
// of the receiver operation when is connecting to simulink server.
|
||||
// if (d_sample_counter<d_acq_sample_stamp)
|
||||
// {
|
||||
// acq_trk_diff_samples=0; //disable the correction
|
||||
// }else{
|
||||
// acq_trk_diff_samples = d_sample_counter - d_acq_sample_stamp;//-d_vector_length;
|
||||
// }
|
||||
acq_trk_diff_samples = (long int)d_sample_counter - (long int)d_acq_sample_stamp;
|
||||
std::cout << "acq_trk_diff_samples=" << acq_trk_diff_samples << std::endl;
|
||||
acq_trk_diff_seconds = (float)acq_trk_diff_samples / (float)d_fs_in;
|
||||
@ -308,6 +299,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attri
|
||||
tcp_packet_data tcp_data;
|
||||
// GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder
|
||||
Gnss_Synchro current_synchro_data = Gnss_Synchro();
|
||||
|
||||
// Block input data and block output stream pointers
|
||||
const gr_complex* in = (gr_complex*) input_items[0];
|
||||
Gnss_Synchro **out = (Gnss_Synchro **) &output_items[0];
|
||||
@ -329,9 +321,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attri
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_next_prn_length_samples - fmod((float)acq_to_trk_delay_samples, (float)d_next_prn_length_samples);
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
// /todo: Check if the sample counter sent to the next block as a time reference should be incremented AFTER sended or BEFORE
|
||||
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
d_sample_counter_seconds = d_sample_counter_seconds + (((double)samples_offset) / (double)d_fs_in);
|
||||
d_sample_counter = d_sample_counter + samples_offset; //count for the processed samples
|
||||
@ -450,13 +441,10 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attri
|
||||
|
||||
current_synchro_data.Prompt_I = (double)(*d_Prompt).real();
|
||||
current_synchro_data.Prompt_Q = (double)(*d_Prompt).imag();
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample (Hybridization OK!, but some glitches??)
|
||||
current_synchro_data.Tracking_timestamp_secs = ((double)d_sample_counter + (double)d_rem_code_phase_samples)/(double)d_fs_in;
|
||||
//compute remnant code phase samples AFTER the Tracking timestamp
|
||||
d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample
|
||||
|
||||
// This tracking block aligns the Tracking_timestamp_secs with the start sample of the PRN, thus, Code_phase_secs=0
|
||||
current_synchro_data.Tracking_timestamp_secs = d_sample_counter_seconds;
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = (double)d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = (double)d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = (double)d_CN0_SNV_dB_Hz;
|
||||
@ -470,7 +458,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attri
|
||||
*d_Prompt = gr_complex(0,0);
|
||||
*d_Late = gr_complex(0,0);
|
||||
// GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder
|
||||
current_synchro_data.Tracking_timestamp_secs = ((double)d_sample_counter + (double)d_rem_code_phase_samples)/(double)d_fs_in;
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_correlation_length_samples;
|
||||
//! When tracking is disabled an array of 1's is sent to maintain the TCP connection
|
||||
boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> tx_variables_array = {{1,1,1,1,1,1,1,1,0}};
|
||||
d_tcp_com.send_receive_tcp_packet_gps_l1_ca(tx_variables_array, &tcp_data);
|
||||
@ -482,6 +470,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items __attri
|
||||
const char * str = str_aux.c_str(); // get a C style null terminated string
|
||||
std::memcpy((void*)current_synchro_data.Signal, str, 3);
|
||||
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
|
@ -257,14 +257,14 @@ void gps_l2_m_dll_pll_tracking_cc::start_tracking()
|
||||
sys = sys_.substr(0,1);
|
||||
|
||||
// DEBUG OUTPUT
|
||||
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
|
||||
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
|
||||
std::cout << "Tracking GPS L2CM start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
|
||||
LOG(INFO) << "Starting GPS L2CM tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
|
||||
|
||||
// enable tracking
|
||||
d_pull_in = true;
|
||||
d_enable_tracking = true;
|
||||
|
||||
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
|
||||
LOG(INFO) << "GPS L2CM PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
|
||||
<< " Code Phase correction [samples]=" << delay_correction_samples
|
||||
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
|
||||
}
|
||||
@ -312,13 +312,14 @@ int gps_l2_m_dll_pll_tracking_cc::general_work (int noutput_items __attribute__(
|
||||
acq_to_trk_delay_samples = d_sample_counter - d_acq_sample_stamp;
|
||||
acq_trk_shif_correction_samples = d_current_prn_length_samples - fmod(static_cast<float>(acq_to_trk_delay_samples), static_cast<float>(d_current_prn_length_samples));
|
||||
samples_offset = round(d_acq_code_phase_samples + acq_trk_shif_correction_samples);
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + samples_offset;
|
||||
d_sample_counter = d_sample_counter + samples_offset; // count for the processed samples
|
||||
d_pull_in = false;
|
||||
// take into account the carrier cycles accumulated in the pull in signal alignment
|
||||
d_acc_carrier_phase_rad -= d_carrier_phase_step_rad * samples_offset;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
consume_each(samples_offset); // shift input to perform alignment with local replica
|
||||
return 1;
|
||||
@ -349,13 +350,14 @@ int gps_l2_m_dll_pll_tracking_cc::general_work (int noutput_items __attribute__(
|
||||
code_error_chips = dll_nc_e_minus_l_normalized(d_correlator_outs[0], d_correlator_outs[2]); // [chips/Ti]
|
||||
// Code discriminator filter
|
||||
code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); //[chips/second]
|
||||
double code_error_filt_secs = (GPS_L2_M_PERIOD * code_error_filt_chips) / GPS_L2_M_CODE_RATE_HZ; //[seconds]
|
||||
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
|
||||
double T_prn_seconds = T_chip_seconds * GPS_L2_M_CODE_LENGTH_CHIPS;
|
||||
double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips*T_chip_seconds); //[seconds]
|
||||
//double code_error_filt_secs = (GPS_L2_M_PERIOD * code_error_filt_chips) / GPS_L2_M_CODE_RATE_HZ; //[seconds]
|
||||
|
||||
// ################## CARRIER AND CODE NCO BUFFER ALIGNEMENT #######################
|
||||
// keep alignment parameters for the next input buffer
|
||||
// Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation
|
||||
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
|
||||
double T_prn_seconds = T_chip_seconds * GPS_L2_M_CODE_LENGTH_CHIPS;
|
||||
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
|
||||
double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
|
||||
d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
|
||||
@ -411,8 +413,8 @@ int gps_l2_m_dll_pll_tracking_cc::general_work (int noutput_items __attribute__(
|
||||
// ########### Output the tracking data to navigation and PVT ##########
|
||||
current_synchro_data.Prompt_I = static_cast<double>(d_correlator_outs[1].real());
|
||||
current_synchro_data.Prompt_Q = static_cast<double>(d_correlator_outs[1].imag());
|
||||
// Tracking_timestamp_secs is aligned with the CURRENT PRN start sample
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter + d_current_prn_length_samples) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter = d_sample_counter + d_current_prn_length_samples;
|
||||
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
|
||||
current_synchro_data.Carrier_phase_rads = d_acc_carrier_phase_rad;
|
||||
current_synchro_data.Carrier_Doppler_hz = d_carrier_doppler_hz;
|
||||
current_synchro_data.CN0_dB_hz = d_CN0_SNV_dB_Hz;
|
||||
@ -426,9 +428,10 @@ int gps_l2_m_dll_pll_tracking_cc::general_work (int noutput_items __attribute__(
|
||||
{
|
||||
d_correlator_outs[n] = gr_complex(0,0);
|
||||
}
|
||||
current_synchro_data.Tracking_timestamp_secs = (static_cast<double>(d_sample_counter + d_current_prn_length_samples) + static_cast<double>(d_rem_code_phase_samples)) / static_cast<double>(d_fs_in);
|
||||
current_synchro_data.Tracking_sample_counter =d_sample_counter + d_current_prn_length_samples;
|
||||
}
|
||||
//assign the GNURadio block output data
|
||||
current_synchro_data.fs=d_fs_in;
|
||||
*out[0] = current_synchro_data;
|
||||
|
||||
if(d_dump)
|
||||
|
@ -216,7 +216,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetSignalConditioner(
|
||||
|
||||
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetObservables(std::shared_ptr<ConfigurationInterface> configuration)
|
||||
{
|
||||
std::string default_implementation = "GPS_L1_CA_Observables";
|
||||
std::string default_implementation = "Hybrid_Observables";
|
||||
std::string implementation = configuration->property("Observables.implementation", default_implementation);
|
||||
LOG(INFO) << "Getting Observables with implementation " << implementation;
|
||||
unsigned int Galileo_channels = configuration->property("Channels_1B.count", 0);
|
||||
@ -230,7 +230,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetObservables(std::shared
|
||||
|
||||
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetPVT(std::shared_ptr<ConfigurationInterface> configuration)
|
||||
{
|
||||
std::string default_implementation = "Pass_Through";
|
||||
std::string default_implementation = "Hybrid_PVT";
|
||||
std::string implementation = configuration->property("PVT.implementation", default_implementation);
|
||||
LOG(INFO) << "Getting PVT with implementation " << implementation;
|
||||
unsigned int Galileo_channels =configuration->property("Channels_1B.count", 0);
|
||||
|
@ -384,6 +384,7 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
|
||||
channels_.at(who)->set_signal(available_GNSS_signals_.front());
|
||||
available_GNSS_signals_.pop_front();
|
||||
usleep(100);
|
||||
LOG(INFO) << "Channel "<< who << " Starting acquisition " << channels_.at(who)->get_signal().get_satellite() << ", Signal " << channels_.at(who)->get_signal().get_signal_str();
|
||||
channels_.at(who)->start_acquisition();
|
||||
break;
|
||||
case 1:
|
||||
|
@ -52,20 +52,21 @@ public:
|
||||
unsigned long int Acq_samplestamp_samples; //!< Set by Acquisition processing block
|
||||
bool Flag_valid_acquisition; //!< Set by Acquisition processing block
|
||||
//Tracking
|
||||
long int fs; //!< Set by Tracking processing block
|
||||
double Prompt_I; //!< Set by Tracking processing block
|
||||
double Prompt_Q; //!< Set by Tracking processing block
|
||||
double CN0_dB_hz; //!< Set by Tracking processing block
|
||||
double Carrier_Doppler_hz; //!< Set by Tracking processing block
|
||||
double Carrier_phase_rads; //!< Set by Tracking processing block
|
||||
double Tracking_timestamp_secs; //!< Set by Tracking processing block
|
||||
double Code_phase_samples; //!< Set by Tracking processing block
|
||||
unsigned long int Tracking_sample_counter; //!< Set by Tracking processing block
|
||||
|
||||
bool Flag_valid_symbol_output; //!< Set by Tracking processing block
|
||||
int correlation_length_ms; //!< Set by Tracking processing block
|
||||
|
||||
//Telemetry Decoder
|
||||
double Prn_timestamp_ms; //!< Set by Telemetry Decoder processing block
|
||||
bool Flag_valid_word; //!< Set by Telemetry Decoder processing block
|
||||
double d_TOW_at_current_symbol; //!< Set by Telemetry Decoder processing block
|
||||
double TOW_at_current_symbol_s; //!< Set by Telemetry Decoder processing block
|
||||
|
||||
// Observables
|
||||
double Pseudorange_m; //!< Set by Observables processing block
|
||||
|
@ -120,6 +120,10 @@ double Gps_CNAV_Ephemeris::sv_clock_drift(double transmitTime)
|
||||
double dt;
|
||||
dt = check_t(transmitTime - d_Toc);
|
||||
d_satClkDrift = d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt) + sv_clock_relativistic_term(transmitTime);
|
||||
|
||||
//Correct satellite group delay
|
||||
d_satClkDrift-=d_TGD;
|
||||
|
||||
return d_satClkDrift;
|
||||
}
|
||||
|
||||
|
@ -117,14 +117,21 @@ double Gps_Ephemeris::check_t(double time)
|
||||
// 20.3.3.3.3.1 User Algorithm for SV Clock Correction.
|
||||
double Gps_Ephemeris::sv_clock_drift(double transmitTime)
|
||||
{
|
||||
// double dt;
|
||||
// dt = check_t(transmitTime - d_Toc);
|
||||
//
|
||||
// for (int i = 0; i < 2; i++)
|
||||
// {
|
||||
// dt -= d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt);
|
||||
// }
|
||||
// d_satClkDrift = d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt);
|
||||
|
||||
|
||||
double dt;
|
||||
dt = check_t(transmitTime - d_Toc);
|
||||
|
||||
for (int i = 0; i < 2; i++)
|
||||
{
|
||||
dt -= d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt);
|
||||
}
|
||||
d_satClkDrift = d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt);
|
||||
d_satClkDrift = d_A_f0 + d_A_f1 * dt + d_A_f2 * (dt * dt) + sv_clock_relativistic_term(transmitTime);
|
||||
//Correct satellite group delay
|
||||
d_satClkDrift-=d_TGD;
|
||||
|
||||
return d_satClkDrift;
|
||||
}
|
||||
|
@ -260,6 +260,8 @@ include_directories(
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/adapters
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/gnuradio_blocks
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/telemetry_decoder/libs
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/observables/adapters
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/observables/gnuradio_blocks
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/signal_source/adapters
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/signal_source/gnuradio_blocks
|
||||
${CMAKE_SOURCE_DIR}/src/algorithms/signal_generator/adapters
|
||||
|
@ -33,7 +33,7 @@
|
||||
|
||||
#include <gflags/gflags.h>
|
||||
|
||||
|
||||
DEFINE_bool(disable_generator, false, "Disable the signal generator (a external signal file must be available for the test)");
|
||||
DEFINE_string(generator_binary, std::string(SW_GENERATOR_BIN), "Path of software-defined signal generator binary");
|
||||
DEFINE_string(rinex_nav_file, std::string(DEFAULT_RINEX_NAV), "Input RINEX navigation file");
|
||||
DEFINE_int32(duration, 100, "Duration of the experiment [in seconds, max = 300]");
|
||||
@ -43,6 +43,6 @@ DEFINE_string(filename_rinex_obs, "sim.16o", "Filename of output RINEX navigatio
|
||||
DEFINE_string(filename_raw_data, "signal_out.bin", "Filename of output raw data file");
|
||||
DEFINE_int32(fs_gen_hz, 2600000, "Samppling frequency [Hz]");
|
||||
DEFINE_int32(test_satellite_PRN, 1, "PRN of the satellite under test (must be visible during the observation time)");
|
||||
|
||||
DEFINE_int32(test_satellite_PRN2, 2, "PRN of the satellite under test (must be visible during the observation time)");
|
||||
|
||||
#endif
|
||||
|
@ -298,13 +298,13 @@ int Obs_Gps_L1_System_Test::configure_receiver()
|
||||
config->set_property("TelemetryDecoder_1C.decimation_factor", std::to_string(decimation_factor));
|
||||
|
||||
// Set Observables
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("Observables.dump", "false");
|
||||
config->set_property("Observables.dump_filename", "./observables.dat");
|
||||
config->set_property("Observables.averaging_depth", std::to_string(100));
|
||||
|
||||
// Set PVT
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
config->set_property("PVT.averaging_depth", std::to_string(averaging_depth));
|
||||
config->set_property("PVT.flag_averaging", "true");
|
||||
config->set_property("PVT.output_rate_ms", std::to_string(output_rate_ms));
|
||||
|
@ -215,12 +215,12 @@ void TTFF_GPS_L1_CA_Test::config_1()
|
||||
config->set_property("TelemetryDecoder_1C.decimation_factor", std::to_string(decimation_factor));
|
||||
|
||||
// Set Observables
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("Observables.dump", "false");
|
||||
config->set_property("Observables.dump_filename", "./observables.dat");
|
||||
|
||||
// Set PVT
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
config->set_property("PVT.averaging_depth", std::to_string(averaging_depth));
|
||||
config->set_property("PVT.flag_averaging", "true");
|
||||
config->set_property("PVT.output_rate_ms", std::to_string(output_rate_ms));
|
||||
|
@ -133,6 +133,7 @@ DECLARE_string(log_dir);
|
||||
#if MODERN_ARMADILLO
|
||||
#include "unit-tests/signal-processing-blocks/tracking/gps_l1_ca_dll_pll_tracking_test.cc"
|
||||
#include "unit-tests/signal-processing-blocks/telemetry_decoder/gps_l1_ca_telemetry_decoder_test.cc"
|
||||
#include "unit-tests/signal-processing-blocks/observables/hybrid_observables_test.cc"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -111,9 +111,9 @@ TEST_F(Control_Thread_Test, InstantiateRunControlMessages)
|
||||
config->set_property("Tracking_1C.item_type", "gr_complex");
|
||||
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
|
||||
config->set_property("TelemetryDecoder_1C.item_type", "gr_complex");
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("Observables.item_type", "gr_complex");
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
config->set_property("PVT.item_type", "gr_complex");
|
||||
|
||||
std::shared_ptr<ControlThread> control_thread = std::make_shared<ControlThread>(config);
|
||||
@ -171,9 +171,9 @@ TEST_F(Control_Thread_Test, InstantiateRunControlMessages2)
|
||||
config->set_property("Tracking_1C.item_type", "gr_complex");
|
||||
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
|
||||
config->set_property("TelemetryDecoder_1C.item_type", "gr_complex");
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("Observables.item_type", "gr_complex");
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
config->set_property("PVT.item_type", "gr_complex");
|
||||
|
||||
std::unique_ptr<ControlThread> control_thread2(new ControlThread(config));
|
||||
@ -235,9 +235,9 @@ TEST_F(Control_Thread_Test, StopReceiverProgrammatically)
|
||||
config->set_property("Tracking_1C.item_type", "gr_complex");
|
||||
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
|
||||
config->set_property("TelemetryDecoder_1C.item_type", "gr_complex");
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("Observables.item_type", "gr_complex");
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
config->set_property("PVT.item_type", "gr_complex");
|
||||
|
||||
std::unique_ptr<ControlThread> control_thread(new ControlThread(config));
|
||||
|
@ -304,11 +304,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateObservables)
|
||||
TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaObservables)
|
||||
{
|
||||
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
|
||||
configuration->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
configuration->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
std::unique_ptr<GNSSBlockFactory> factory;
|
||||
std::unique_ptr<GNSSBlockInterface> observables = factory->GetObservables(configuration);
|
||||
EXPECT_STREQ("Observables", observables->role().c_str());
|
||||
EXPECT_STREQ("GPS_L1_CA_Observables", observables->implementation().c_str());
|
||||
EXPECT_STREQ("Hybrid_Observables", observables->implementation().c_str());
|
||||
}
|
||||
|
||||
|
||||
@ -328,12 +328,12 @@ TEST(GNSS_Block_Factory_Test, InstantiatePvt)
|
||||
TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaPvt)
|
||||
{
|
||||
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
|
||||
configuration->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
configuration->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
std::unique_ptr<GNSSBlockFactory> factory;
|
||||
std::shared_ptr<GNSSBlockInterface> pvt_ = factory->GetPVT(configuration);
|
||||
std::shared_ptr<PvtInterface> pvt = std::dynamic_pointer_cast<PvtInterface>(pvt_);
|
||||
EXPECT_STREQ("PVT", pvt->role().c_str());
|
||||
EXPECT_STREQ("GPS_L1_CA_PVT", pvt->implementation().c_str());
|
||||
EXPECT_STREQ("Hybrid_PVT", pvt->implementation().c_str());
|
||||
}
|
||||
|
||||
|
||||
|
@ -64,8 +64,8 @@ TEST(GNSSFlowgraph, InstantiateConnectStartStopOldNotation)
|
||||
config->set_property("Acquisition_1C.doppler_max", "5000");
|
||||
config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking");
|
||||
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
|
||||
std::shared_ptr<GNSSFlowgraph> flowgraph = std::make_shared<GNSSFlowgraph>(config, gr::msg_queue::make(0));
|
||||
|
||||
@ -99,8 +99,8 @@ TEST(GNSSFlowgraph, InstantiateConnectStartStop)
|
||||
config->set_property("Acquisition_1C.doppler_max", "5000");
|
||||
config->set_property("Tracking_1C.implementation", "GPS_L1_CA_DLL_PLL_Tracking");
|
||||
config->set_property("TelemetryDecoder_1C.implementation", "GPS_L1_CA_Telemetry_Decoder");
|
||||
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
|
||||
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
|
||||
std::shared_ptr<GNSSFlowgraph> flowgraph = std::make_shared<GNSSFlowgraph>(config, gr::msg_queue::make(0));
|
||||
|
||||
@ -133,8 +133,8 @@ TEST(GNSSFlowgraph, InstantiateConnectStartStopGalileoE1B)
|
||||
config->set_property("Acquisition_1B.doppler_max", "5000");
|
||||
config->set_property("Tracking_1B.implementation", "Galileo_E1_DLL_PLL_VEML_Tracking");
|
||||
config->set_property("TelemetryDecoder_1B.implementation", "Galileo_E1B_Telemetry_Decoder");
|
||||
config->set_property("Observables.implementation", "Galileo_E1B_Observables");
|
||||
config->set_property("PVT.implementation", "GALILEO_E1_PVT");
|
||||
config->set_property("Observables.implementation", "Hybrid_Observables");
|
||||
config->set_property("PVT.implementation", "Hybrid_PVT");
|
||||
|
||||
std::shared_ptr<GNSSFlowgraph> flowgraph = std::make_shared<GNSSFlowgraph>(config, gr::msg_queue::make(0));
|
||||
|
||||
|
@ -19,8 +19,10 @@
|
||||
|
||||
set(SIGNAL_PROCESSING_TESTING_LIB_SOURCES
|
||||
tracking_dump_reader.cc
|
||||
tlm_dump_reader.cc
|
||||
tlm_dump_reader.cc
|
||||
observables_dump_reader.cc
|
||||
tracking_true_obs_reader.cc
|
||||
true_observables_reader.cc
|
||||
)
|
||||
|
||||
include_directories(
|
||||
|
@ -0,0 +1,133 @@
|
||||
/*!
|
||||
* \file observables_dump_reader.cc
|
||||
* \brief Helper file for unit testing
|
||||
* \author Javier Arribas, 2017. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#include "observables_dump_reader.h"
|
||||
|
||||
bool observables_dump_reader::read_binary_obs()
|
||||
{
|
||||
try
|
||||
{
|
||||
for(int i=0;i<n_channels;i++)
|
||||
{
|
||||
|
||||
d_dump_file.read((char *) &RX_time[i], sizeof(double));
|
||||
d_dump_file.read((char *) &TOW_at_current_symbol_s[i], sizeof(double));
|
||||
d_dump_file.read((char *) &Carrier_Doppler_hz[i], sizeof(double));
|
||||
d_dump_file.read((char *) &Acc_carrier_phase_hz[i], sizeof(double));
|
||||
d_dump_file.read((char *) &Pseudorange_m[i], sizeof(double));
|
||||
d_dump_file.read((char *) &PRN[i], sizeof(double));
|
||||
}
|
||||
}
|
||||
catch (const std::ifstream::failure &e)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool observables_dump_reader::restart()
|
||||
{
|
||||
if (d_dump_file.is_open())
|
||||
{
|
||||
d_dump_file.clear();
|
||||
d_dump_file.seekg(0, std::ios::beg);
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
long int observables_dump_reader::num_epochs()
|
||||
{
|
||||
std::ifstream::pos_type size;
|
||||
int number_of_vars_in_epoch = n_channels*6;
|
||||
int epoch_size_bytes = sizeof(double) * number_of_vars_in_epoch;
|
||||
std::ifstream tmpfile( d_dump_filename.c_str(), std::ios::binary | std::ios::ate);
|
||||
if (tmpfile.is_open())
|
||||
{
|
||||
size = tmpfile.tellg();
|
||||
long int nepoch = size / epoch_size_bytes;
|
||||
return nepoch;
|
||||
}
|
||||
else
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
bool observables_dump_reader::open_obs_file(std::string out_file)
|
||||
{
|
||||
if (d_dump_file.is_open() == false)
|
||||
{
|
||||
try
|
||||
{
|
||||
d_dump_filename=out_file;
|
||||
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
|
||||
d_dump_file.open(d_dump_filename.c_str(), std::ios::in | std::ios::binary);
|
||||
std::cout << "Observables sum file opened, Log file: " << d_dump_filename.c_str() << std::endl;
|
||||
return true;
|
||||
}
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
std::cout << "Problem opening TLM dump Log file: " << d_dump_filename.c_str() << std::endl;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
observables_dump_reader::observables_dump_reader(int n_channels_)
|
||||
{
|
||||
n_channels=n_channels_;
|
||||
RX_time=new double[n_channels];
|
||||
TOW_at_current_symbol_s=new double[n_channels];
|
||||
Carrier_Doppler_hz=new double[n_channels];
|
||||
Acc_carrier_phase_hz=new double[n_channels];
|
||||
Pseudorange_m=new double[n_channels];
|
||||
PRN=new double[n_channels];
|
||||
}
|
||||
observables_dump_reader::~observables_dump_reader()
|
||||
{
|
||||
if (d_dump_file.is_open() == true)
|
||||
{
|
||||
d_dump_file.close();
|
||||
}
|
||||
delete[] RX_time;
|
||||
delete[] TOW_at_current_symbol_s;
|
||||
delete[] Carrier_Doppler_hz;
|
||||
delete[] Acc_carrier_phase_hz;
|
||||
delete[] Pseudorange_m;
|
||||
delete[] PRN;
|
||||
}
|
@ -0,0 +1,65 @@
|
||||
/*!
|
||||
* \file observables_dump_reader.h
|
||||
* \brief Helper file for unit testing
|
||||
* \author Javier Arribas, 2017. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#ifndef GNSS_SDR_OBSERVABLES_DUMP_READER_H
|
||||
#define GNSS_SDR_OBSERVABLES_DUMP_READER_H
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
class observables_dump_reader
|
||||
{
|
||||
public:
|
||||
observables_dump_reader(int n_channels);
|
||||
~observables_dump_reader();
|
||||
bool read_binary_obs();
|
||||
bool restart();
|
||||
long int num_epochs();
|
||||
bool open_obs_file(std::string out_file);
|
||||
|
||||
|
||||
//dump variables
|
||||
|
||||
double* RX_time;
|
||||
double* TOW_at_current_symbol_s;
|
||||
double* Carrier_Doppler_hz;
|
||||
double* Acc_carrier_phase_hz;
|
||||
double* Pseudorange_m;
|
||||
double* PRN;
|
||||
|
||||
private:
|
||||
int n_channels;
|
||||
std::string d_dump_filename;
|
||||
std::ifstream d_dump_file;
|
||||
};
|
||||
|
||||
#endif //GNSS_SDR_OBSERVABLES_DUMP_READER_H
|
@ -35,7 +35,7 @@ bool tlm_dump_reader::read_binary_obs()
|
||||
try
|
||||
{
|
||||
d_dump_file.read((char *) &TOW_at_current_symbol, sizeof(double));
|
||||
d_dump_file.read((char *) &Prn_timestamp_ms, sizeof(double));
|
||||
d_dump_file.read((char *) &Tracking_sample_counter, sizeof(double));
|
||||
d_dump_file.read((char *) &d_TOW_at_Preamble, sizeof(double));
|
||||
}
|
||||
catch (const std::ifstream::failure &e)
|
||||
|
@ -47,7 +47,7 @@ public:
|
||||
|
||||
//telemetry decoder dump variables
|
||||
double TOW_at_current_symbol;
|
||||
double Prn_timestamp_ms;
|
||||
unsigned long int Tracking_sample_counter;
|
||||
double d_TOW_at_Preamble;
|
||||
|
||||
private:
|
||||
|
@ -0,0 +1,116 @@
|
||||
/*!
|
||||
* \file true_observables_reader.cc
|
||||
* \brief Helper file for unit testing
|
||||
* \author Javier Arribas, 2017. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#include "true_observables_reader.h"
|
||||
|
||||
bool true_observables_reader::read_binary_obs()
|
||||
{
|
||||
try
|
||||
{
|
||||
for(int i=0;i<12;i++)
|
||||
{
|
||||
d_dump_file.read((char *) &gps_time_sec[i], sizeof(double));
|
||||
d_dump_file.read((char *) &doppler_l1_hz, sizeof(double));
|
||||
d_dump_file.read((char *) &acc_carrier_phase_l1_cycles[i], sizeof(double));
|
||||
d_dump_file.read((char *) &dist_m[i], sizeof(double));
|
||||
d_dump_file.read((char *) &carrier_phase_l1_cycles[i], sizeof(double));
|
||||
d_dump_file.read((char *) &prn[i], sizeof(double));
|
||||
}
|
||||
}
|
||||
catch (const std::ifstream::failure &e)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool true_observables_reader::restart()
|
||||
{
|
||||
if (d_dump_file.is_open())
|
||||
{
|
||||
d_dump_file.clear();
|
||||
d_dump_file.seekg(0, std::ios::beg);
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
long int true_observables_reader::num_epochs()
|
||||
{
|
||||
std::ifstream::pos_type size;
|
||||
int number_of_vars_in_epoch = 6*12;
|
||||
int epoch_size_bytes = sizeof(double) * number_of_vars_in_epoch;
|
||||
std::ifstream tmpfile( d_dump_filename.c_str(), std::ios::binary | std::ios::ate);
|
||||
if (tmpfile.is_open())
|
||||
{
|
||||
size = tmpfile.tellg();
|
||||
long int nepoch = size / epoch_size_bytes;
|
||||
return nepoch;
|
||||
}
|
||||
else
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
bool true_observables_reader::open_obs_file(std::string out_file)
|
||||
{
|
||||
if (d_dump_file.is_open() == false)
|
||||
{
|
||||
try
|
||||
{
|
||||
d_dump_filename=out_file;
|
||||
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
|
||||
d_dump_file.open(d_dump_filename.c_str(), std::ios::in | std::ios::binary);
|
||||
std::cout << "True observables Log file opened: " << d_dump_filename.c_str() << std::endl;
|
||||
return true;
|
||||
}
|
||||
catch (const std::ifstream::failure & e)
|
||||
{
|
||||
std::cout << "Problem opening True observables Log file: " << d_dump_filename.c_str() << std::endl;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
true_observables_reader::~true_observables_reader()
|
||||
{
|
||||
if (d_dump_file.is_open() == true)
|
||||
{
|
||||
d_dump_file.close();
|
||||
}
|
||||
}
|
@ -0,0 +1,60 @@
|
||||
/*!
|
||||
* \file tlm_dump_reader.h
|
||||
* \brief Helper file for unit testing
|
||||
* \author Javier Arribas, 2017. jarribas(at)cttc.es
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2010-2017 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
#ifndef GNSS_SDR_TRUE_OBSERVABLES_READER_H
|
||||
#define GNSS_SDR_TRUE_OBSERVABLES_READER_H
|
||||
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
class true_observables_reader
|
||||
{
|
||||
public:
|
||||
~true_observables_reader();
|
||||
bool read_binary_obs();
|
||||
bool restart();
|
||||
long int num_epochs();
|
||||
bool open_obs_file(std::string out_file);
|
||||
|
||||
double gps_time_sec[12];
|
||||
double doppler_l1_hz[12];
|
||||
double acc_carrier_phase_l1_cycles[12];
|
||||
double dist_m[12];
|
||||
double carrier_phase_l1_cycles[12];
|
||||
double prn[12];
|
||||
|
||||
private:
|
||||
std::string d_dump_filename;
|
||||
std::ifstream d_dump_file;
|
||||
};
|
||||
|
||||
#endif //GNSS_SDR_TRUE_OBSERVABLES_READER_H
|
@ -0,0 +1,627 @@
|
||||
/*!
|
||||
* \file hybrid_observables_test.cc
|
||||
* \brief This class implements a tracking test for Galileo_E5a_DLL_PLL_Tracking
|
||||
* implementation based on some input parameters.
|
||||
* \author Javier Arribas, 2015. jarribas(at)cttc.es
|
||||
*
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*
|
||||
* Copyright (C) 2012-2015 (see AUTHORS file for a list of contributors)
|
||||
*
|
||||
* GNSS-SDR is a software defined Global Navigation
|
||||
* Satellite Systems receiver
|
||||
*
|
||||
* This file is part of GNSS-SDR.
|
||||
*
|
||||
* GNSS-SDR is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* GNSS-SDR is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with GNSS-SDR. If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* -------------------------------------------------------------------------
|
||||
*/
|
||||
|
||||
|
||||
#include <exception>
|
||||
#include <cstring>
|
||||
#include <ctime>
|
||||
#include <iostream>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <sys/wait.h>
|
||||
#include <unistd.h>
|
||||
#include <armadillo>
|
||||
#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/blocks/interleaved_char_to_complex.h>
|
||||
#include <gnuradio/blocks/null_sink.h>
|
||||
#include <gnuradio/blocks/skiphead.h>
|
||||
#include <gtest/gtest.h>
|
||||
#include "GPS_L1_CA.h"
|
||||
#include "gnss_satellite.h"
|
||||
#include "gnss_block_factory.h"
|
||||
#include "gnss_block_interface.h"
|
||||
#include "tracking_interface.h"
|
||||
#include "telemetry_decoder_interface.h"
|
||||
#include "in_memory_configuration.h"
|
||||
#include "gnss_synchro.h"
|
||||
#include "gps_l1_ca_telemetry_decoder.h"
|
||||
#include "tracking_true_obs_reader.h"
|
||||
#include "true_observables_reader.h"
|
||||
#include "tracking_dump_reader.h"
|
||||
#include "observables_dump_reader.h"
|
||||
#include "tlm_dump_reader.h"
|
||||
#include "gps_l1_ca_dll_pll_tracking.h"
|
||||
#include "gps_l1_ca_dll_pll_c_aid_tracking.h"
|
||||
#include "hybrid_observables.h"
|
||||
#include "signal_generator_flags.h"
|
||||
|
||||
|
||||
// ######## GNURADIO BLOCK MESSAGE RECEVER FOR TRACKING MESSAGES #########
|
||||
class HybridObservablesTest_msg_rx;
|
||||
|
||||
typedef boost::shared_ptr<HybridObservablesTest_msg_rx> HybridObservablesTest_msg_rx_sptr;
|
||||
|
||||
HybridObservablesTest_msg_rx_sptr HybridObservablesTest_msg_rx_make();
|
||||
|
||||
class HybridObservablesTest_msg_rx : public gr::block
|
||||
{
|
||||
private:
|
||||
friend HybridObservablesTest_msg_rx_sptr HybridObservablesTest_msg_rx_make();
|
||||
void msg_handler_events(pmt::pmt_t msg);
|
||||
HybridObservablesTest_msg_rx();
|
||||
|
||||
public:
|
||||
int rx_message;
|
||||
~HybridObservablesTest_msg_rx(); //!< Default destructor
|
||||
|
||||
};
|
||||
|
||||
HybridObservablesTest_msg_rx_sptr HybridObservablesTest_msg_rx_make()
|
||||
{
|
||||
return HybridObservablesTest_msg_rx_sptr(new HybridObservablesTest_msg_rx());
|
||||
}
|
||||
|
||||
void HybridObservablesTest_msg_rx::msg_handler_events(pmt::pmt_t msg)
|
||||
{
|
||||
try
|
||||
{
|
||||
long int message = pmt::to_long(msg);
|
||||
rx_message = message;
|
||||
}
|
||||
catch(boost::bad_any_cast& e)
|
||||
{
|
||||
LOG(WARNING) << "msg_handler_telemetry Bad any cast!";
|
||||
rx_message = 0;
|
||||
}
|
||||
}
|
||||
|
||||
HybridObservablesTest_msg_rx::HybridObservablesTest_msg_rx() :
|
||||
gr::block("HybridObservablesTest_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0))
|
||||
{
|
||||
this->message_port_register_in(pmt::mp("events"));
|
||||
this->set_msg_handler(pmt::mp("events"), boost::bind(&HybridObservablesTest_msg_rx::msg_handler_events, this, _1));
|
||||
rx_message = 0;
|
||||
}
|
||||
|
||||
HybridObservablesTest_msg_rx::~HybridObservablesTest_msg_rx()
|
||||
{}
|
||||
|
||||
|
||||
// ###########################################################
|
||||
|
||||
|
||||
// ######## GNURADIO BLOCK MESSAGE RECEVER FOR TLM MESSAGES #########
|
||||
class HybridObservablesTest_tlm_msg_rx;
|
||||
|
||||
typedef boost::shared_ptr<HybridObservablesTest_tlm_msg_rx> HybridObservablesTest_tlm_msg_rx_sptr;
|
||||
|
||||
HybridObservablesTest_tlm_msg_rx_sptr HybridObservablesTest_tlm_msg_rx_make();
|
||||
|
||||
class HybridObservablesTest_tlm_msg_rx : public gr::block
|
||||
{
|
||||
private:
|
||||
friend HybridObservablesTest_tlm_msg_rx_sptr HybridObservablesTest_tlm_msg_rx_make();
|
||||
void msg_handler_events(pmt::pmt_t msg);
|
||||
HybridObservablesTest_tlm_msg_rx();
|
||||
|
||||
public:
|
||||
int rx_message;
|
||||
~HybridObservablesTest_tlm_msg_rx(); //!< Default destructor
|
||||
|
||||
};
|
||||
|
||||
HybridObservablesTest_tlm_msg_rx_sptr HybridObservablesTest_tlm_msg_rx_make()
|
||||
{
|
||||
return HybridObservablesTest_tlm_msg_rx_sptr(new HybridObservablesTest_tlm_msg_rx());
|
||||
}
|
||||
|
||||
void HybridObservablesTest_tlm_msg_rx::msg_handler_events(pmt::pmt_t msg)
|
||||
{
|
||||
try
|
||||
{
|
||||
long int message = pmt::to_long(msg);
|
||||
rx_message = message;
|
||||
}
|
||||
catch(boost::bad_any_cast& e)
|
||||
{
|
||||
LOG(WARNING) << "msg_handler_telemetry Bad any cast!";
|
||||
rx_message = 0;
|
||||
}
|
||||
}
|
||||
|
||||
HybridObservablesTest_tlm_msg_rx::HybridObservablesTest_tlm_msg_rx() :
|
||||
gr::block("HybridObservablesTest_tlm_msg_rx", gr::io_signature::make(0, 0, 0), gr::io_signature::make(0, 0, 0))
|
||||
{
|
||||
this->message_port_register_in(pmt::mp("events"));
|
||||
this->set_msg_handler(pmt::mp("events"), boost::bind(&HybridObservablesTest_tlm_msg_rx::msg_handler_events, this, _1));
|
||||
rx_message = 0;
|
||||
}
|
||||
|
||||
HybridObservablesTest_tlm_msg_rx::~HybridObservablesTest_tlm_msg_rx()
|
||||
{}
|
||||
|
||||
|
||||
// ###########################################################
|
||||
|
||||
|
||||
class HybridObservablesTest: public ::testing::Test
|
||||
{
|
||||
|
||||
public:
|
||||
std::string generator_binary;
|
||||
std::string p1;
|
||||
std::string p2;
|
||||
std::string p3;
|
||||
std::string p4;
|
||||
std::string p5;
|
||||
|
||||
const int baseband_sampling_freq = FLAGS_fs_gen_hz;
|
||||
|
||||
std::string filename_rinex_obs = FLAGS_filename_rinex_obs;
|
||||
std::string filename_raw_data = FLAGS_filename_raw_data;
|
||||
|
||||
int configure_generator();
|
||||
int generate_signal();
|
||||
void check_results(
|
||||
arma::vec true_ch0_dist_m, arma::vec true_ch1_dist_m,
|
||||
arma::vec true_ch0_tow_s,
|
||||
arma::vec measuded_ch0_Pseudorange_m,
|
||||
arma::vec measuded_ch1_Pseudorange_m,
|
||||
arma::vec measuded_ch0_RX_time_s);
|
||||
|
||||
HybridObservablesTest()
|
||||
{
|
||||
factory = std::make_shared<GNSSBlockFactory>();
|
||||
config = std::make_shared<InMemoryConfiguration>();
|
||||
item_size = sizeof(gr_complex);
|
||||
gnss_synchro_ch0 = Gnss_Synchro();
|
||||
gnss_synchro_ch1 = Gnss_Synchro();
|
||||
}
|
||||
|
||||
~HybridObservablesTest()
|
||||
{}
|
||||
|
||||
void configure_receiver();
|
||||
|
||||
gr::top_block_sptr top_block;
|
||||
std::shared_ptr<GNSSBlockFactory> factory;
|
||||
std::shared_ptr<InMemoryConfiguration> config;
|
||||
Gnss_Synchro gnss_synchro_ch0;
|
||||
Gnss_Synchro gnss_synchro_ch1;
|
||||
size_t item_size;
|
||||
};
|
||||
|
||||
int HybridObservablesTest::configure_generator()
|
||||
{
|
||||
// Configure signal generator
|
||||
generator_binary = FLAGS_generator_binary;
|
||||
|
||||
p1 = std::string("-rinex_nav_file=") + FLAGS_rinex_nav_file;
|
||||
if(FLAGS_dynamic_position.empty())
|
||||
{
|
||||
p2 = std::string("-static_position=") + FLAGS_static_position + std::string(",") + std::to_string(FLAGS_duration * 10);
|
||||
}
|
||||
else
|
||||
{
|
||||
p2 = std::string("-obs_pos_file=") + std::string(FLAGS_dynamic_position);
|
||||
}
|
||||
p3 = std::string("-rinex_obs_file=") + FLAGS_filename_rinex_obs; // RINEX 2.10 observation file output
|
||||
p4 = std::string("-sig_out_file=") + FLAGS_filename_raw_data; // Baseband signal output file. Will be stored in int8_t IQ multiplexed samples
|
||||
p5 = std::string("-sampling_freq=") + std::to_string(baseband_sampling_freq); //Baseband sampling frequency [MSps]
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int HybridObservablesTest::generate_signal()
|
||||
{
|
||||
int child_status;
|
||||
|
||||
char *const parmList[] = { &generator_binary[0], &generator_binary[0], &p1[0], &p2[0], &p3[0], &p4[0], &p5[0], NULL };
|
||||
|
||||
int pid;
|
||||
if ((pid = fork()) == -1)
|
||||
perror("fork err");
|
||||
else if (pid == 0)
|
||||
{
|
||||
execv(&generator_binary[0], parmList);
|
||||
std::cout << "Return not expected. Must be an execv err." << std::endl;
|
||||
std::terminate();
|
||||
}
|
||||
|
||||
waitpid(pid, &child_status, 0);
|
||||
|
||||
std::cout << "Signal and Observables RINEX and RAW files created." << std::endl;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
void HybridObservablesTest::configure_receiver()
|
||||
{
|
||||
gnss_synchro_ch0.Channel_ID = 0;
|
||||
gnss_synchro_ch0.System = 'G';
|
||||
std::string signal = "1C";
|
||||
signal.copy(gnss_synchro_ch0.Signal, 2, 0);
|
||||
gnss_synchro_ch0.PRN = FLAGS_test_satellite_PRN;
|
||||
|
||||
gnss_synchro_ch1.Channel_ID = 1;
|
||||
gnss_synchro_ch1.System = 'G';
|
||||
signal.copy(gnss_synchro_ch1.Signal, 2, 0);
|
||||
gnss_synchro_ch1.PRN = FLAGS_test_satellite_PRN2;
|
||||
|
||||
|
||||
config->set_property("GNSS-SDR.internal_fs_hz", std::to_string(baseband_sampling_freq));
|
||||
|
||||
// Set Tracking
|
||||
config->set_property("Tracking_1C.item_type", "gr_complex");
|
||||
config->set_property("Tracking_1C.if", "0");
|
||||
config->set_property("Tracking_1C.dump", "true");
|
||||
config->set_property("Tracking_1C.dump_filename", "./tracking_ch_");
|
||||
config->set_property("Tracking_1C.pll_bw_hz", "20.0");
|
||||
config->set_property("Tracking_1C.dll_bw_hz", "1.5");
|
||||
config->set_property("Tracking_1C.early_late_space_chips", "0.5");
|
||||
|
||||
|
||||
config->set_property("TelemetryDecoder_1C.dump","true");
|
||||
config->set_property("TelemetryDecoder_1C.decimation_factor","1");
|
||||
|
||||
config->set_property("Observables.history_depth","500");
|
||||
config->set_property("Observables.dump","true");
|
||||
|
||||
|
||||
}
|
||||
|
||||
void HybridObservablesTest::check_results(
|
||||
arma::vec true_ch0_dist_m,
|
||||
arma::vec true_ch1_dist_m,
|
||||
arma::vec true_ch0_tow_s,
|
||||
arma::vec measuded_ch0_Pseudorange_m,
|
||||
arma::vec measuded_ch1_Pseudorange_m,
|
||||
arma::vec measuded_ch0_RX_time_s)
|
||||
{
|
||||
//1. True value interpolation to match the measurement times
|
||||
|
||||
arma::vec true_ch0_dist_interp;
|
||||
arma::vec true_ch1_dist_interp;
|
||||
arma::interp1(true_ch0_tow_s, true_ch0_dist_m, measuded_ch0_RX_time_s, true_ch0_dist_interp);
|
||||
arma::interp1(true_ch0_tow_s, true_ch1_dist_m, measuded_ch0_RX_time_s, true_ch1_dist_interp);
|
||||
|
||||
// generate delta pseudoranges
|
||||
std::cout<<"s1:"<<true_ch0_dist_m.size()<<std::endl;
|
||||
std::cout<<"s2:"<<true_ch1_dist_m.size()<<std::endl;
|
||||
std::cout<<"s3:"<<measuded_ch0_Pseudorange_m.size()<<std::endl;
|
||||
std::cout<<"s4:"<<measuded_ch1_Pseudorange_m.size()<<std::endl;
|
||||
arma::vec delta_true_dist_m = true_ch0_dist_interp-true_ch1_dist_interp;
|
||||
arma::vec delta_measured_dist_m = measuded_ch0_Pseudorange_m-measuded_ch1_Pseudorange_m;
|
||||
|
||||
|
||||
|
||||
//2. RMSE
|
||||
arma::vec err;
|
||||
|
||||
err = delta_measured_dist_m - delta_true_dist_m;
|
||||
arma::vec err2 = arma::square(err);
|
||||
double rmse = sqrt(arma::mean(err2));
|
||||
|
||||
//3. Mean err and variance
|
||||
double error_mean = arma::mean(err);
|
||||
double error_var = arma::var(err);
|
||||
|
||||
// 4. Peaks
|
||||
double max_error = arma::max(err);
|
||||
double min_error = arma::min(err);
|
||||
|
||||
//5. report
|
||||
|
||||
std::cout << std::setprecision(10) << "Delta Observables RMSE="
|
||||
<< rmse << ", mean=" << error_mean
|
||||
<< ", stdev=" << sqrt(error_var)
|
||||
<< " (max,min)=" << max_error
|
||||
<< "," << min_error
|
||||
<< " [meters]" << std::endl;
|
||||
|
||||
ASSERT_LT(rmse, 10E-3);
|
||||
ASSERT_LT(error_mean, 10E-3);
|
||||
ASSERT_GT(error_mean, 10E-3);
|
||||
ASSERT_LT(error_var, 10E-3);
|
||||
ASSERT_LT(max_error, 10E-3);
|
||||
ASSERT_GT(min_error, 10E-3);
|
||||
}
|
||||
|
||||
TEST_F(HybridObservablesTest, ValidationOfResults)
|
||||
{
|
||||
// Configure the signal generator
|
||||
configure_generator();
|
||||
|
||||
// Generate signal raw signal samples and observations RINEX file
|
||||
if (FLAGS_disable_generator==false)
|
||||
{
|
||||
generate_signal();
|
||||
}
|
||||
|
||||
struct timeval tv;
|
||||
long long int begin = 0;
|
||||
long long int end = 0;
|
||||
|
||||
configure_receiver();
|
||||
|
||||
//open true observables log file written by the simulator
|
||||
tracking_true_obs_reader true_obs_data_ch0;
|
||||
tracking_true_obs_reader true_obs_data_ch1;
|
||||
int test_satellite_PRN = FLAGS_test_satellite_PRN;
|
||||
int test_satellite_PRN2 = FLAGS_test_satellite_PRN2;
|
||||
std::cout << "Testing satellite PRNs " << test_satellite_PRN <<","<<test_satellite_PRN << std::endl;
|
||||
std::string true_obs_file = std::string("./gps_l1_ca_obs_prn");
|
||||
true_obs_file.append(std::to_string(test_satellite_PRN));
|
||||
true_obs_file.append(".dat");
|
||||
ASSERT_NO_THROW({
|
||||
if (true_obs_data_ch0.open_obs_file(true_obs_file) == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
}) << "Failure opening true observables file" << std::endl;
|
||||
|
||||
true_obs_file = std::string("./gps_l1_ca_obs_prn");
|
||||
true_obs_file.append(std::to_string(test_satellite_PRN2));
|
||||
true_obs_file.append(".dat");
|
||||
ASSERT_NO_THROW({
|
||||
if (true_obs_data_ch1.open_obs_file(true_obs_file) == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
}) << "Failure opening true observables file" << std::endl;
|
||||
|
||||
top_block = gr::make_top_block("Telemetry_Decoder test");
|
||||
std::shared_ptr<TrackingInterface> tracking_ch0 = std::make_shared<GpsL1CaDllPllTracking>(config.get(), "Tracking_1C", 1, 1);
|
||||
//std::shared_ptr<TrackingInterface> tracking_ch1 = std::make_shared<GpsL1CaDllPllCAidTracking>(config.get(), "Tracking_1C", 1, 1);
|
||||
std::shared_ptr<TrackingInterface> tracking_ch1 = std::make_shared<GpsL1CaDllPllTracking>(config.get(), "Tracking_1C", 1, 1);
|
||||
//std::shared_ptr<TrackingInterface> tracking_ch1 = std::make_shared<GpsL1CaDllPllCAidTracking>(config.get(), "Tracking_1C", 1, 1);
|
||||
|
||||
boost::shared_ptr<HybridObservablesTest_msg_rx> msg_rx_ch0 = HybridObservablesTest_msg_rx_make();
|
||||
boost::shared_ptr<HybridObservablesTest_msg_rx> msg_rx_ch1 = HybridObservablesTest_msg_rx_make();
|
||||
|
||||
// load acquisition data based on the first epoch of the true observations
|
||||
ASSERT_NO_THROW({
|
||||
if (true_obs_data_ch0.read_binary_obs() == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
})<< "Failure reading true observables file" << std::endl;
|
||||
|
||||
ASSERT_NO_THROW({
|
||||
if (true_obs_data_ch1.read_binary_obs() == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
})<< "Failure reading true observables file" << std::endl;
|
||||
|
||||
//restart the epoch counter
|
||||
true_obs_data_ch0.restart();
|
||||
true_obs_data_ch1.restart();
|
||||
|
||||
std::cout << "Initial Doppler [Hz]=" << true_obs_data_ch0.doppler_l1_hz << " Initial code delay [Chips]=" << true_obs_data_ch0.prn_delay_chips << std::endl;
|
||||
|
||||
gnss_synchro_ch0.Acq_delay_samples = (GPS_L1_CA_CODE_LENGTH_CHIPS - true_obs_data_ch0.prn_delay_chips / GPS_L1_CA_CODE_LENGTH_CHIPS) * baseband_sampling_freq * GPS_L1_CA_CODE_PERIOD;
|
||||
gnss_synchro_ch0.Acq_doppler_hz = true_obs_data_ch0.doppler_l1_hz;
|
||||
gnss_synchro_ch0.Acq_samplestamp_samples = 0;
|
||||
|
||||
std::cout << "Initial Doppler [Hz]=" << true_obs_data_ch1.doppler_l1_hz << " Initial code delay [Chips]=" << true_obs_data_ch1.prn_delay_chips << std::endl;
|
||||
|
||||
gnss_synchro_ch1.Acq_delay_samples = (GPS_L1_CA_CODE_LENGTH_CHIPS - true_obs_data_ch1.prn_delay_chips / GPS_L1_CA_CODE_LENGTH_CHIPS) * baseband_sampling_freq * GPS_L1_CA_CODE_PERIOD;
|
||||
gnss_synchro_ch1.Acq_doppler_hz = true_obs_data_ch1.doppler_l1_hz;
|
||||
gnss_synchro_ch1.Acq_samplestamp_samples = 0;
|
||||
|
||||
//telemetry decoders
|
||||
std::shared_ptr<TelemetryDecoderInterface> tlm_ch0(new GpsL1CaTelemetryDecoder(config.get(), "TelemetryDecoder_1C",1, 1));
|
||||
std::shared_ptr<TelemetryDecoderInterface> tlm_ch1(new GpsL1CaTelemetryDecoder(config.get(), "TelemetryDecoder_1C",1, 1));
|
||||
|
||||
|
||||
|
||||
ASSERT_NO_THROW( {
|
||||
tlm_ch0->set_channel(0);
|
||||
tlm_ch1->set_channel(1);
|
||||
|
||||
tlm_ch0->set_satellite(Gnss_Satellite(std::string("GPS"),gnss_synchro_ch0.PRN));
|
||||
tlm_ch1->set_satellite(Gnss_Satellite(std::string("GPS"),gnss_synchro_ch1.PRN));
|
||||
}) << "Failure setting gnss_synchro." << std::endl;
|
||||
|
||||
boost::shared_ptr<HybridObservablesTest_tlm_msg_rx> tlm_msg_rx_ch1 = HybridObservablesTest_tlm_msg_rx_make();
|
||||
boost::shared_ptr<HybridObservablesTest_tlm_msg_rx> tlm_msg_rx_ch2 = HybridObservablesTest_tlm_msg_rx_make();
|
||||
|
||||
//Observables
|
||||
std::shared_ptr<ObservablesInterface> observables(new HybridObservables(config.get(), "Observables",2, 2));
|
||||
|
||||
|
||||
ASSERT_NO_THROW( {
|
||||
tracking_ch0->set_channel(gnss_synchro_ch0.Channel_ID);
|
||||
tracking_ch1->set_channel(gnss_synchro_ch1.Channel_ID);
|
||||
}) << "Failure setting channel." << std::endl;
|
||||
|
||||
ASSERT_NO_THROW( {
|
||||
tracking_ch0->set_gnss_synchro(&gnss_synchro_ch0);
|
||||
tracking_ch1->set_gnss_synchro(&gnss_synchro_ch1);
|
||||
}) << "Failure setting gnss_synchro." << std::endl;
|
||||
|
||||
ASSERT_NO_THROW( {
|
||||
tracking_ch0->connect(top_block);
|
||||
tracking_ch1->connect(top_block);
|
||||
}) << "Failure connecting tracking to the top_block." << std::endl;
|
||||
|
||||
ASSERT_NO_THROW( {
|
||||
std::string file = "./" + filename_raw_data;
|
||||
const char * file_name = file.c_str();
|
||||
gr::blocks::file_source::sptr file_source = gr::blocks::file_source::make(sizeof(int8_t), file_name, false);
|
||||
gr::blocks::interleaved_char_to_complex::sptr gr_interleaved_char_to_complex = gr::blocks::interleaved_char_to_complex::make();
|
||||
gr::blocks::null_sink::sptr sink_ch0 = gr::blocks::null_sink::make(sizeof(Gnss_Synchro));
|
||||
gr::blocks::null_sink::sptr sink_ch1 = gr::blocks::null_sink::make(sizeof(Gnss_Synchro));
|
||||
top_block->connect(file_source, 0, gr_interleaved_char_to_complex, 0);
|
||||
//ch0
|
||||
top_block->connect(gr_interleaved_char_to_complex, 0, tracking_ch0->get_left_block(), 0);
|
||||
top_block->connect(tracking_ch0->get_right_block(), 0, tlm_ch0->get_left_block(), 0);
|
||||
top_block->connect(tlm_ch0->get_right_block(), 0, observables->get_left_block(), 0);
|
||||
top_block->msg_connect(tracking_ch0->get_right_block(), pmt::mp("events"), msg_rx_ch0, pmt::mp("events"));
|
||||
//ch1
|
||||
top_block->connect(gr_interleaved_char_to_complex, 0, tracking_ch1->get_left_block(), 0);
|
||||
top_block->connect(tracking_ch1->get_right_block(), 0, tlm_ch1->get_left_block(), 0);
|
||||
top_block->connect(tlm_ch1->get_right_block(), 0, observables->get_left_block(), 1);
|
||||
top_block->msg_connect(tracking_ch1->get_right_block(), pmt::mp("events"), msg_rx_ch1, pmt::mp("events"));
|
||||
|
||||
top_block->connect(observables->get_right_block(), 0, sink_ch0, 0);
|
||||
top_block->connect(observables->get_right_block(), 1, sink_ch1, 0);
|
||||
|
||||
}) << "Failure connecting the blocks." << std::endl;
|
||||
|
||||
tracking_ch0->start_tracking();
|
||||
tracking_ch1->start_tracking();
|
||||
|
||||
EXPECT_NO_THROW( {
|
||||
gettimeofday(&tv, NULL);
|
||||
begin = tv.tv_sec * 1000000 + tv.tv_usec;
|
||||
top_block->run(); // Start threads and wait
|
||||
gettimeofday(&tv, NULL);
|
||||
end = tv.tv_sec * 1000000 + tv.tv_usec;
|
||||
}) << "Failure running the top_block." << std::endl;
|
||||
|
||||
//check results
|
||||
//load the true values
|
||||
|
||||
true_observables_reader true_observables;
|
||||
|
||||
ASSERT_NO_THROW({
|
||||
if ( true_observables.open_obs_file(std::string("./obs_out.bin")) == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
}) << "Failure opening true observables file" << std::endl;
|
||||
|
||||
long int nepoch = true_observables.num_epochs();
|
||||
|
||||
std::cout << "True observation epochs=" << nepoch << std::endl;
|
||||
arma::vec true_ch0_dist_m = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch0_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch0_Doppler_Hz = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch0_tow_s = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch1_dist_m = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch1_acc_carrier_phase_cycles = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch1_Doppler_Hz = arma::zeros(nepoch, 1);
|
||||
arma::vec true_ch1_tow_s = arma::zeros(nepoch, 1);
|
||||
|
||||
true_observables.restart();
|
||||
long int epoch_counter = 0;
|
||||
ASSERT_NO_THROW({
|
||||
while(true_observables.read_binary_obs())
|
||||
{
|
||||
if (round(true_observables.prn[0])!=gnss_synchro_ch0.PRN)
|
||||
{
|
||||
std::cout<<"True observables SV PRN do not match"<<round(true_observables.prn[1])<<std::endl;
|
||||
throw std::exception();
|
||||
}
|
||||
if (round(true_observables.prn[1])!=gnss_synchro_ch1.PRN)
|
||||
{
|
||||
std::cout<<"True observables SV PRN do not match "<<round(true_observables.prn[1])<<std::endl;
|
||||
throw std::exception();
|
||||
}
|
||||
true_ch0_tow_s(epoch_counter) = true_observables.gps_time_sec[0];
|
||||
true_ch0_dist_m(epoch_counter) = true_observables.dist_m[0];
|
||||
true_ch0_Doppler_Hz(epoch_counter) = true_observables.doppler_l1_hz[0];
|
||||
true_ch0_acc_carrier_phase_cycles(epoch_counter) = true_observables.acc_carrier_phase_l1_cycles[0];
|
||||
|
||||
true_ch1_tow_s(epoch_counter) = true_observables.gps_time_sec[1];
|
||||
true_ch1_dist_m(epoch_counter) = true_observables.dist_m[1];
|
||||
true_ch1_Doppler_Hz(epoch_counter) = true_observables.doppler_l1_hz[1];
|
||||
true_ch1_acc_carrier_phase_cycles(epoch_counter) = true_observables.acc_carrier_phase_l1_cycles[1];
|
||||
|
||||
epoch_counter++;
|
||||
}
|
||||
|
||||
});
|
||||
|
||||
//read measured values
|
||||
observables_dump_reader estimated_observables(2); //two channels
|
||||
ASSERT_NO_THROW({
|
||||
if (estimated_observables.open_obs_file(std::string("./observables.dat")) == false)
|
||||
{
|
||||
throw std::exception();
|
||||
};
|
||||
}) << "Failure opening dump observables file" << std::endl;
|
||||
|
||||
nepoch = estimated_observables.num_epochs();
|
||||
std::cout << "Measured observation epochs=" << nepoch << std::endl;
|
||||
|
||||
arma::vec measuded_ch0_RX_time_s = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch0_TOW_at_current_symbol_s = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch0_Carrier_Doppler_hz = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch0_Acc_carrier_phase_hz = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch0_Pseudorange_m = arma::zeros(nepoch, 1);
|
||||
|
||||
arma::vec measuded_ch1_RX_time_s = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch1_TOW_at_current_symbol_s = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch1_Carrier_Doppler_hz = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch1_Acc_carrier_phase_hz = arma::zeros(nepoch, 1);
|
||||
arma::vec measuded_ch1_Pseudorange_m = arma::zeros(nepoch, 1);
|
||||
|
||||
estimated_observables.restart();
|
||||
|
||||
epoch_counter = 0;
|
||||
while(estimated_observables.read_binary_obs())
|
||||
{
|
||||
measuded_ch0_RX_time_s(epoch_counter) = estimated_observables.RX_time[0];
|
||||
measuded_ch0_TOW_at_current_symbol_s(epoch_counter) =estimated_observables.TOW_at_current_symbol_s[0];
|
||||
measuded_ch0_Carrier_Doppler_hz(epoch_counter) = estimated_observables.Carrier_Doppler_hz[0];
|
||||
measuded_ch0_Acc_carrier_phase_hz(epoch_counter) = estimated_observables.Acc_carrier_phase_hz[0];
|
||||
measuded_ch0_Pseudorange_m(epoch_counter) = estimated_observables.Pseudorange_m[0];
|
||||
|
||||
measuded_ch1_RX_time_s(epoch_counter) = estimated_observables.RX_time[1];
|
||||
measuded_ch1_TOW_at_current_symbol_s(epoch_counter) =estimated_observables.TOW_at_current_symbol_s[1];
|
||||
measuded_ch1_Carrier_Doppler_hz(epoch_counter) = estimated_observables.Carrier_Doppler_hz[1];
|
||||
measuded_ch1_Acc_carrier_phase_hz(epoch_counter) = estimated_observables.Acc_carrier_phase_hz[1];
|
||||
measuded_ch1_Pseudorange_m(epoch_counter) = estimated_observables.Pseudorange_m[1];
|
||||
|
||||
epoch_counter++;
|
||||
}
|
||||
|
||||
//Cut measurement initial transitory of the measurements
|
||||
arma::uvec initial_meas_point = arma::find(measuded_ch0_RX_time_s >= true_ch0_tow_s(0), 1, "first");
|
||||
|
||||
measuded_ch0_RX_time_s = measuded_ch0_RX_time_s.subvec(initial_meas_point(0), measuded_ch0_RX_time_s.size() - 1);
|
||||
measuded_ch0_Pseudorange_m = measuded_ch0_Pseudorange_m.subvec(initial_meas_point(0), measuded_ch0_Pseudorange_m.size() - 1);
|
||||
measuded_ch1_RX_time_s = measuded_ch1_RX_time_s.subvec(initial_meas_point(0), measuded_ch1_RX_time_s.size() - 1);
|
||||
measuded_ch1_Pseudorange_m = measuded_ch1_Pseudorange_m.subvec(initial_meas_point(0), measuded_ch1_Pseudorange_m.size() - 1);
|
||||
|
||||
check_results(true_ch0_dist_m, true_ch1_dist_m, true_ch0_tow_s,
|
||||
measuded_ch0_Pseudorange_m,measuded_ch1_Pseudorange_m, measuded_ch0_RX_time_s);
|
||||
|
||||
std::cout << "Test completed in " << (end - begin) << " microseconds" << std::endl;
|
||||
}
|
||||
|
@ -312,8 +312,17 @@ void GpsL1CATelemetryDecoderTest::check_results(arma::vec true_time_s,
|
||||
|
||||
std::cout << std::setprecision(10) << "TLM TOW RMSE="
|
||||
<< rmse << ", mean=" << error_mean
|
||||
<< ", stdev=" << sqrt(error_var) << " (max,min)=" << max_error << "," << min_error << " [Chips]" << std::endl;
|
||||
<< ", stdev=" << sqrt(error_var)
|
||||
<< " (max,min)=" << max_error
|
||||
<< "," << min_error
|
||||
<< " [Seconds]" << std::endl;
|
||||
|
||||
ASSERT_LT(rmse, 0.2E-6);
|
||||
ASSERT_LT(error_mean, 0.2E-6);
|
||||
ASSERT_GT(error_mean, -0.2E-6);
|
||||
ASSERT_LT(error_var, 0.2E-6);
|
||||
ASSERT_LT(max_error, 0.5E-6);
|
||||
ASSERT_GT(min_error, -0.5E-6);
|
||||
}
|
||||
|
||||
TEST_F(GpsL1CATelemetryDecoderTest, ValidationOfResults)
|
||||
@ -322,7 +331,10 @@ TEST_F(GpsL1CATelemetryDecoderTest, ValidationOfResults)
|
||||
configure_generator();
|
||||
|
||||
// Generate signal raw signal samples and observations RINEX file
|
||||
generate_signal();
|
||||
if (FLAGS_disable_generator==false)
|
||||
{
|
||||
generate_signal();
|
||||
}
|
||||
|
||||
struct timeval tv;
|
||||
long long int begin = 0;
|
||||
@ -447,7 +459,7 @@ TEST_F(GpsL1CATelemetryDecoderTest, ValidationOfResults)
|
||||
epoch_counter = 0;
|
||||
while(tlm_dump.read_binary_obs())
|
||||
{
|
||||
tlm_timestamp_s(epoch_counter) = tlm_dump.Prn_timestamp_ms / 1000.0;
|
||||
tlm_timestamp_s(epoch_counter) = (double)tlm_dump.Tracking_sample_counter/(double)baseband_sampling_freq;
|
||||
tlm_TOW_at_Preamble(epoch_counter) = tlm_dump.d_TOW_at_Preamble;
|
||||
tlm_tow_s(epoch_counter) = tlm_dump.TOW_at_current_symbol;
|
||||
epoch_counter++;
|
||||
|
@ -331,7 +331,10 @@ TEST_F(GpsL1CADllPllTrackingTest, ValidationOfResults)
|
||||
configure_generator();
|
||||
|
||||
// Generate signal raw signal samples and observations RINEX file
|
||||
generate_signal();
|
||||
if (FLAGS_disable_generator==false)
|
||||
{
|
||||
generate_signal();
|
||||
}
|
||||
|
||||
struct timeval tv;
|
||||
long long int begin = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user