mirror of
https://github.com/gnss-sdr/gnss-sdr
synced 2024-12-12 19:20:32 +00:00
Merge branch 'vladisslav2011-fake_multichannel' into next
This commit is contained in:
commit
9c6a312226
@ -0,0 +1,281 @@
|
||||
; This is a GNSS-SDR configuration file
|
||||
; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/
|
||||
; SPDX-License-Identifier: GPL-3.0-or-later
|
||||
; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors)
|
||||
|
||||
; You can define your own receiver and invoke it by doing
|
||||
; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf
|
||||
;
|
||||
|
||||
[GNSS-SDR]
|
||||
|
||||
;######### GLOBAL OPTIONS ##################
|
||||
GNSS-SDR.internal_fs_sps=8000000
|
||||
GNSS-SDR.Beidou_banned_prns=56,57,58
|
||||
|
||||
|
||||
;######### SIGNAL_SOURCE CONFIG ############
|
||||
SignalSource.implementation=Osmosdr_Signal_Source
|
||||
SignalSource.item_type=gr_complex
|
||||
SignalSource.sampling_frequency=56000000
|
||||
SignalSource.freq=1584000000
|
||||
SignalSource.osmosdr_args=uhd,type=b200,num_recv_frames=256
|
||||
SignalSource.gain=50
|
||||
SignalSource.antenna=TX/RX
|
||||
SignalSource.if_bw=56000000
|
||||
SignalSource.AGC_enabled=false
|
||||
SignalSource.samples=0
|
||||
SignalSource.repeat=false
|
||||
SignalSource.RF_channels=3
|
||||
SignalSource.enable_throttle_control=false
|
||||
SignalSource.dump=false
|
||||
|
||||
|
||||
|
||||
;######### SIGNAL_CONDITIONER CONFIG ############
|
||||
SignalConditioner0.implementation=Signal_Conditioner
|
||||
SignalConditioner1.implementation=Signal_Conditioner
|
||||
SignalConditioner2.implementation=Signal_Conditioner
|
||||
|
||||
;######### DATA_TYPE_ADAPTER CONFIG ############
|
||||
DataTypeAdapter0.implementation=Pass_Through
|
||||
DataTypeAdapter1.implementation=Pass_Through
|
||||
DataTypeAdapter2.implementation=Pass_Through
|
||||
|
||||
;######### INPUT_FILTER CONFIG ############
|
||||
InputFilter0.implementation=Freq_Xlating_Fir_Filter
|
||||
InputFilter0.decimation_factor=7
|
||||
InputFilter0.input_item_type=gr_complex
|
||||
InputFilter0.output_item_type=gr_complex
|
||||
InputFilter0.taps_item_type=float
|
||||
InputFilter0.filter_type=lowpass
|
||||
InputFilter0.bw=7000000
|
||||
InputFilter0.tw=500000
|
||||
InputFilter0.IF=-22902000
|
||||
InputFilter0.sampling_frequency=56000000
|
||||
InputFilter0.dump=false
|
||||
InputFilter0.dump_filename=../data/input_filter.dat
|
||||
|
||||
;######### INPUT_FILTER CONFIG ############
|
||||
InputFilter1.implementation=Freq_Xlating_Fir_Filter
|
||||
InputFilter1.decimation_factor=7
|
||||
InputFilter1.input_item_type=gr_complex
|
||||
InputFilter1.output_item_type=gr_complex
|
||||
InputFilter1.taps_item_type=float
|
||||
InputFilter1.filter_type=lowpass
|
||||
InputFilter1.bw=7000000
|
||||
InputFilter1.tw=500000
|
||||
InputFilter1.IF=-8580000
|
||||
InputFilter1.sampling_frequency=56000000
|
||||
InputFilter1.dump=false
|
||||
InputFilter1.dump_filename=../data/input_filter.dat
|
||||
|
||||
;######### INPUT_FILTER CONFIG ############
|
||||
InputFilter2.implementation=Freq_Xlating_Fir_Filter
|
||||
InputFilter2.decimation_factor=7
|
||||
InputFilter2.input_item_type=gr_complex
|
||||
InputFilter2.output_item_type=gr_complex
|
||||
InputFilter2.taps_item_type=float
|
||||
InputFilter2.filter_type=lowpass
|
||||
InputFilter2.bw=7000000
|
||||
InputFilter2.tw=500000
|
||||
InputFilter2.IF=18000000
|
||||
InputFilter2.sampling_frequency=56000000
|
||||
InputFilter2.dump=false
|
||||
InputFilter2.dump_filename=../data/input_filter.dat
|
||||
|
||||
;######### RESAMPLER CONFIG ############
|
||||
Resampler0.implementation=Pass_Through
|
||||
Resampler1.implementation=Pass_Through
|
||||
Resampler2.implementation=Pass_Through
|
||||
|
||||
;######### CHANNELS GLOBAL CONFIG ############
|
||||
Channels_1B.count=10
|
||||
Channels_1C.count=10
|
||||
Channels_B1.count=14
|
||||
Channels_1G.count=8
|
||||
|
||||
Channels_1B.RF_channel_ID=1
|
||||
Channels_1C.RF_channel_ID=1
|
||||
Channels_B1.RF_channel_ID=0
|
||||
Channels_1G.RF_channel_ID=2
|
||||
|
||||
|
||||
Channels.in_acquisition=2
|
||||
|
||||
;######### ACQUISITION BEIDOU CONFIG ############
|
||||
Acquisition_B1.implementation=BEIDOU_B1I_PCPS_Acquisition
|
||||
Acquisition_B1.item_type=gr_complex
|
||||
Acquisition_B1.coherent_integration_time_ms=2
|
||||
;Acquisition_B1.max_dwells=2
|
||||
;Acquisition_B1.pfa=0.02
|
||||
Acquisition_B1.pfa=0.000002
|
||||
Acquisition_B1.doppler_max=6000
|
||||
Acquisition_B1.doppler_step=100
|
||||
Acquisition_B1.dump=false
|
||||
Acquisition_B1.dump_filename=./bds_acq
|
||||
;Acquisition_B1.blocking=true
|
||||
Acquisition_B1.bit_transition_flag = false;
|
||||
|
||||
;######### ACQUISITION GPS CONFIG ############
|
||||
Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
|
||||
Acquisition_1C.item_type=gr_complex
|
||||
Acquisition_1C.coherent_integration_time_ms=1
|
||||
Acquisition_1C.pfa=0.015
|
||||
Acquisition_1C.doppler_max=6000
|
||||
Acquisition_1C.doppler_step=200
|
||||
Acquisition_1C.max_dwells=4
|
||||
;Acquisition_1C.blocking=true
|
||||
Acquisition_1C.dump=false
|
||||
Acquisition_1C.dump_filename=./acq_dump.dat
|
||||
|
||||
;######### ACQUISITION GALILEO CONFIG ############
|
||||
Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition
|
||||
Acquisition_1B.coherent_integration_time_ms=2
|
||||
;Acquisition_1B.pfa=0.000008
|
||||
Acquisition_1B.pfa=0.025
|
||||
Acquisition_1B.doppler_max=6000
|
||||
Acquisition_1B.doppler_step=200
|
||||
Acquisition_1B.max_dwells=4
|
||||
;Acquisition_1B.repeat_satellite=true
|
||||
Acquisition_1B.cboc=true
|
||||
;Acquisition_1B.blocking=true
|
||||
Acquisition_1B.dump=false
|
||||
Acquisition_1B.dump_filename=./acq_dump.dat
|
||||
|
||||
;######### ACQUISITION GLONASS CONFIG ############
|
||||
Acquisition_1G.implementation=GLONASS_L1_CA_PCPS_Acquisition
|
||||
Acquisition_1G.item_type=gr_complex
|
||||
Acquisition_1G.coherent_integration_time_ms=1
|
||||
Acquisition_1G.max_dwells=4
|
||||
Acquisition_1G.pfa=0.02
|
||||
Acquisition_1G.doppler_max=6000
|
||||
Acquisition_1G.doppler_step=100
|
||||
Acquisition_1G.dump=false
|
||||
Acquisition_1G.dump_filename=./G1_acq
|
||||
|
||||
|
||||
|
||||
;######### TRACKING BEIDOU CONFIG ############
|
||||
Tracking_B1.implementation=BEIDOU_B1I_DLL_PLL_Tracking
|
||||
Tracking_B1.item_type=gr_complex
|
||||
Tracking_B1.extend_correlation_symbols=10
|
||||
Tracking_B1.pll_bw_hz=50.0
|
||||
Tracking_B1.dll_bw_hz=2.00
|
||||
Tracking_B1.pll_bw_narrow_hz=15.0
|
||||
Tracking_B1.dll_bw_narrow_hz=1.50
|
||||
;Tracking_B1.cn0_min=20
|
||||
;Tracking_B1.fll_bw_hz=20
|
||||
;Tracking_B1.enable_fll_pull_in=true
|
||||
;Tracking_B1.enable_fll_steady_state=false
|
||||
Tracking_B1.dump=false
|
||||
Tracking_B1.dump_filename=./epl_tracking_ch_
|
||||
|
||||
;######### TRACKING GPS CONFIG ############
|
||||
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
|
||||
Tracking_1C.item_type=gr_complex
|
||||
Tracking_1C.extend_correlation_symbols=10
|
||||
Tracking_1C.early_late_space_chips=0.5
|
||||
Tracking_1C.early_late_space_narrow_chips=0.15
|
||||
Tracking_1C.pll_bw_hz=30.0
|
||||
Tracking_1C.dll_bw_hz=2.0
|
||||
Tracking_1C.pll_bw_narrow_hz=10.0
|
||||
Tracking_1C.dll_bw_narrow_hz=1.50
|
||||
Tracking_1C.fll_bw_hz=10
|
||||
Tracking_1C.enable_fll_pull_in=true
|
||||
Tracking_1C.enable_fll_steady_state=false
|
||||
Tracking_1C.dump=false
|
||||
Tracking_1C.dump_filename=tracking_ch_
|
||||
|
||||
;######### TRACKING GALILEO CONFIG ############
|
||||
Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking
|
||||
Tracking_1B.extend_correlation_symbols=4
|
||||
Tracking_1B.item_type=gr_complex
|
||||
Tracking_1B.pll_bw_hz=30.0
|
||||
Tracking_1B.dll_bw_hz=2.0
|
||||
Tracking_1B.pll_bw_narrow_hz=20.0
|
||||
Tracking_1B.dll_bw_narrow_hz=1.50
|
||||
Tracking_1B.track_pilot=true
|
||||
Tracking_1B.enable_fll_pull_in=true;
|
||||
Tracking_1B.enable_fll_steady_state=false
|
||||
Tracking_1B.fll_bw_hz=20
|
||||
|
||||
;######### TRACKING GLONASS CONFIG ############
|
||||
Tracking_1G.implementation=GLONASS_L1_CA_DLL_PLL_C_Aid_Tracking
|
||||
Tracking_1G.item_type=gr_complex
|
||||
Tracking_1G.pll_bw_hz=40
|
||||
Tracking_1G.dll_bw_hz=2.5
|
||||
Tracking_1G.extend_correlation_ms=1
|
||||
Tracking_1G.pll_bw_narrow_hz=20
|
||||
Tracking_1G.dll_bw_narrow_hz=1.5
|
||||
Tracking_1G.dump=false
|
||||
Tracking_1G.dump_filename=./epl_tracking_ch_
|
||||
|
||||
|
||||
|
||||
;######### TELEMETRY DECODER BEIDOU CONFIG ############
|
||||
TelemetryDecoder_B1.implementation=BEIDOU_B1I_Telemetry_Decoder
|
||||
TelemetryDecoder_B1.dump=false
|
||||
|
||||
;######### TELEMETRY DECODER GPS CONFIG ############
|
||||
TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder
|
||||
TelemetryDecoder_1C.dump=false
|
||||
|
||||
;######### TELEMETRY DECODER GALILEO E1B CONFIG ############
|
||||
TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder
|
||||
TelemetryDecoder_1B.dump=false
|
||||
|
||||
;######### TELEMETRY DECODER GLONASS CONFIG ############
|
||||
TelemetryDecoder_1G.implementation=GLONASS_L1_CA_Telemetry_Decoder
|
||||
TelemetryDecoder_1G.dump=false
|
||||
|
||||
|
||||
;######### OBSERVABLES CONFIG ############
|
||||
Observables.implementation=Hybrid_Observables
|
||||
Observables.dump=false
|
||||
Observables.dump_filename=./observables.dat
|
||||
|
||||
;######### PVT CONFIG ############
|
||||
PVT.implementation=RTKLIB_PVT
|
||||
PVT.threshold_reject_GDOP=100
|
||||
PVT.elevation_mask=3
|
||||
PVT.raim_fde=1
|
||||
PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic
|
||||
PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX
|
||||
PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad
|
||||
PVT.output_rate_ms=100
|
||||
PVT.display_rate_ms=500
|
||||
PVT.enable_rx_clock_correction=true
|
||||
PVT.flag_rtcm_server=true
|
||||
PVT.flag_rtcm_tty_port=false
|
||||
PVT.rtcm_dump_devname=/dev/pts/1
|
||||
PVT.rtcm_tcp_port=2101
|
||||
PVT.rtcm_MT1019_rate_ms=5000
|
||||
PVT.rtcm_MT1077_rate_ms=1000
|
||||
PVT.rinex_version=2
|
||||
PVT.flag_nmea_tty_port=true
|
||||
PVT.nmea_dump_devname=/dev/pts/3
|
||||
|
||||
; To use gpsd with GNSS-SDR
|
||||
; 1. run socat -d -d pty,raw,echo=0 pty,raw,echo=0
|
||||
; 2. Set PVT.nmea_dump_devname to first PTY from socat output
|
||||
; 3. run gpsd -b -n -N /dev/pts/4
|
||||
; where /dev/pts/4 is the second PTY from socat output
|
||||
; 4. run some gpsd client (xgps or other)
|
||||
|
||||
|
||||
|
||||
PVT.enable_monitor=true
|
||||
PVT.monitor_client_addresses=127.0.0.1
|
||||
PVT.monitor_udp_port=1111
|
||||
|
||||
Monitor.enable_monitor=true
|
||||
Monitor.decimation_factor=4
|
||||
Monitor.client_addresses=127.0.0.1
|
||||
Monitor.udp_port=1112
|
||||
|
||||
;AcquisitionMonitor.enable_monitor=true
|
||||
AcquisitionMonitor.client_addresses=127.0.0.1
|
||||
AcquisitionMonitor.udp_port=1112
|
||||
|
||||
|
@ -0,0 +1,237 @@
|
||||
; This is a GNSS-SDR configuration file
|
||||
; The configuration API is described at https://gnss-sdr.org/docs/sp-blocks/
|
||||
; SPDX-License-Identifier: GPL-3.0-or-later
|
||||
; SPDX-FileCopyrightText: (C) 2010-2020 (see AUTHORS file for a list of contributors)
|
||||
|
||||
; You can define your own receiver and invoke it by doing
|
||||
; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf
|
||||
;
|
||||
|
||||
[GNSS-SDR]
|
||||
|
||||
;######### GLOBAL OPTIONS ##################
|
||||
GNSS-SDR.internal_fs_sps=4000000
|
||||
GNSS-SDR.Beidou_banned_prns=56,57,58
|
||||
|
||||
|
||||
;######### SIGNAL_SOURCE CONFIG ############
|
||||
SignalSource.implementation=Osmosdr_Signal_Source
|
||||
SignalSource.item_type=gr_complex
|
||||
SignalSource.sampling_frequency=20000000
|
||||
SignalSource.freq=1567420000
|
||||
SignalSource.if_bw=18000000
|
||||
;# Next line enables the internal HackRF One bias (3.3 VDC)
|
||||
SignalSource.osmosdr_args=hackrf=0,bias=1,buffers=256
|
||||
SignalSource.gain=0
|
||||
SignalSource.rf_gain=40
|
||||
SignalSource.if_gain=40
|
||||
SignalSource.AGC_enabled=false
|
||||
SignalSource.samples=0
|
||||
SignalSource.repeat=false
|
||||
SignalSource.RF_channels=2
|
||||
SignalSource.enable_throttle_control=false
|
||||
SignalSource.dump=false
|
||||
|
||||
|
||||
|
||||
;######### SIGNAL_CONDITIONER CONFIG ############
|
||||
SignalConditioner0.implementation=Signal_Conditioner
|
||||
SignalConditioner1.implementation=Signal_Conditioner
|
||||
|
||||
;######### DATA_TYPE_ADAPTER CONFIG ############
|
||||
DataTypeAdapter0.implementation=Pass_Through
|
||||
DataTypeAdapter1.implementation=Pass_Through
|
||||
|
||||
;######### INPUT_FILTER CONFIG ############
|
||||
InputFilter0.implementation=Freq_Xlating_Fir_Filter
|
||||
;InputFilter0.implementation=Pass_Through
|
||||
InputFilter0.decimation_factor=5
|
||||
InputFilter0.input_item_type=gr_complex
|
||||
InputFilter0.output_item_type=gr_complex
|
||||
InputFilter0.taps_item_type=float
|
||||
InputFilter0.filter_type=lowpass
|
||||
InputFilter0.bw=3000000
|
||||
InputFilter0.tw=1000000
|
||||
InputFilter0.IF=-6322000
|
||||
InputFilter0.sampling_frequency=20000000
|
||||
InputFilter0.dump=false
|
||||
InputFilter0.dump_filename=../data/input_filter.dat
|
||||
|
||||
;######### INPUT_FILTER CONFIG ############
|
||||
InputFilter1.implementation=Freq_Xlating_Fir_Filter
|
||||
;InputFilter1.implementation=Pass_Through
|
||||
InputFilter1.decimation_factor=5
|
||||
InputFilter1.input_item_type=gr_complex
|
||||
InputFilter1.output_item_type=gr_complex
|
||||
InputFilter1.taps_item_type=float
|
||||
InputFilter1.filter_type=lowpass
|
||||
InputFilter1.bw=3000000
|
||||
InputFilter1.tw=1000000
|
||||
InputFilter1.IF=8000000
|
||||
InputFilter1.sampling_frequency=20000000
|
||||
InputFilter1.dump=false
|
||||
InputFilter1.dump_filename=../data/input_filter.dat
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
;######### RESAMPLER CONFIG ############
|
||||
Resampler0.implementation=Pass_Through
|
||||
Resampler1.implementation=Pass_Through
|
||||
|
||||
;######### CHANNELS GLOBAL CONFIG ############
|
||||
Channels_1B.count=10
|
||||
Channels_1C.count=10
|
||||
Channels_B1.count=14
|
||||
|
||||
Channels_1B.RF_channel_ID=1
|
||||
Channels_1C.RF_channel_ID=1
|
||||
Channels_B1.RF_channel_ID=0
|
||||
|
||||
|
||||
|
||||
Channels.in_acquisition=10
|
||||
|
||||
;######### ACQUISITION BEIDOU CONFIG ############
|
||||
Acquisition_B1.implementation=BEIDOU_B1I_PCPS_Acquisition
|
||||
Acquisition_B1.item_type=gr_complex
|
||||
Acquisition_B1.coherent_integration_time_ms=2
|
||||
;Acquisition_B1.max_dwells=2
|
||||
;Acquisition_B1.pfa=0.02
|
||||
Acquisition_B1.pfa=0.000002
|
||||
Acquisition_B1.doppler_max=3800
|
||||
Acquisition_B1.doppler_step=100
|
||||
Acquisition_B1.dump=false
|
||||
Acquisition_B1.dump_filename=./bds_acq
|
||||
;Acquisition_B1.blocking=true
|
||||
Acquisition_B1.bit_transition_flag = false;
|
||||
|
||||
;######### ACQUISITION GPS CONFIG ############
|
||||
Acquisition_1C.implementation=GPS_L1_CA_PCPS_Acquisition
|
||||
Acquisition_1C.item_type=gr_complex
|
||||
Acquisition_1C.coherent_integration_time_ms=1
|
||||
Acquisition_1C.pfa=0.015
|
||||
Acquisition_1C.doppler_max=5000
|
||||
Acquisition_1C.doppler_step=200
|
||||
Acquisition_1C.max_dwells=4
|
||||
;Acquisition_1C.blocking=true
|
||||
Acquisition_1C.dump=false
|
||||
Acquisition_1C.dump_filename=./acq_dump.dat
|
||||
|
||||
;######### ACQUISITION GALILEO CONFIG ############
|
||||
Acquisition_1B.implementation=Galileo_E1_PCPS_Ambiguous_Acquisition
|
||||
Acquisition_1B.coherent_integration_time_ms=2
|
||||
;Acquisition_1B.pfa=0.000008
|
||||
Acquisition_1B.pfa=0.025
|
||||
Acquisition_1B.doppler_max=5000
|
||||
Acquisition_1B.doppler_step=200
|
||||
Acquisition_1B.max_dwells=4
|
||||
;Acquisition_1B.repeat_satellite=true
|
||||
Acquisition_1B.cboc=true
|
||||
;Acquisition_1B.blocking=true
|
||||
Acquisition_1B.dump=false
|
||||
Acquisition_1B.dump_filename=./acq_dump.dat
|
||||
|
||||
|
||||
|
||||
|
||||
;######### TRACKING BEIDOU CONFIG ############
|
||||
Tracking_B1.implementation=BEIDOU_B1I_DLL_PLL_Tracking
|
||||
Tracking_B1.item_type=gr_complex
|
||||
Tracking_B1.extend_correlation_symbols=10
|
||||
Tracking_B1.pll_bw_hz=30.0
|
||||
Tracking_B1.dll_bw_hz=2.00
|
||||
Tracking_B1.pll_bw_narrow_hz=15.0
|
||||
Tracking_B1.dll_bw_narrow_hz=0.50
|
||||
;Tracking_B1.cn0_min=20
|
||||
Tracking_B1.fll_bw_hz=20
|
||||
Tracking_B1.enable_fll_pull_in=true
|
||||
Tracking_B1.enable_fll_steady_state=false
|
||||
Tracking_B1.dump=false
|
||||
Tracking_B1.dump_filename=./epl_tracking_ch_
|
||||
|
||||
;######### TRACKING GPS CONFIG ############
|
||||
Tracking_1C.implementation=GPS_L1_CA_DLL_PLL_Tracking
|
||||
Tracking_1C.item_type=gr_complex
|
||||
Tracking_1C.extend_correlation_symbols=10
|
||||
Tracking_1C.early_late_space_chips=0.5
|
||||
Tracking_1C.early_late_space_narrow_chips=0.15
|
||||
Tracking_1C.pll_bw_hz=30.0
|
||||
Tracking_1C.dll_bw_hz=2.0
|
||||
Tracking_1C.pll_bw_narrow_hz=10.0
|
||||
Tracking_1C.dll_bw_narrow_hz=0.50
|
||||
Tracking_1C.fll_bw_hz=10
|
||||
Tracking_1C.enable_fll_pull_in=true
|
||||
Tracking_1C.enable_fll_steady_state=false
|
||||
Tracking_1C.dump=false
|
||||
Tracking_1C.dump_filename=tracking_ch_
|
||||
|
||||
;######### TRACKING GALILEO CONFIG ############
|
||||
Tracking_1B.implementation=Galileo_E1_DLL_PLL_VEML_Tracking
|
||||
Tracking_1B.extend_correlation_symbols=4
|
||||
Tracking_1B.item_type=gr_complex
|
||||
Tracking_1B.pll_bw_hz=30.0
|
||||
Tracking_1B.dll_bw_hz=2.0
|
||||
Tracking_1B.pll_bw_narrow_hz=20.0
|
||||
Tracking_1B.dll_bw_narrow_hz=0.50
|
||||
Tracking_1B.track_pilot=true
|
||||
Tracking_1B.enable_fll_pull_in=true;
|
||||
Tracking_1B.enable_fll_steady_state=false
|
||||
Tracking_1B.fll_bw_hz=20
|
||||
|
||||
|
||||
;######### TELEMETRY DECODER BEIDOU CONFIG ############
|
||||
TelemetryDecoder_B1.implementation=BEIDOU_B1I_Telemetry_Decoder
|
||||
TelemetryDecoder_B1.dump=false
|
||||
|
||||
;######### TELEMETRY DECODER GPS CONFIG ############
|
||||
TelemetryDecoder_1C.implementation=GPS_L1_CA_Telemetry_Decoder
|
||||
TelemetryDecoder_1C.dump=false
|
||||
|
||||
;######### TELEMETRY DECODER GALILEO E1B CONFIG ############
|
||||
TelemetryDecoder_1B.implementation=Galileo_E1B_Telemetry_Decoder
|
||||
TelemetryDecoder_1B.dump=false
|
||||
|
||||
|
||||
|
||||
;######### OBSERVABLES CONFIG ############
|
||||
Observables.implementation=Hybrid_Observables
|
||||
Observables.dump=false
|
||||
Observables.dump_filename=./observables.dat
|
||||
|
||||
;######### PVT CONFIG ############
|
||||
PVT.implementation=RTKLIB_PVT
|
||||
PVT.threshold_reject_GDOP=100
|
||||
PVT.elevation_mask=4
|
||||
PVT.positioning_mode=Single ; options: Single, Static, Kinematic, PPP_Static, PPP_Kinematic
|
||||
PVT.iono_model=Broadcast ; options: OFF, Broadcast, SBAS, Iono-Free-LC, Estimate_STEC, IONEX
|
||||
PVT.trop_model=Saastamoinen ; options: OFF, Saastamoinen, SBAS, Estimate_ZTD, Estimate_ZTD_Grad
|
||||
PVT.output_rate_ms=100
|
||||
PVT.display_rate_ms=500
|
||||
PVT.enable_rx_clock_correction=true
|
||||
PVT.flag_rtcm_server=true
|
||||
PVT.flag_rtcm_tty_port=false
|
||||
PVT.rtcm_dump_devname=/dev/pts/1
|
||||
PVT.rtcm_tcp_port=2101
|
||||
PVT.rtcm_MT1019_rate_ms=5000
|
||||
PVT.rtcm_MT1077_rate_ms=1000
|
||||
PVT.rinex_version=2
|
||||
PVT.flag_nmea_tty_port=true
|
||||
PVT.nmea_dump_devname=/dev/pts/3
|
||||
|
||||
|
||||
PVT.enable_monitor=true
|
||||
PVT.monitor_client_addresses=127.0.0.1
|
||||
PVT.monitor_udp_port=1111
|
||||
|
||||
Monitor.enable_monitor=true
|
||||
Monitor.decimation_factor=4
|
||||
Monitor.client_addresses=127.0.0.1
|
||||
Monitor.udp_port=1112
|
||||
|
||||
AcquisitionMonitor.enable_monitor=true
|
||||
AcquisitionMonitor.client_addresses=127.0.0.1
|
||||
AcquisitionMonitor.udp_port=1112
|
||||
|
||||
|
@ -17,6 +17,10 @@ All notable changes to GNSS-SDR will be documented in this file.
|
||||
### Improvements in Interoperability:
|
||||
|
||||
- Improved error handling in UDP connections.
|
||||
- Make it possible to receive multiple constellations using a single channel
|
||||
wideband device (HackRF/LimeSDR/USRP). Demonstration:
|
||||
https://www.youtube.com/watch?v=ZQs2sFchJ6w
|
||||
https://www.youtube.com/watch?v=HnZkKj9a-QM
|
||||
|
||||
### Improvements in Portability:
|
||||
|
||||
|
@ -264,7 +264,7 @@ void GNSSFlowgraph::init()
|
||||
}
|
||||
|
||||
/*
|
||||
* Instantiate the receiver av message monitor block, if required
|
||||
* Instantiate the receiver nav message monitor block, if required
|
||||
*/
|
||||
enable_navdata_monitor_ = configuration_->property("NavDataMonitor.enable_monitor", false);
|
||||
if (enable_navdata_monitor_)
|
||||
@ -966,7 +966,7 @@ int GNSSFlowgraph::connect_signal_sources_to_signal_conditioners()
|
||||
}
|
||||
else
|
||||
{
|
||||
if (j == 0)
|
||||
if (j == 0 || !src->get_right_block(j))
|
||||
{
|
||||
// RF_channel 0 backward compatibility with single channel sources
|
||||
LOG(INFO) << "connecting sig_source_ " << i << " stream " << 0 << " to conditioner " << signal_conditioner_ID;
|
||||
|
Loading…
Reference in New Issue
Block a user