Merge remote-tracking branch 'origin/modern_factory' into next

Conflicts:
	src/core/receiver/control_thread.h
This commit is contained in:
Carles Fernandez 2014-04-26 19:12:19 +02:00
commit 949c9fa972
18 changed files with 666 additions and 947 deletions

View File

@ -1,398 +0,0 @@
; Default configuration file
; You can define your own receiver and invoke it by doing
; gnss-sdr --config_file=my_GNSS_SDR_configuration.conf
;
[GNSS-SDR]
;######### GLOBAL OPTIONS ##################
;internal_fs_hz: Internal signal sampling frequency after the signal conditioning stage [Hz].
GNSS-SDR.internal_fs_hz=4000000
;######### CONTROL_THREAD CONFIG ############
ControlThread.wait_for_flowgraph=false
;######### SUPL RRLP GPS assistance configuration #####
GNSS-SDR.SUPL_gps_enabled=false
GNSS-SDR.SUPL_read_gps_assistance_xml=true
GNSS-SDR.SUPL_gps_ephemeris_server=supl.nokia.com
GNSS-SDR.SUPL_gps_ephemeris_port=7275
GNSS-SDR.SUPL_gps_acquisition_server=supl.google.com
GNSS-SDR.SUPL_gps_acquisition_port=7275
GNSS-SDR.SUPL_MCC=244
GNSS-SDR.SUPL_MNS=5
GNSS-SDR.SUPL_LAC=0x59e2
GNSS-SDR.SUPL_CI=0x31b0
;######### SIGNAL_SOURCE CONFIG ############
;#implementation: Use [File_Signal_Source] or [UHD_Signal_Source] or [GN3S_Signal_Source] (experimental)
SignalSource.implementation=File_Signal_Source
;#filename: path to file with the captured GNSS signal samples to be processed
SignalSource.filename=/media/DATALOGGER/Agilent GPS Generator/cap2/agilent_cap2.dat
;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version.
SignalSource.item_type=gr_complex
;#sampling_frequency: Original Signal sampling frequency in [Hz]
SignalSource.sampling_frequency=4000000
;#freq: RF front-end center frequency in [Hz]
SignalSource.freq=1575420000
;#gain: Front-end Gain in [dB]
SignalSource.gain=60
;#subdevice: UHD subdevice specification (for USRP1 use A:0 or B:0)
SignalSource.subdevice=B:0
;#samples: Number of samples to be processed. Notice that 0 indicates the entire file.
SignalSource.samples=0
;#repeat: Repeat the processing file. Disable this option in this version
SignalSource.repeat=false
;#dump: Dump the Signal source data to a file. Disable this option in this version
SignalSource.dump=false
SignalSource.dump_filename=../data/signal_source.dat
;#enable_throttle_control: Enabling this option tells the signal source to keep the delay between samples in post processing.
; it helps to not overload the CPU, but the processing time will be longer.
SignalSource.enable_throttle_control=false
;######### SIGNAL_CONDITIONER CONFIG ############
;## It holds blocks to change data type, filter and resample input data.
;#implementation: Use [Pass_Through] or [Signal_Conditioner]
;#[Pass_Through] disables this block and the [DataTypeAdapter], [InputFilter] and [Resampler] blocks
;#[Signal_Conditioner] enables this block. Then you have to configure [DataTypeAdapter], [InputFilter] and [Resampler] blocks
;SignalConditioner.implementation=Signal_Conditioner
SignalConditioner.implementation=Pass_Through
;######### DATA_TYPE_ADAPTER CONFIG ############
;## Changes the type of input data. Please disable it in this version.
;#implementation: [Pass_Through] disables this block
DataTypeAdapter.implementation=Pass_Through
;######### INPUT_FILTER CONFIG ############
;## Filter the input data. Can be combined with frequency translation for IF signals
;#implementation: Use [Pass_Through] or [Fir_Filter] or [Freq_Xlating_Fir_Filter]
;#[Pass_Through] disables this block
;#[Fir_Filter] enables a FIR Filter
;#[Freq_Xlating_Fir_Filter] enables FIR filter and a composite frequency translation that shifts IF down to zero Hz.
;InputFilter.implementation=Fir_Filter
;InputFilter.implementation=Freq_Xlating_Fir_Filter
InputFilter.implementation=Pass_Through
;#dump: Dump the filtered data to a file.
InputFilter.dump=false
;#dump_filename: Log path and filename.
InputFilter.dump_filename=../data/input_filter.dat
;#The following options are used in the filter design of Fir_Filter and Freq_Xlating_Fir_Filter implementation.
;#These options are based on parameters of gnuradio's function: gr_remez.
;#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=gr_complex
;#outut_item_type: Type and resolution for output filtered signal samples. Use only gr_complex in this version.
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
;#number_of_taps: Number of taps in the filter. Increasing this parameter increases the processing time
InputFilter.number_of_taps=5
;#number_of _bands: Number of frequency bands in the filter.
InputFilter.number_of_bands=2
;#bands: frequency at the band edges [ b1 e1 b2 e2 b3 e3 ...].
;#Frequency is in the range [0, 1], with 1 being the Nyquist frequency (Fs/2)
;#The number of band_begin and band_end elements must match the number of bands
InputFilter.band1_begin=0.0
InputFilter.band1_end=0.45
InputFilter.band2_begin=0.55
InputFilter.band2_end=1.0
;#ampl: desired amplitude at the band edges [ a(b1) a(e1) a(b2) a(e2) ...].
;#The number of ampl_begin and ampl_end elements must match the number of bands
InputFilter.ampl1_begin=1.0
InputFilter.ampl1_end=1.0
InputFilter.ampl2_begin=0.0
InputFilter.ampl2_end=0.0
;#band_error: weighting applied to each band (usually 1).
;#The number of band_error elements must match the number of bands
InputFilter.band1_error=1.0
InputFilter.band2_error=1.0
;#filter_type: one of "bandpass", "hilbert" or "differentiator"
InputFilter.filter_type=bandpass
;#grid_density: determines how accurately the filter will be constructed.
;The minimum value is 16; higher values are slower to compute the filter.
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.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. Use only gr_complex in this version.
Resampler.item_type=gr_complex
;#sample_freq_in: the sample frequency of the input signal
Resampler.sample_freq_in=8000000
;#sample_freq_out: the desired sample frequency of the output signal
Resampler.sample_freq_out=4000000
;######### CHANNELS GLOBAL CONFIG ############
;#count: Number of available satellite channels.
Channels.count=6
;#in_acquisition: Number of channels simultaneously acquiring
Channels.in_acquisition=1
;#system: GPS, GLONASS, Galileo, SBAS or Compass
;#if the option is disabled by default is assigned GPS
Channel.system=GPS
;#signal:
;# "1C" GPS L1 C/A
;# "1P" GPS L1 P
;# "1W" GPS L1 Z-tracking and similar (AS on)
;# "1Y" GPS L1 Y
;# "1M" GPS L1 M
;# "1N" GPS L1 codeless
;# "2C" GPS L2 C/A
;# "2D" GPS L2 L1(C/A)+(P2-P1) semi-codeless
;# "2S" GPS L2 L2C (M)
;# "2L" GPS L2 L2C (L)
;# "2X" GPS L2 L2C (M+L)
;# "2P" GPS L2 P
;# "2W" GPS L2 Z-tracking and similar (AS on)
;# "2Y" GPS L2 Y
;# "2M" GPS GPS L2 M
;# "2N" GPS L2 codeless
;# "5I" GPS L5 I
;# "5Q" GPS L5 Q
;# "5X" GPS L5 I+Q
;# "1C" GLONASS G1 C/A
;# "1P" GLONASS G1 P
;# "2C" GLONASS G2 C/A (Glonass M)
;# "2P" GLONASS G2 P
;# "1A" GALILEO E1 A (PRS)
;# "1B" GALILEO E1 B (I/NAV OS/CS/SoL)
;# "1C" GALILEO E1 C (no data)
;# "1X" GALILEO E1 B+C
;# "1Z" GALILEO E1 A+B+C
;# "5I" GALILEO E5a I (F/NAV OS)
;# "5Q" GALILEO E5a Q (no data)
;# "5X" GALILEO E5a I+Q
;# "7I" GALILEO E5b I
;# "7Q" GALILEO E5b Q
;# "7X" GALILEO E5b I+Q
;# "8I" GALILEO E5 I
;# "8Q" GALILEO E5 Q
;# "8X" GALILEO E5 I+Q
;# "6A" GALILEO E6 A
;# "6B" GALILEO E6 B
;# "6C" GALILEO E6 C
;# "6X" GALILEO E6 B+C
;# "6Z" GALILEO E6 A+B+C
;# "1C" SBAS L1 C/A
;# "5I" SBAS L5 I
;# "5Q" SBAS L5 Q
;# "5X" SBAS L5 I+Q
;# "2I" COMPASS E2 I
;# "2Q" COMPASS E2 Q
;# "2X" COMPASS E2 IQ
;# "7I" COMPASS E5b I
;# "7Q" COMPASS E5b Q
;# "7X" COMPASS E5b IQ
;# "6I" COMPASS E6 I
;# "6Q" COMPASS E6 Q
;# "6X" COMPASS E6 IQ
;#if the option is disabled by default is assigned "1C" GPS L1 C/A
Channel.signal=1C
;######### SPECIFIC CHANNELS CONFIG ######
;#The following options are specific to each channel and overwrite the generic options
;######### CHANNEL 0 CONFIG ############
Channel0.system=GPS
Channel0.signal=1C
;#satellite: Satellite PRN ID for this channel. Disable this option to random search
Channel0.satellite=11
;######### CHANNEL 1 CONFIG ############
Channel1.system=GPS
Channel1.signal=1C
Channel1.satellite=18
;######### ACQUISITION GLOBAL CONFIG ############
;#dump: Enable or disable the acquisition internal data file logging [true] or [false]
Acquisition.dump=false
;#filename: Log path and filename
Acquisition.dump_filename=./acq_dump.dat
;#item_type: Type and resolution for each of the signal samples. Use only gr_complex in this version.
Acquisition.item_type=gr_complex
;#if: Signal intermediate frequency in [Hz]
Acquisition.if=0
;#sampled_ms: Signal block duration for the acquisition signal detection [ms]
Acquisition.coherent_integration_time_ms=1
;#implementation: Acquisition algorithm selection for this channel: [GPS_L1_CA_PCPS_Acquisition] or [Galileo_E1_PCPS_Ambiguous_Acquisition]
Acquisition.implementation=GPS_L1_CA_PCPS_Acquisition
;#threshold: Acquisition threshold. It will be ignored if pfa is defined.
Acquisition.threshold=0.005
;#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.pfa=0.0001
;#doppler_max: Maximum expected Doppler shift [Hz]
Acquisition.doppler_max=10000
;#doppler_max: Doppler step in the grid search [Hz]
Acquisition.doppler_step=500
;#bit_transition_flag: Enable or disable a strategy to deal with bit transitions in GPS signals: process two dwells and take
maximum test statistics. Only use with implementation: [GPS_L1_CA_PCPS_Acquisition] (should not be used for Galileo_E1_PCPS_Ambiguous_Acquisition])
Acquisition.bit_transition_flag=false
;#max_dwells: Maximum number of consecutive dwells to be processed. It will be ignored if bit_transition_flag=true
Acquisition.max_dwells=1
;######### ACQUISITION CHANNELS CONFIG ######
;#The following options are specific to each channel and overwrite the generic options
;######### ACQUISITION CH 0 CONFIG ############
;Acquisition0.implementation=GPS_L1_CA_PCPS_Acquisition
;Acquisition0.threshold=0.005
;Acquisition0.pfa=0.001
;Acquisition0.doppler_max=10000
;Acquisition0.doppler_step=250
;#repeat_satellite: Use only jointly with the satellite PRN ID option. The default value is false
;Acquisition0.repeat_satellite = false
;######### ACQUISITION CH 1 CONFIG ############
;Acquisition1.implementation=GPS_L1_CA_PCPS_Acquisition
;Acquisition1.threshold=0.005
;Acquisition1.pfa=0.001
;Acquisition1.doppler_max=10000
;Acquisition1.doppler_step=250
;Acquisition1.repeat_satellite = false
;######### TRACKING GLOBAL CONFIG ############
;#implementation: Selected tracking algorithm: [GPS_L1_CA_DLL_PLL_Tracking] or [GPS_L1_CA_DLL_FLL_PLL_Tracking]
Tracking.implementation=GPS_L1_CA_DLL_PLL_Optim_Tracking
;#item_type: Type and resolution for each of the signal samples. Use only [gr_complex] in this version.
Tracking.item_type=gr_complex
;#sampling_frequency: Signal Intermediate Frequency in [Hz]
Tracking.if=0
;#dump: Enable or disable the Tracking internal binary data file logging [true] or [false]
Tracking.dump=false
;#dump_filename: Log path and filename. Notice that the tracking channel will add "x.dat" where x is the channel number.
Tracking.dump_filename=./tracking_ch_
;#pll_bw_hz: PLL loop filter bandwidth [Hz]
Tracking.pll_bw_hz=50.0;
;#dll_bw_hz: DLL loop filter bandwidth [Hz]
Tracking.dll_bw_hz=2.0;
;#fll_bw_hz: FLL loop filter bandwidth [Hz]
Tracking.fll_bw_hz=10.0;
;#order: PLL/DLL loop filter order [2] or [3]
Tracking.order=3;
;#early_late_space_chips: correlator early-late space [chips]. Use [0.5]
Tracking.early_late_space_chips=0.5;
;######### TELEMETRY DECODER CONFIG ############
;#implementation: Use [GPS_L1_CA_Telemetry_Decoder] for GPS L1 C/A.
TelemetryDecoder.implementation=GPS_L1_CA_Telemetry_Decoder
TelemetryDecoder.dump=false
;######### OBSERVABLES CONFIG ############
;#implementation: Use [GPS_L1_CA_Observables] for GPS L1 C/A.
Observables.implementation=GPS_L1_CA_Observables
;#dump: Enable or disable the Observables internal binary data file logging [true] or [false]
Observables.dump=false
;#dump_filename: Log path and filename.
Observables.dump_filename=./observables.dat
;######### PVT CONFIG ############
;#implementation: Position Velocity and Time (PVT) implementation algorithm: Use [GPS_L1_CA_PVT] in this version.
PVT.implementation=GPS_L1_CA_PVT
;#averaging_depth: Number of PVT observations in the moving average algorithm
PVT.averaging_depth=10
;#flag_average: Enables the PVT averaging between output intervals (arithmetic mean) [true] or [false]
PVT.flag_averaging=true
;#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
;#display_rate_ms: Position console print (std::out) interval [ms]. Notice that output_rate_ms<=display_rate_ms.
PVT.display_rate_ms=500
;# RINEX, KML, and NMEA output configuration
;#dump_filename: Log path and filename without extension. Notice that PVT will add ".dat" to the binary dump and ".kml" to GoogleEarth dump.
PVT.dump_filename=./PVT
;#nmea_dump_filename: NMEA log path and filename
PVT.nmea_dump_filename=./gnss_sdr_pvt.nmea;
;#flag_nmea_tty_port: Enable or disable the NMEA log to a serial TTY port (Can be used with real hardware or virtual one)
PVT.flag_nmea_tty_port=true;
;#nmea_dump_devname: serial device descriptor for NMEA logging
PVT.nmea_dump_devname=/dev/pts/4
;#dump: Enable or disable the PVT internal binary data file logging [true] or [false]
PVT.dump=false
;######### OUTPUT_FILTER CONFIG ############
;# Receiver output filter: Leave this block disabled in this version
OutputFilter.implementation=Null_Sink_Output_Filter
OutputFilter.filename=data/gnss-sdr.dat
OutputFilter.item_type=gr_complex

View File

@ -55,9 +55,9 @@ boost::shared_ptr<gr::message> ControlMessageFactory::GetQueueMessage(unsigned i
}
std::vector<ControlMessage*>* ControlMessageFactory::GetControlMessages(boost::shared_ptr<gr::message> queue_message)
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> ControlMessageFactory::GetControlMessages(boost::shared_ptr<gr::message> queue_message)
{
std::vector<ControlMessage*>* control_messages = new std::vector<ControlMessage*>();
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages = std::make_shared<std::vector<std::shared_ptr<ControlMessage>>>();
unsigned int control_messages_count = queue_message->length() / sizeof(ControlMessage);
if(queue_message->length() % sizeof(ControlMessage) != 0)
{
@ -66,10 +66,10 @@ std::vector<ControlMessage*>* ControlMessageFactory::GetControlMessages(boost::s
LOG(WARNING) << "Ignoring this queue message to prevent unexpected results.";
return control_messages;
}
for(unsigned int i=0; i<control_messages_count; i++)
for(unsigned int i = 0; i < control_messages_count; i++)
{
control_messages->push_back(new ControlMessage);
memcpy(control_messages->at(i), queue_message->msg() + (i*sizeof(ControlMessage)), sizeof(ControlMessage));
control_messages->push_back(std::make_shared<ControlMessage>());
memcpy(control_messages->at(i).get(), queue_message->msg() + (i*sizeof(ControlMessage)), sizeof(ControlMessage));
}
return control_messages;
}

View File

@ -31,6 +31,7 @@
#ifndef GNSS_SDR_CONTROL_MESSAGE_FACTORY_H_
#define GNSS_SDR_CONTROL_MESSAGE_FACTORY_H_
#include <memory>
#include <vector>
#include <gnuradio/message.h>
@ -58,7 +59,7 @@ public:
virtual ~ControlMessageFactory();
boost::shared_ptr<gr::message> GetQueueMessage(unsigned int who, unsigned int what);
std::vector<ControlMessage*>* GetControlMessages(gr::message::sptr queue_message);
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> GetControlMessages(gr::message::sptr queue_message);
};
#endif /*GNSS_SDR_CONTROL_MESSAGE_FACTORY_H_*/

View File

@ -189,6 +189,7 @@ void ControlThread::run()
galileo_ephemeris_data_collector_thread_.timed_join(boost::posix_time::seconds(1));
galileo_iono_data_collector_thread_.timed_join(boost::posix_time::seconds(1));
galileo_utc_model_data_collector_thread_.timed_join(boost::posix_time::seconds(1));
//Join keyboard threads
keyboard_thread_.timed_join(boost::posix_time::seconds(1));
@ -422,11 +423,9 @@ void ControlThread::process_control_messages()
{
flowgraph_->apply_action(control_messages_->at(i)->who, control_messages_->at(i)->what);
}
delete control_messages_->at(i);
processed_control_messages_++;
}
control_messages_->clear();
delete control_messages_;
DLOG(INFO) << "Processed all control messages";
}

View File

@ -1,11 +1,11 @@
/*!
* \file control_thread.h
* \file control_thread.h
* \brief Interface of the receiver control plane
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
*
* GNSS Receiver Control Plane: connects the flowgraph, starts running it,
* and while it does not stop, reads the control messages generated by the blocks,
* process them, and apply the corresponding actions.
* processes them, and applies the corresponding actions.
*
* -------------------------------------------------------------------------
*
@ -19,7 +19,7 @@
* 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.
* (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
@ -35,6 +35,7 @@
#ifndef GNSS_SDR_CONTROL_THREAD_H_
#define GNSS_SDR_CONTROL_THREAD_H_
#include <memory>
#include <vector>
#include <boost/thread/thread.hpp>
#include <gnuradio/msg_queue.h>
@ -46,7 +47,10 @@ class ConfigurationInterface;
/*!
* \brief This class represents the main thread of the application, aka Control Thread.
* \brief This class represents the main thread of the application, so the name is ControlThread.
* This is the GNSS Receiver Control Plane: it connects the flowgraph, starts running it,
* and while it does not stop, reads the control messages generated by the blocks,
* processes them, and applies the corresponding actions.
*/
class ControlThread
{
@ -101,14 +105,13 @@ public:
/*!
* \brief Instantiates a flowgraph
*
* \return Returns a flowgraph object
* \return Returns a smart pointer to a flowgraph object
*/
GNSSFlowgraph* flowgraph()
std::shared_ptr<GNSSFlowgraph> flowgraph()
{
return flowgraph_.get();
return flowgraph_;
}
private:
//SUPL assistance classes
gnss_sdr_supl_client supl_client_acquisition_;
@ -128,15 +131,17 @@ private:
void process_control_messages();
/*
* \brief Blocking function that reads the GPS ephemeris queue and updates the shared ephemeris map, accessible from the PVT block
* Blocking function that reads the GPS ephemeris queue and updates the shared ephemeris map, accessible from the PVT block
*/
void gps_ephemeris_data_collector();
/*
* \brief Writes the ephemeris map to a local XML file
* Writes the ephemeris map to a local XML file
*/
void gps_ephemeris_data_write_to_XML();
/*
* \brief Blocking function that reads the UTC model queue and updates the shared map, accessible from the PVT block
* Blocking function that reads the UTC model queue and updates the shared map, accessible from the PVT block
*/
void gps_utc_model_data_collector();
@ -151,7 +156,7 @@ private:
void gps_ref_time_data_collector();
/*
* \brief Write the latest GPS UTC model to XML file
* Write the latest GPS UTC model to XML file
*/
void gps_utc_model_data_write_to_XML();
@ -166,43 +171,47 @@ private:
void gps_ref_time_data_write_to_XML();
/*
* \brief Blocking function that reads the iono model queue and updates the shared map, accessible from the PVT block
* Blocking function that reads the iono model queue and updates the shared map, accessible from the PVT block
*/
void gps_iono_data_collector();
/*
* \brief Write the latest GPS IONO model to XML file
* Write the latest GPS IONO model to XML file
*/
void gps_iono_data_write_to_XML();
/*
* \brief Blocking function that reads the GPS assistance queue
* Blocking function that reads the GPS assistance queue
*/
void gps_acq_assist_data_collector();
/*
* \brief Blocking function that reads the Galileo ephemeris queue and updates the shared ephemeris map, accessible from the PVT block
* Blocking function that reads the Galileo ephemeris queue and updates the shared ephemeris map, accessible from the PVT block
*/
void galileo_ephemeris_data_collector();
/*
* \brief Blocking function that reads the UTC model queue and updates the shared map, accessible from the PVT block
*/
* Blocking function that reads the UTC model queue and updates the shared map, accessible from the PVT block
*/
void galileo_utc_model_data_collector();
/*
* Blocking function that reads the iono data queue and updates the shared map, accessible from the PVT block
*/
void galileo_iono_data_collector();
void apply_action(unsigned int what);
std::shared_ptr<GNSSFlowgraph> flowgraph_;
std::shared_ptr<ConfigurationInterface> configuration_;
boost::shared_ptr<gr::msg_queue> control_queue_;
std::shared_ptr<ControlMessageFactory> control_message_factory_;
std::vector<ControlMessage*> *control_messages_;
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages_;
bool stop_;
bool delete_configuration_;
unsigned int processed_control_messages_;
unsigned int applied_actions_;
boost::thread keyboard_thread_;
boost::thread gps_ephemeris_data_collector_thread_;
boost::thread gps_iono_data_collector_thread_;
boost::thread gps_utc_model_data_collector_thread_;

View File

@ -60,7 +60,7 @@ public:
FileConfiguration(std::string filename);
FileConfiguration();
//! Virtual destructor
virtual ~FileConfiguration();
~FileConfiguration();
std::string property(std::string property_name, std::string default_value);
bool property(std::string property_name, bool default_value);
long property(std::string property_name, long default_value);

View File

@ -33,6 +33,7 @@
* -------------------------------------------------------------------------
*/
#include "gnss_block_factory.h"
#include <string>
#include <sstream>
@ -83,15 +84,15 @@
#endif
#if GN3S_DRIVER
#include "gn3s_signal_source.h"
#include "gn3s_signal_source.h"
#endif
#if RAW_ARRAY_DRIVER
#include "raw_array_signal_source.h"
#include "raw_array_signal_source.h"
#endif
#if RTLSDR_DRIVER
#include "rtlsdr_signal_source.h"
#include "rtlsdr_signal_source.h"
#endif
using google::LogMessage;
@ -105,20 +106,18 @@ GNSSBlockFactory::~GNSSBlockFactory()
{}
GNSSBlockInterface* GNSSBlockFactory::GetSignalSource(
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetSignalSource(
std::shared_ptr<ConfigurationInterface> configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "File_Signal_Source";
std::string implementation = configuration->property(
"SignalSource.implementation", default_implementation);
std::string implementation = configuration->property("SignalSource.implementation", default_implementation);
LOG(INFO) << "Getting SignalSource with implementation " << implementation;
return GetBlock(configuration, "SignalSource", implementation, 0, 1,
queue);
return GetBlock(configuration, "SignalSource", implementation, 0, 1, queue);
}
GNSSBlockInterface* GNSSBlockFactory::GetSignalConditioner(
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetSignalConditioner(
std::shared_ptr<ConfigurationInterface> configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Pass_Through";
@ -140,7 +139,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetSignalConditioner(
input_filter = configuration->property(
"InputFilter.implementation", default_implementation);
resampler = configuration->property(
"Resampler.implementation", default_implementation);
"Resampler.implementation", default_implementation);
}
LOG(INFO) << "Getting SignalConditioner with DataTypeAdapter implementation: "
@ -151,26 +150,28 @@ GNSSBlockInterface* GNSSBlockFactory::GetSignalConditioner(
if(signal_conditioner.compare("Array_Signal_Conditioner") == 0)
{
//instantiate the array version
return new ArraySignalConditioner(configuration.get(), GetBlock(configuration,
"DataTypeAdapter", data_type_adapter, 1, 1, queue), GetBlock(
configuration,"InputFilter", input_filter, 1, 1, queue),
GetBlock(configuration,"Resampler", resampler, 1, 1, queue),
"SignalConditioner", "Signal_Conditioner", queue);
std::unique_ptr<GNSSBlockInterface> conditioner_(new ArraySignalConditioner(configuration.get(), GetBlock(configuration,
"DataTypeAdapter", data_type_adapter, 1, 1, queue).release(), GetBlock(
configuration,"InputFilter", input_filter, 1, 1, queue).release(),
GetBlock(configuration,"Resampler", resampler, 1, 1, queue).release(),
"SignalConditioner", "Signal_Conditioner", queue));
return conditioner_;
}
else
{
//normal version
return new SignalConditioner(configuration.get(), GetBlock(configuration,
"DataTypeAdapter", data_type_adapter, 1, 1, queue), GetBlock(
configuration,"InputFilter", input_filter, 1, 1, queue),
GetBlock(configuration,"Resampler", resampler, 1, 1, queue),
"SignalConditioner", "Signal_Conditioner", queue);
//single-antenna version
std::unique_ptr<GNSSBlockInterface> conditioner_(new SignalConditioner(configuration.get(), GetBlock(configuration,
"DataTypeAdapter", data_type_adapter, 1, 1, queue).release(), GetBlock(
configuration,"InputFilter", input_filter, 1, 1, queue).release(),
GetBlock(configuration,"Resampler", resampler, 1, 1, queue).release(),
"SignalConditioner", "Signal_Conditioner", queue));
return conditioner_;
}
}
GNSSBlockInterface* GNSSBlockFactory::GetObservables(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetObservables(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "GPS_L1_CA_Observables";
@ -182,7 +183,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetObservables(std::shared_ptr<Configurati
GNSSBlockInterface* GNSSBlockFactory::GetPVT(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetPVT(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Pass_Through";
@ -194,7 +195,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetPVT(std::shared_ptr<ConfigurationInterf
GNSSBlockInterface* GNSSBlockFactory::GetOutputFilter(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetOutputFilter(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Null_Sink_Output_Filter";
@ -204,7 +205,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetOutputFilter(std::shared_ptr<Configurat
}
GNSSBlockInterface* GNSSBlockFactory::GetChannel(
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel(
std::shared_ptr<ConfigurationInterface> configuration,
std::string acq, std::string trk, std::string tlm, int channel,
boost::shared_ptr<gr::msg_queue> queue)
@ -215,23 +216,31 @@ GNSSBlockInterface* GNSSBlockFactory::GetChannel(
LOG(INFO) << "Instantiating Channel " << id << " with Acquisition Implementation: "
<< acq << ", Tracking Implementation: " << trk << ", Telemetry Decoder implementation: " << tlm;
return new Channel(configuration.get(), channel, GetBlock(configuration,
"Channel", "Pass_Through", 1, 1, queue),
(AcquisitionInterface*)GetBlock(configuration, "Acquisition", acq, 1, 1, queue),
(TrackingInterface*)GetBlock(configuration, "Tracking", trk, 1, 1, queue),
(TelemetryDecoderInterface*)GetBlock(configuration, "TelemetryDecoder", tlm, 1, 1, queue),
"Channel", "Channel", queue);
std::unique_ptr<GNSSBlockInterface> pass_through_ = GetBlock(configuration, "Channel", "Pass_Through", 1, 1, queue);
std::unique_ptr<AcquisitionInterface> acq_ = GetAcqBlock(configuration, "Acquisition", acq, 1, 1, queue);
std::unique_ptr<TrackingInterface> trk_ = GetTrkBlock(configuration, "Tracking", trk, 1, 1, queue);
std::unique_ptr<TelemetryDecoderInterface> tlm_ = GetTlmBlock(configuration, "TelemetryDecoder", tlm, 1, 1, queue);
std::unique_ptr<GNSSBlockInterface> channel_(new Channel(configuration.get(), channel, pass_through_.release(),
acq_.release(),
trk_.release(),
tlm_.release(),
"Channel", "Channel", queue));
return channel_;
}
std::vector<GNSSBlockInterface*>* GNSSBlockFactory::GetChannels(
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GNSSBlockFactory::GetChannels(
std::shared_ptr<ConfigurationInterface> configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Pass_Through";
unsigned int channel_count = configuration->property("Channels.count", 12);
LOG(INFO) << "Getting " << channel_count << " channels";
std::vector<GNSSBlockInterface*>* channels = new std::vector<GNSSBlockInterface*>();
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> channels(new std::vector<std::unique_ptr<GNSSBlockInterface>>());
std::string tracking = configuration->property("Tracking.implementation", default_implementation);
std::string telemetry_decoder = configuration->property("TelemetryDecoder.implementation", default_implementation);
std::string acquisition_implementation = configuration->property("Acquisition.implementation", default_implementation);
@ -239,15 +248,15 @@ std::vector<GNSSBlockInterface*>* GNSSBlockFactory::GetChannels(
for (unsigned int i = 0; i < channel_count; i++)
{
std::string acquisition_implementation_specific = configuration->property(
"Acquisition"+ boost::lexical_cast<std::string>(i) + ".implementation",
default_implementation);
"Acquisition" + boost::lexical_cast<std::string>(i) + ".implementation",
default_implementation);
if(acquisition_implementation_specific.compare(default_implementation) != 0)
{
acquisition_implementation = acquisition_implementation_specific;
acquisition_implementation = acquisition_implementation_specific;
}
channels->push_back(GetChannel(configuration,
acquisition_implementation, tracking, telemetry_decoder, i,
queue));
channels->push_back(std::move(GetChannel(configuration,
acquisition_implementation, tracking, telemetry_decoder, i, queue)));
}
return channels;
}
@ -258,18 +267,19 @@ std::vector<GNSSBlockInterface*>* GNSSBlockFactory::GetChannels(
*
* PLEASE ADD YOUR NEW BLOCK HERE!!
*/
GNSSBlockInterface* GNSSBlockFactory::GetBlock(
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue)
{
GNSSBlockInterface* block = NULL; //Change to nullptr when available in compilers (C++11)
std::unique_ptr<GNSSBlockInterface> block;
//PASS THROUGH ----------------------------------------------------------------
if (implementation.compare("Pass_Through") == 0)
{
block = new Pass_Through(configuration.get(), role, in_streams, out_streams);
std::unique_ptr<GNSSBlockInterface> block_(new Pass_Through(configuration.get(), role, in_streams, out_streams));
block = std::move(block_);
}
// SIGNAL SOURCES -------------------------------------------------------------
@ -277,9 +287,11 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
{
try
{
block = new FileSignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new FileSignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
catch (const std::exception &e)
{
std::cout << "GNSS-SDR program ended." << std::endl;
@ -291,8 +303,10 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
{
try
{
block = new NsrFileSignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new NsrFileSignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
catch (const std::exception &e)
{
@ -303,208 +317,418 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
}
else if (implementation.compare("UHD_Signal_Source") == 0)
{
block = new UhdSignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new UhdSignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#if GN3S_DRIVER
else if (implementation.compare("GN3S_Signal_Source") == 0)
{
block = new Gn3sSignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new Gn3sSignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#endif
#if RAW_ARRAY_DRIVER
else if (implementation.compare("Raw_Array_Signal_Source") == 0)
{
block = new RawArraySignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new RawArraySignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#endif
#if RTLSDR_DRIVER
else if (implementation.compare("Rtlsdr_Signal_Source") == 0)
{
block = new RtlsdrSignalSource(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new RtlsdrSignalSource(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#endif
// DATA TYPE ADAPTER -----------------------------------------------------------
else if (implementation.compare("Ishort_To_Complex") == 0)
{
block = new IshortToComplex(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface>block_(new IshortToComplex(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// INPUT FILTER ----------------------------------------------------------------
else if (implementation.compare("Fir_Filter") == 0)
{
block = new FirFilter(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new FirFilter(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Freq_Xlating_Fir_Filter") == 0)
{
block = new FreqXlatingFirFilter(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new FreqXlatingFirFilter(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Beamformer_Filter") == 0)
{
block = new BeamformerFilter(configuration.get(), role, in_streams,
out_streams);
std::unique_ptr<GNSSBlockInterface> block_(new BeamformerFilter(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
// RESAMPLER -------------------------------------------------------------------
else if (implementation.compare("Direct_Resampler") == 0)
{
block = new DirectResamplerConditioner(configuration.get(), role,
in_streams, out_streams);
std::unique_ptr<GNSSBlockInterface> block_(new DirectResamplerConditioner(configuration.get(), role,
in_streams, out_streams));
block = std::move(block_);
}
// ACQUISITION BLOCKS ---------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_PCPS_Acquisition") == 0)
{
block = new GpsL1CaPcpsAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Assisted_Acquisition") == 0)
{
block = new GpsL1CaPcpsAssistedAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsAssistedAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Tong_Acquisition") == 0)
{
block = new GpsL1CaPcpsTongAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsTongAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Multithread_Acquisition") == 0)
{
block = new GpsL1CaPcpsMultithreadAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsMultithreadAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#if OPENCL_BLOCKS
else if (implementation.compare("GPS_L1_CA_PCPS_OpenCl_Acquisition") == 0)
{
block = new GpsL1CaPcpsOpenClAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsOpenClAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#endif
else if (implementation.compare("GPS_L1_CA_PCPS_Acquisition_Fine_Doppler") == 0)
{
block = new GpsL1CaPcpsAcquisitionFineDoppler(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPcpsAcquisitionFineDoppler(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_Ambiguous_Acquisition") == 0)
{
block = new GalileoE1PcpsAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1PcpsAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_8ms_Ambiguous_Acquisition") == 0)
{
block = new GalileoE1Pcps8msAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1Pcps8msAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_Tong_Ambiguous_Acquisition") == 0)
{
block = new GalileoE1PcpsTongAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1PcpsTongAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_CCCWSR_Ambiguous_Acquisition") == 0)
{
block = new GalileoE1PcpsCccwsrAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1PcpsCccwsrAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// TRACKING BLOCKS -------------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_DLL_PLL_Tracking") == 0)
{
block = new GpsL1CaDllPllTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaDllPllTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_DLL_PLL_Optim_Tracking") == 0)
{
block = new GpsL1CaDllPllOptimTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaDllPllOptimTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_DLL_FLL_PLL_Tracking") == 0)
{
block = new GpsL1CaDllFllPllTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaDllFllPllTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_TCP_CONNECTOR_Tracking") == 0)
{
block = new GpsL1CaTcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaTcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_DLL_PLL_VEML_Tracking") == 0)
{
block = new GalileoE1DllPllVemlTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1DllPllVemlTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_TCP_CONNECTOR_Tracking") == 0)
{
block = new GalileoE1TcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1TcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// TELEMETRY DECODERS ----------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_Telemetry_Decoder") == 0)
{
block = new GpsL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1B_Telemetry_Decoder") == 0)
{
block = new GalileoE1BTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1BTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("SBAS_L1_Telemetry_Decoder") == 0)
{
block = new SbasL1TelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new SbasL1TelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// OBSERVABLES -----------------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_Observables") == 0)
{
block = new GpsL1CaObservables(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaObservables(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1B_Observables") == 0)
{
block = new GalileoE1Observables(configuration.get(), role, in_streams,
out_streams, queue);
}
{
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1Observables(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// PVT -------------------------------------------------------------------------
else if (implementation.compare("GPS_L1_CA_PVT") == 0)
{
block = new GpsL1CaPvt(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GpsL1CaPvt(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GALILEO_E1_PVT") == 0)
{
block = new GalileoE1Pvt(configuration.get(), role, in_streams,
out_streams, queue);
std::unique_ptr<GNSSBlockInterface> block_(new GalileoE1Pvt(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
// OUTPUT FILTERS --------------------------------------------------------------
else if (implementation.compare("Null_Sink_Output_Filter") == 0)
{
block = new NullSinkOutputFilter(configuration.get(), role, in_streams,
out_streams);
std::unique_ptr<GNSSBlockInterface> block_(new NullSinkOutputFilter(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else if (implementation.compare("File_Output_Filter") == 0)
{
block = new FileOutputFilter(configuration.get(), role, in_streams,
out_streams);
std::unique_ptr<GNSSBlockInterface> block_(new FileOutputFilter(configuration.get(), role, in_streams,
out_streams));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
LOG(ERROR) << implementation << ": Undefined implementation for block";
}
return block;
return std::move(block);
}
/*
* Not very elegant, Acq, Ttk and Tlm blocks must be added here, too.
* To be fixed!
*/
std::unique_ptr<AcquisitionInterface> GNSSBlockFactory::GetAcqBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue)
{
std::unique_ptr<AcquisitionInterface> block;
// ACQUISITION BLOCKS ---------------------------------------------------------
if (implementation.compare("GPS_L1_CA_PCPS_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Assisted_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsAssistedAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Tong_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsTongAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_PCPS_Multithread_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsMultithreadAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#if OPENCL_BLOCKS
else if (implementation.compare("GPS_L1_CA_PCPS_OpenCl_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsOpenClAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
#endif
else if (implementation.compare("GPS_L1_CA_PCPS_Acquisition_Fine_Doppler") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GpsL1CaPcpsAcquisitionFineDoppler(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_Ambiguous_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GalileoE1PcpsAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_8ms_Ambiguous_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GalileoE1Pcps8msAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_Tong_Ambiguous_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GalileoE1PcpsTongAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_PCPS_CCCWSR_Ambiguous_Acquisition") == 0)
{
std::unique_ptr<AcquisitionInterface> block_(new GalileoE1PcpsCccwsrAmbiguousAcquisition(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
LOG(ERROR) << implementation << ": Undefined implementation for block";
}
return std::move(block);
}
std::unique_ptr<TrackingInterface> GNSSBlockFactory::GetTrkBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue)
{
std::unique_ptr<TrackingInterface> block;
// TRACKING BLOCKS -------------------------------------------------------------
if (implementation.compare("GPS_L1_CA_DLL_PLL_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaDllPllTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_DLL_PLL_Optim_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaDllPllOptimTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_DLL_FLL_PLL_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaDllFllPllTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("GPS_L1_CA_TCP_CONNECTOR_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GpsL1CaTcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_DLL_PLL_VEML_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GalileoE1DllPllVemlTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1_TCP_CONNECTOR_Tracking") == 0)
{
std::unique_ptr<TrackingInterface> block_(new GalileoE1TcpConnectorTracking(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
LOG(ERROR) << implementation << ": Undefined implementation for block";
}
return std::move(block);
}
std::unique_ptr<TelemetryDecoderInterface> GNSSBlockFactory::GetTlmBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue)
{
std::unique_ptr<TelemetryDecoderInterface> block;
// TELEMETRY DECODERS ----------------------------------------------------------
if (implementation.compare("GPS_L1_CA_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new GpsL1CaTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("Galileo_E1B_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new GalileoE1BTelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else if (implementation.compare("SBAS_L1_Telemetry_Decoder") == 0)
{
std::unique_ptr<TelemetryDecoderInterface> block_(new SbasL1TelemetryDecoder(configuration.get(), role, in_streams,
out_streams, queue));
block = std::move(block_);
}
else
{
// Log fatal. This causes execution to stop.
LOG(ERROR) << implementation << ": Undefined implementation for block";
}
return std::move(block);
}

View File

@ -1,16 +1,17 @@
/*!
* \file gnss_block_factory.h
* \brief Interface of a factory that returns instances of GNSS blocks.
* \brief Interface of a factory that returns smart pointers to GNSS blocks.
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Luis Esteve, 2011. luis(at)epsilon-formacion.com
* Javier Arribas, 2011. jarribas(at)cttc.es
* Carles Fernandez-Prades, 2014. cfernandez(at)cttc.es
*
* This class encapsulates the complexity behind the instantiation
* of GNSS blocks.
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2012 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2014 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
@ -36,12 +37,16 @@
#ifndef GNSS_SDR_BLOCK_FACTORY_H_
#define GNSS_SDR_BLOCK_FACTORY_H_
#include <vector>
#include <memory>
#include <string>
#include <vector>
#include <gnuradio/msg_queue.h>
class ConfigurationInterface;
class GNSSBlockInterface;
class AcquisitionInterface;
class TrackingInterface;
class TelemetryDecoderInterface;
/*!
* \brief Class that produces all kinds of GNSS blocks
@ -51,28 +56,45 @@ class GNSSBlockFactory
public:
GNSSBlockFactory();
virtual ~GNSSBlockFactory();
GNSSBlockInterface* GetSignalSource(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetSignalSource(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
GNSSBlockInterface* GetSignalConditioner(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetSignalConditioner(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
GNSSBlockInterface* GetPVT(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetPVT(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
GNSSBlockInterface* GetObservables(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetObservables(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
GNSSBlockInterface* GetOutputFilter(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetOutputFilter(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
GNSSBlockInterface* GetChannel(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetChannel(std::shared_ptr<ConfigurationInterface> configuration,
std::string acq, std::string trk, std::string tlm, int channel,
boost::shared_ptr<gr::msg_queue> queue);
std::vector<GNSSBlockInterface*>* GetChannels(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GetChannels(std::shared_ptr<ConfigurationInterface> configuration,
boost::shared_ptr<gr::msg_queue> queue);
/*
* \brief Returns the block with the required configuration and implementation
*/
GNSSBlockInterface* GetBlock(std::shared_ptr<ConfigurationInterface> configuration,
std::unique_ptr<GNSSBlockInterface> GetBlock(std::shared_ptr<ConfigurationInterface> configuration,
std::string role, std::string implementation,
unsigned int in_streams, unsigned int out_streams,
boost::shared_ptr<gr::msg_queue> queue);
private:
std::unique_ptr<AcquisitionInterface> GetAcqBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue);
std::unique_ptr<TrackingInterface> GetTrkBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue);
std::unique_ptr<TelemetryDecoderInterface> GetTlmBlock(
std::shared_ptr<ConfigurationInterface> configuration,
std::string role,
std::string implementation, unsigned int in_streams,
unsigned int out_streams, boost::shared_ptr<gr::msg_queue> queue);
};
#endif /*GNSS_SDR_BLOCK_FACTORY_H_*/

View File

@ -3,6 +3,7 @@
* \brief Implementation of a GNSS receiver flowgraph
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Luis Esteve, 2012. luis(at)epsilon-formacion.com
* Carles Fernandez-Prades, 2014. cfernandez(at)cttc.es
*
* Detailed description of the file here if needed.
*
@ -35,7 +36,6 @@
#include "unistd.h"
#include <exception>
#include <iostream>
#include <memory>
#include <set>
#include <boost/lexical_cast.hpp>
#include <glog/logging.h>
@ -54,7 +54,7 @@ GNSSFlowgraph::GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configurati
connected_ = false;
running_ = false;
configuration_ = configuration;
blocks_ = new std::vector<GNSSBlockInterface*>();
std::shared_ptr<std::vector<std::shared_ptr<GNSSBlockInterface>>> blocks_ = std::make_shared<std::vector<std::shared_ptr<GNSSBlockInterface>>>();
queue_ = queue;
init();
}
@ -62,12 +62,7 @@ GNSSFlowgraph::GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configurati
GNSSFlowgraph::~GNSSFlowgraph()
{
for (unsigned int i = 0; i < blocks_->size(); i++)
{
delete blocks_->at(i);
}
blocks_->clear();
delete blocks_;
}
@ -101,7 +96,7 @@ void GNSSFlowgraph::stop()
for (unsigned int i = 0; i < channels_count_; i++)
{
// if(channels_state_[i]==2) channel(i)->
channel(i)->stop();
channels_.at(i)->stop();
}
for (unsigned int i = 0; i < channels_count_; i++)
{
@ -129,7 +124,8 @@ void GNSSFlowgraph::connect()
try
{
signal_source()->connect(top_block_);
sig_source_ = std::move(blocks_->at(0));
sig_source_->connect(top_block_);
}
catch (std::exception& e)
{
@ -142,7 +138,8 @@ void GNSSFlowgraph::connect()
// Signal Source > Signal conditioner >
try
{
signal_conditioner()->connect(top_block_);
sig_conditioner_ = std::move(blocks_->at(1));
sig_conditioner_->connect(top_block_);
}
catch (std::exception& e)
{
@ -156,7 +153,10 @@ void GNSSFlowgraph::connect()
{
try
{
channel(i)->connect(top_block_);
auto chan_ = std::move(blocks_->at(i + 5));
std::shared_ptr<ChannelInterface> chan = std::dynamic_pointer_cast<ChannelInterface>(chan_);
channels_.push_back(chan);
channels_.at(i)->connect(top_block_);
}
catch (std::exception& e)
{
@ -169,7 +169,8 @@ void GNSSFlowgraph::connect()
try
{
observables()->connect(top_block_);
observables_ = std::move(blocks_->at(2));
observables_->connect(top_block_);
}
catch (std::exception& e)
{
@ -182,7 +183,8 @@ void GNSSFlowgraph::connect()
// Signal Source > Signal conditioner >> Channels >> Observables > PVT
try
{
pvt()->connect(top_block_);
pvt_ = std::move(blocks_->at(3));
pvt_->connect(top_block_);
}
catch (std::exception& e)
{
@ -195,7 +197,8 @@ void GNSSFlowgraph::connect()
// Signal Source > Signal conditioner >> Channels >> Observables > PVT > Output Filter
try
{
output_filter()->connect(top_block_);
output_filter_ = std::move(blocks_->at(4));
output_filter_->connect(top_block_);
}
catch (std::exception& e)
{
@ -208,25 +211,22 @@ void GNSSFlowgraph::connect()
DLOG(INFO) << "blocks connected internally";
// Signal Source > Signal conditioner >
try
{
if(signal_source()->implementation().compare("Raw_Array_Signal_Source") == 0)
if(sig_source_->implementation().compare("Raw_Array_Signal_Source") == 0)
{
//Multichannel Array
std::cout << "ARRAY MODE" << std::endl;
for (int i = 0; i < GNSS_SDR_ARRAY_SIGNAL_CONDITIONER_CHANNELS; i++)
{
std::cout << "connecting ch "<< i << std::endl;
top_block_->connect(signal_source()->get_right_block(), i, signal_conditioner()->get_left_block(), i);
top_block_->connect(sig_source_->get_right_block(), i, sig_conditioner_->get_left_block(), i);
}
}
else
{
//single channel
// std::cout<<"NORMAL MODE"<<std::endl;
top_block_->connect(signal_source()->get_right_block(), 0, signal_conditioner()->get_left_block(), 0);
top_block_->connect(sig_source_->get_right_block(), 0, sig_conditioner_->get_left_block(), 0);
}
}
@ -244,8 +244,8 @@ void GNSSFlowgraph::connect()
{
try
{
top_block_->connect(signal_conditioner()->get_right_block(), 0,
channel(i)->get_left_block(), 0);
top_block_->connect(sig_conditioner_->get_right_block(), 0,
channels_.at(i)->get_left_block(), 0);
}
catch (std::exception& e)
{
@ -260,8 +260,8 @@ void GNSSFlowgraph::connect()
// Signal Source > Signal conditioner >> Channels >> Observables
try
{
top_block_->connect(channel(i)->get_right_block(), 0,
observables()->get_left_block(), i);
top_block_->connect(channels_.at(i)->get_right_block(), 0,
observables_->get_left_block(), i);
}
catch (std::exception& e)
{
@ -271,13 +271,14 @@ void GNSSFlowgraph::connect()
return;
}
channel(i)->set_signal(available_GNSS_signals_.front());
channels_.at(i)->set_signal(available_GNSS_signals_.front());
LOG(INFO) << "Channel " << i << " assigned to " << available_GNSS_signals_.front();
available_GNSS_signals_.pop_front();
channel(i)->start();
channels_.at(i)->start();
if (channels_state_[i] == 1)
{
channel(i)->start_acquisition();
channels_.at(i)->start_acquisition();
LOG(INFO) << "Channel " << i
<< " connected to observables and ready for acquisition";
}
@ -295,7 +296,7 @@ void GNSSFlowgraph::connect()
{
for (unsigned int i = 0; i < channels_count_; i++)
{
top_block_->connect(observables()->get_right_block(), i, pvt()->get_left_block(), i);
top_block_->connect(observables_->get_right_block(), i, pvt_->get_left_block(), i);
}
}
catch (std::exception& e)
@ -308,7 +309,7 @@ void GNSSFlowgraph::connect()
try
{
top_block_->connect(pvt()->get_right_block(), 0, output_filter()->get_left_block(), 0);
top_block_->connect(pvt_->get_right_block(), 0, output_filter_->get_left_block(), 0);
}
catch (std::exception& e)
{
@ -356,23 +357,23 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
switch (what)
{
case 0:
LOG(INFO) << "Channel " << who << " ACQ FAILED satellite " << channel(who)->get_signal().get_satellite();
available_GNSS_signals_.push_back(channel(who)->get_signal());
LOG(INFO) << "Channel " << who << " ACQ FAILED satellite " << channels_.at(who)->get_signal().get_satellite();
available_GNSS_signals_.push_back(channels_.at(who)->get_signal());
while (channel(who)->get_signal().get_satellite().get_system() != available_GNSS_signals_.front().get_satellite().get_system())
while (channels_.at(who)->get_signal().get_satellite().get_system() != available_GNSS_signals_.front().get_satellite().get_system())
{
available_GNSS_signals_.push_back(available_GNSS_signals_.front());
available_GNSS_signals_.pop_front();
}
channel(who)->set_signal(available_GNSS_signals_.front());
channels_.at(who)->set_signal(available_GNSS_signals_.front());
available_GNSS_signals_.pop_front();
channel(who)->start_acquisition();
channels_.at(who)->start_acquisition();
break;
// TODO: Tracking messages
case 1:
LOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite " << channel(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite " << channels_.at(who)->get_signal().get_satellite();
channels_state_[who] = 2;
acq_channels_count_--;
if (acq_channels_count_ < max_acq_channels_)
@ -383,7 +384,7 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
{
channels_state_[i] = 1;
acq_channels_count_++;
channel(i)->start_acquisition();
channels_.at(i)->start_acquisition();
break;
}
}
@ -396,17 +397,17 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
break;
case 2:
LOG(INFO) << "Channel " << who << " TRK FAILED satellite " << channel(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " TRK FAILED satellite " << channels_.at(who)->get_signal().get_satellite();
if (acq_channels_count_ < max_acq_channels_)
{
channels_state_[who] = 1;
acq_channels_count_++;
channel(who)->start_acquisition();
channels_.at(who)->start_acquisition();
}
else
{
channels_state_[who] = 0;
channel(who)->standby();
channels_.at(who)->standby();
}
for (unsigned int i = 0; i < channels_count_; i++)
@ -440,78 +441,41 @@ void GNSSFlowgraph::set_configuration(std::shared_ptr<ConfigurationInterface> co
GNSSBlockInterface* GNSSFlowgraph::signal_source()
{
return blocks_->at(0);
}
GNSSBlockInterface* GNSSFlowgraph::signal_conditioner()
{
return blocks_->at(1);
}
ChannelInterface* GNSSFlowgraph::channel(unsigned int index)
{
return (ChannelInterface*) blocks_->at(index + 5);
}
GNSSBlockInterface* GNSSFlowgraph::observables()
{
return blocks_->at(2);
}
GNSSBlockInterface* GNSSFlowgraph::pvt()
{
return blocks_->at(3);
}
GNSSBlockInterface* GNSSFlowgraph::output_filter()
{
return blocks_->at(4);
}
void GNSSFlowgraph::init()
{
/*
* Instantiates the receiver blocks
*/
blocks_->push_back(block_factory_->GetSignalSource(configuration_, queue_));
blocks_->push_back(block_factory_->GetSignalConditioner(configuration_, queue_));
blocks_->push_back(block_factory_->GetObservables(configuration_, queue_));
blocks_->push_back(block_factory_->GetPVT(configuration_, queue_));
blocks_->push_back(block_factory_->GetOutputFilter(configuration_, queue_));
std::shared_ptr<GNSSBlockFactory> block_factory_ = std::make_shared<GNSSBlockFactory>();
std::vector<GNSSBlockInterface*>* channels = block_factory_->GetChannels(configuration_, queue_);
std::shared_ptr<GNSSBlockInterface> signal_source_ = block_factory_->GetSignalSource(configuration_, queue_);
std::shared_ptr<GNSSBlockInterface> cond_ = block_factory_->GetSignalConditioner(configuration_, queue_);
std::shared_ptr<GNSSBlockInterface> obs_ = block_factory_->GetObservables(configuration_, queue_);
std::shared_ptr<GNSSBlockInterface> pvt_ = block_factory_->GetPVT(configuration_, queue_);
std::shared_ptr<GNSSBlockInterface> output_ = block_factory_->GetOutputFilter(configuration_, queue_);
blocks_->push_back(signal_source_);
blocks_->push_back(cond_);
blocks_->push_back(obs_);
blocks_->push_back(pvt_);
blocks_->push_back(output_);
std::shared_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> channels = block_factory_->GetChannels(configuration_, queue_);
channels_count_ = channels->size();
for (unsigned int i = 0; i < channels_count_; i++)
{
blocks_->push_back(channels->at(i));
std::shared_ptr<GNSSBlockInterface> chan_ = std::move(channels->at(i));
blocks_->push_back(chan_);
}
top_block_ = gr::make_top_block("GNSSFlowgraph");
delete channels;
// fill the available_GNSS_signals_ queue with the satellites ID's to be searched by the acquisition
set_signals_list();
set_channels_state();
applied_actions_ = 0;
std::vector<std::shared_ptr<ChannelInterface>> channels_(channels_count_);
DLOG(INFO) << "Blocks instantiated. " << channels_count_ << " channels.";
}
@ -521,7 +485,6 @@ void GNSSFlowgraph::set_signals_list()
/*
* Sets a sequential list of GNSS satellites
*/
std::set<unsigned int>::iterator available_gnss_prn_iter;
/*
@ -532,7 +495,6 @@ void GNSSFlowgraph::set_signals_list()
/*
* Read GNSS-SDR default GNSS system and signal
*/
std::string default_system = configuration_->property("Channel.system", std::string("GPS"));
std::string default_signal = configuration_->property("Channel.signal", std::string("1C"));
@ -540,60 +502,59 @@ void GNSSFlowgraph::set_signals_list()
* Loop to create the list of GNSS Signals
* To add signals from other systems, add another loop 'for'
*/
if (default_system.compare(std::string("GPS")) == 0)
{
/*
* Loop to create GPS L1 C/A signals
*/
std::set<unsigned int> available_gps_prn = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 25, 26, 27, 28,
29, 30, 31, 32 };
{
/*
* Loop to create GPS L1 C/A signals
*/
std::set<unsigned int> available_gps_prn = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 25, 26, 27, 28,
29, 30, 31, 32 };
for (available_gnss_prn_iter = available_gps_prn.begin();
available_gnss_prn_iter != available_gps_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("GPS"),
*available_gnss_prn_iter), std::string("1C")));
}
}
for (available_gnss_prn_iter = available_gps_prn.begin();
available_gnss_prn_iter != available_gps_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("GPS"),
*available_gnss_prn_iter), std::string("1C")));
}
}
if (default_system.compare(std::string("SBAS")) == 0)
{
/*
* Loop to create SBAS L1 C/A signals
*/
std::set<unsigned int> available_sbas_prn = {120, 124, 126};
{
/*
* Loop to create SBAS L1 C/A signals
*/
std::set<unsigned int> available_sbas_prn = {120, 124, 126};
for (available_gnss_prn_iter = available_sbas_prn.begin();
available_gnss_prn_iter != available_sbas_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("SBAS"),
*available_gnss_prn_iter), std::string("1C")));
}
}
for (available_gnss_prn_iter = available_sbas_prn.begin();
available_gnss_prn_iter != available_sbas_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("SBAS"),
*available_gnss_prn_iter), std::string("1C")));
}
}
if (default_system.compare(std::string("Galileo")) == 0)
{
/*
* Loop to create the list of Galileo E1 B signals
*/
std::set<unsigned int> available_galileo_prn = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 25, 26, 27, 28,
29, 30, 31, 32, 33, 34, 35, 36};
for (available_gnss_prn_iter = available_galileo_prn.begin();
available_gnss_prn_iter != available_galileo_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("Galileo"),
*available_gnss_prn_iter), std::string("1B")));
/*
* Loop to create the list of Galileo E1 B signals
*/
std::set<unsigned int> available_galileo_prn = { 1, 2, 3, 4, 5, 6, 7, 8, 9, 10,
11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 25, 26, 27, 28,
29, 30, 31, 32, 33, 34, 35, 36};
for (available_gnss_prn_iter = available_galileo_prn.begin();
available_gnss_prn_iter != available_galileo_prn.end();
available_gnss_prn_iter++)
{
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("Galileo"),
*available_gnss_prn_iter), std::string("1B")));
}
}
}
/*
* Ordering the list of signals from configuration file
@ -628,16 +589,16 @@ void GNSSFlowgraph::set_signals_list()
available_GNSS_signals_.insert(gnss_it, signal_value);
}
}
// **** FOR DEBUGGING THE LIST OF GNSS SIGNALS ****
//
// **** FOR DEBUGGING THE LIST OF GNSS SIGNALS ****
//
//std::cout<<"default_system="<<default_system<<std::endl;
//std::cout<<"default_signal="<<default_signal<<std::endl;
// std::list<Gnss_Signal>::iterator available_gnss_list_iter;
// for (available_gnss_list_iter = available_GNSS_signals_.begin(); available_gnss_list_iter
// != available_GNSS_signals_.end(); available_gnss_list_iter++)
// {
// std::cout << *available_gnss_list_iter << std::endl;
// }
// std::list<Gnss_Signal>::iterator available_gnss_list_iter;
// for (available_gnss_list_iter = available_GNSS_signals_.begin(); available_gnss_list_iter
// != available_GNSS_signals_.end(); available_gnss_list_iter++)
// {
// std::cout << *available_gnss_list_iter << std::endl;
// }
}

View File

@ -3,6 +3,7 @@
* \brief Interface of a GNSS receiver flowgraph.
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
* Luis Esteve, 2011. luis(at)epsilon-formacion.com
* Carles Fernandez-Prades, 2014. cfernandez(at)cttc.es
*
* It contains a signal source,
* a signal conditioner, a set of channels, a pvt and an output filter.
@ -35,10 +36,11 @@
#ifndef GNSS_SDR_GNSS_FLOWGRAPH_H_
#define GNSS_SDR_GNSS_FLOWGRAPH_H_
#include <list>
#include <memory>
#include <queue>
#include <string>
#include <vector>
#include <queue>
#include <list>
#include <gnuradio/top_block.h>
#include <gnuradio/msg_queue.h>
#include "GPS_L1_CA.h"
@ -93,13 +95,6 @@ public:
void set_configuration(std::shared_ptr<ConfigurationInterface> configuration);
GNSSBlockInterface* signal_source();
GNSSBlockInterface* signal_conditioner();
ChannelInterface* channel(unsigned int index);
GNSSBlockInterface* observables();
GNSSBlockInterface* pvt();
GNSSBlockInterface* output_filter();
unsigned int applied_actions()
{
return applied_actions_;
@ -114,15 +109,10 @@ public:
}
private:
void init();
/*!
* \brief Populates the SV PRN list available for acquisition and tracking
*/
void init(); // Populates the SV PRN list available for acquisition and tracking
void set_signals_list();
/*!
* \brief Initializes the channels state (start acquisition or keep standby) using the configuration parameters (number of channels and max channels in acquisition)
*/
void set_channels_state();
void set_channels_state(); // Initializes the channels state (start acquisition or keep standby)
// using the configuration parameters (number of channels and max channels in acquisition)
bool connected_;
bool running_;
unsigned int channels_count_;
@ -131,8 +121,14 @@ private:
unsigned int applied_actions_;
std::string config_file_;
std::shared_ptr<ConfigurationInterface> configuration_;
std::unique_ptr<GNSSBlockFactory> block_factory_;
std::vector<GNSSBlockInterface*>* blocks_;
std::shared_ptr<GNSSBlockFactory> block_factory_;
std::shared_ptr<std::vector<std::shared_ptr<GNSSBlockInterface>>> blocks_ = std::make_shared<std::vector<std::shared_ptr<GNSSBlockInterface>>>();
std::shared_ptr<GNSSBlockInterface> sig_source_;
std::shared_ptr<GNSSBlockInterface> sig_conditioner_;
std::shared_ptr<GNSSBlockInterface> observables_;
std::shared_ptr<GNSSBlockInterface> pvt_;
std::shared_ptr<GNSSBlockInterface> output_filter_;
std::vector<std::shared_ptr<ChannelInterface>> channels_;
gr::top_block_sptr top_block_;
boost::shared_ptr<gr::msg_queue> queue_;
std::list<Gnss_Signal> available_GNSS_signals_;

View File

@ -39,17 +39,13 @@
TEST(Control_Message_Factory_Test, GetQueueMessage)
{
ControlMessageFactory *factory = new ControlMessageFactory();
std::shared_ptr<ControlMessageFactory> factory = std::make_shared<ControlMessageFactory>();
gr::message::sptr queue_message = factory->GetQueueMessage(0, 0);
ControlMessage *control_message = (ControlMessage*)queue_message->msg();
std::shared_ptr<ControlMessage> control_message = std::make_shared<ControlMessage>();
unsigned int expected0 = 0;
EXPECT_EQ(expected0, control_message->who);
EXPECT_EQ(expected0, control_message->what);
EXPECT_EQ(sizeof(ControlMessage), queue_message->length());
delete factory;
}
@ -57,48 +53,40 @@ TEST(Control_Message_Factory_Test, GetQueueMessage)
TEST(Control_Message_Factory_Test, GetControlMessages)
{
ControlMessageFactory *factory = new ControlMessageFactory();
ControlMessage *control_message = new ControlMessage;
std::shared_ptr<ControlMessageFactory> factory = std::make_shared<ControlMessageFactory>();
gr::message::sptr queue_message = gr::message::make(0, 0, 0, sizeof(ControlMessage));
std::shared_ptr<ControlMessage> control_message = std::make_shared<ControlMessage>();
control_message->who = 1;
control_message->what = 4;
gr::message::sptr queue_message = gr::message::make(0, 0, 0, sizeof(ControlMessage));
memcpy(queue_message->msg(), control_message, sizeof(ControlMessage));
std::vector<ControlMessage*> *control_messages = factory->GetControlMessages(queue_message);
memcpy(queue_message->msg(), control_message.get(), sizeof(ControlMessage));
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages = factory->GetControlMessages(queue_message);
unsigned int expected1 = 1;
unsigned int expected4 = 4;
EXPECT_EQ(expected1, control_messages->size());
EXPECT_EQ(expected1, control_messages->at(0)->who);
EXPECT_EQ(expected4, control_messages->at(0)->what);
delete control_message;
delete control_messages;
delete factory;
}
/*
TEST(Control_Message_Factory_Test, GetControlMessagesWrongSize)
{
ControlMessageFactory *factory = new ControlMessageFactory();
ControlMessage *control_message = new ControlMessage;
std::shared_ptr<ControlMessageFactory> factory = std::make_shared<ControlMessageFactory>();
std::shared_ptr<ControlMessage> control_message = std::make_shared<ControlMessage>();
control_message->who = 1;
control_message->what = 4;
int another_int = 10;
gr::message::sptr queue_message = gr::message::make(0, 0, 0, sizeof(ControlMessage) + sizeof(int));
memcpy(queue_message->msg(), control_message, sizeof(ControlMessage));
memcpy(queue_message->msg(), control_message.get(), sizeof(ControlMessage));
memcpy(queue_message->msg() + sizeof(ControlMessage), &another_int, sizeof(int));
std::vector<ControlMessage*> *control_messages = factory->GetControlMessages(queue_message);
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages = factory->GetControlMessages(queue_message);
unsigned int expected0 = 0;
EXPECT_EQ(expected0, control_messages->size());
delete control_message;
delete control_messages;
delete factory;
}
} */

View File

@ -56,36 +56,37 @@ TEST(GNSSFlowgraph, InstantiateConnectStartStop)
config->set_property("SignalSource.filename", filename);
config->set_property("SignalConditioner.implementation", "Pass_Through");
config->set_property("Channels.count", "2");
config->set_property("Channels.acquisition.implementation", "Pass_Through");
config->set_property("Channels.tracking.implementation", "Pass_Through");
config->set_property("Channels.telemetry.implementation", "Pass_Through");
config->set_property("Channels.observables.implementation", "Pass_Through");
config->set_property("Acquisition.implementation", "GPS_L1_CA_PCPS_Acquisition");
config->set_property("Tracking.implementation", "GPS_L1_CA_DLL_PLL_Tracking");
config->set_property("TelemetryDecoder.implementation", "GPS_L1_CA_Telemetry_Decoder");
//config->set_property("Channels.observables.implementation", "Pass_Through");
config->set_property("Observables.implementation", "GPS_L1_CA_Observables");
config->set_property("PVT.implementation", "GPS_L1_CA_PVT");
config->set_property("OutputFilter.implementation", "Null_Sink_Output_Filter");
GNSSFlowgraph* flowgraph = new GNSSFlowgraph(config, gr::msg_queue::make(0));
EXPECT_STREQ("File_Signal_Source", flowgraph->signal_source()->implementation().c_str());
EXPECT_STREQ("Pass_Through", flowgraph->signal_conditioner()->implementation().c_str());
EXPECT_STREQ("Channel", flowgraph->channel(0)->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(0))->acquisition()->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(0))->tracking()->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(0))->telemetry()->implementation().c_str());
EXPECT_STREQ("Channel", flowgraph->channel(1)->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(1))->acquisition()->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(1))->tracking()->implementation().c_str());
EXPECT_STREQ("Pass_Through", ((Channel*)flowgraph->channel(1))->telemetry()->implementation().c_str());
EXPECT_STREQ("GPS_L1_CA_Observables", flowgraph->observables()->implementation().c_str());
EXPECT_STREQ("GPS_L1_CA_PVT", flowgraph->pvt()->implementation().c_str());
EXPECT_STREQ("Null_Sink_Output_Filter", flowgraph->output_filter()->implementation().c_str());
EXPECT_NO_THROW(flowgraph->connect());
std::shared_ptr<GNSSFlowgraph> flowgraph = std::make_shared<GNSSFlowgraph>(config, gr::msg_queue::make(0));
flowgraph->set_configuration(config);
EXPECT_NO_THROW(flowgraph->connect());
EXPECT_TRUE(flowgraph->connected());
EXPECT_STREQ("File_Signal_Source", flowgraph->sig_source_->implementation().c_str());
EXPECT_STREQ("Pass_Through", flowgraph->sig_conditioner_->implementation().c_str());
EXPECT_STREQ("Channel", flowgraph->channels_.at(0)->implementation().c_str());
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(0)->acquisition()->implementation().c_str()));
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(0)->tracking()->implementation().c_str());
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(0)->telemetry()->implementation().c_str());
EXPECT_STREQ("Channel", flowgraph->channels_.at(1)->implementation().c_str());
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(1)->acquisition()->implementation().c_str());
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(1)->tracking()->implementation().c_str());
// EXPECT_STREQ("Pass_Through", (flowgraph->channel(1)->telemetry()->implementation().c_str());
EXPECT_STREQ("GPS_L1_CA_Observables", flowgraph->observables_->implementation().c_str());
EXPECT_STREQ("GPS_L1_CA_PVT", flowgraph->pvt_->implementation().c_str());
EXPECT_STREQ("Null_Sink_Output_Filter", flowgraph->output_filter_->implementation().c_str());
EXPECT_NO_THROW(flowgraph->start());
EXPECT_TRUE(flowgraph->running());
flowgraph->stop();
EXPECT_FALSE(flowgraph->running());
delete flowgraph;
//delete flowgraph;
}

View File

@ -1,12 +1,12 @@
/*!
* \file file_output_filter_test.cc
* \brief This class implements a Unit Test for the class FileOutputFilter.
* \author Carlos Avilés, 2010. carlos.avilesr(at)googlemail.com
* \author Carlos Aviles, 2010. carlos.avilesr(at)googlemail.com
*
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2012 (see AUTHORS file for a list of contributors)
* Copyright (C) 2010-2014 (see AUTHORS file for a list of contributors)
*
* GNSS-SDR is a software defined Global Navigation
* Satellite Systems receiver
@ -35,11 +35,13 @@
TEST(FileOutputFilter, Instantiate)
{
InMemoryConfiguration* config = new InMemoryConfiguration();
std::shared_ptr<InMemoryConfiguration> config = std::make_shared<InMemoryConfiguration>();
std::string path = std::string(TEST_PATH);
std::string file = path + "data/output.dat";
config->set_property("Test.filename", file);
config->set_property("Test.item_type", "float");
FileOutputFilter *output_filter = new FileOutputFilter(config, "Test", 1, 0);
delete output_filter;
std::unique_ptr<FileOutputFilter> output_filter(new FileOutputFilter(config.get(), "Test", 1, 0));
unsigned int res = 0;
if (output_filter) res = 1;
ASSERT_EQ(1, res);
}

View File

@ -39,7 +39,7 @@
TEST(FileSignalSource, Instantiate)
{
boost::shared_ptr<gr::msg_queue> queue = gr::msg_queue::make(0);
InMemoryConfiguration* config = new InMemoryConfiguration();
std::shared_ptr<InMemoryConfiguration> config = std::make_shared<InMemoryConfiguration>();
config->set_property("Test.samples", "0");
config->set_property("Test.sampling_frequency", "0");
@ -49,19 +49,16 @@ TEST(FileSignalSource, Instantiate)
config->set_property("Test.item_type", "gr_complex");
config->set_property("Test.repeat", "false");
FileSignalSource *signal_source = new FileSignalSource(config, "Test", 1, 1, queue);
std::unique_ptr<FileSignalSource> signal_source(new FileSignalSource(config.get(), "Test", 1, 1, queue));
//EXPECT_STREQ("../src/tests/signal_samples/GPS_L1_CA_ID_1_Fs_4Msps_2ms.dat", signal_source->filename().c_str());
EXPECT_STREQ("gr_complex", signal_source->item_type().c_str());
EXPECT_TRUE(signal_source->repeat() == false);
delete signal_source;
}
TEST(FileSignalSource, InstantiateFileNotExists)
{
boost::shared_ptr<gr::msg_queue> queue = gr::msg_queue::make(0);
InMemoryConfiguration* config = new InMemoryConfiguration();
std::shared_ptr<InMemoryConfiguration> config = std::make_shared<InMemoryConfiguration>();
config->set_property("Test.samples", "0");
config->set_property("Test.sampling_frequency", "0");
@ -69,5 +66,5 @@ TEST(FileSignalSource, InstantiateFileNotExists)
config->set_property("Test.item_type", "gr_complex");
config->set_property("Test.repeat", "false");
EXPECT_THROW(new FileSignalSource(config, "Test", 1, 1, queue), std::exception);
EXPECT_THROW(auto uptr(new FileSignalSource(config.get(), "Test", 1, 1, queue)), std::exception);
}

View File

@ -51,22 +51,22 @@ protected:
{
queue = gr::msg_queue::make(0);
top_block = gr::make_top_block("Fir filter test");
config = new InMemoryConfiguration();
config = std::make_shared<InMemoryConfiguration>();
item_size = sizeof(gr_complex);
}
~Fir_Filter_Test()
{
delete config;
}
{}
void init();
boost::shared_ptr<gr::msg_queue> queue;
gr::top_block_sptr top_block;
InMemoryConfiguration* config;
std::shared_ptr<InMemoryConfiguration> config;
size_t item_size;
};
void Fir_Filter_Test::init()
{
config->set_property("InputFilter.number_of_taps", "4");
config->set_property("InputFilter.number_of_bands", "2");
@ -92,8 +92,10 @@ void Fir_Filter_Test::init()
TEST_F(Fir_Filter_Test, Instantiate)
{
init();
FirFilter *filter = new FirFilter(config, "InputFilter", 1, 1, queue);
delete filter;
std::unique_ptr<FirFilter> filter(new FirFilter(config.get(), "InputFilter", 1, 1, queue));
unsigned int res = 0;
if (filter) res = 1;
ASSERT_EQ(1, res);
}
@ -107,7 +109,7 @@ TEST_F(Fir_Filter_Test, ConnectAndRun)
init();
FirFilter *filter = new FirFilter(config, "InputFilter", 1, 1, queue);
std::shared_ptr<FirFilter> filter = std::make_shared<FirFilter>(config.get(), "InputFilter", 1, 1, queue);
ASSERT_NO_THROW( {
filter->connect(top_block);
@ -126,8 +128,6 @@ TEST_F(Fir_Filter_Test, ConnectAndRun)
top_block->run(); // Start threads and wait
gettimeofday(&tv, NULL);
end = tv.tv_sec *1000000 + tv.tv_usec;
}) << "Failure running he top_block."<< std::endl;
std::cout << "Filtered " << nsamples << " samples in " << (end-begin) << " microseconds" << std::endl;
delete filter;
}) << "Failure running the top_block." << std::endl;
//std::cout << "Filtered " << nsamples << " samples in " << (end-begin) << " microseconds" << std::endl;
}

View File

@ -43,7 +43,7 @@
#include "observables_interface.h"
#include "pvt_interface.h"
#include "gnss_block_factory.h"
#include "channel.h"
TEST(GNSS_Block_Factory_Test, InstantiateFileSignalSource)
{
@ -53,11 +53,13 @@ TEST(GNSS_Block_Factory_Test, InstantiateFileSignalSource)
std::string filename = path + "signal_samples/GPS_L1_CA_ID_1_Fs_4Msps_2ms.dat";
configuration->set_property("SignalSource.filename", filename);
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
// Example of a factory as a shared_ptr
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *signal_source = factory->GetSignalSource(configuration, queue);
// Example of a block as a shared_ptr
std::shared_ptr<GNSSBlockInterface> signal_source = factory->GetSignalSource(configuration, queue);
LOG(INFO) << "signal source created";
EXPECT_STREQ("SignalSource", signal_source->role().c_str());
EXPECT_STREQ("File_Signal_Source", signal_source->implementation().c_str());
delete signal_source;
}
@ -66,11 +68,12 @@ TEST(GNSS_Block_Factory_Test, InstantiateUHDSignalSource)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("SignalSource.implementation", "UHD_Signal_Source");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *signal_source = factory->GetSignalSource(configuration, queue);
// Example of a factory created with auto
auto factory = new GNSSBlockFactory();
// Example of a block created with auto
auto signal_source = factory->GetSignalSource(configuration, queue);
EXPECT_STREQ("SignalSource", signal_source->role().c_str());
EXPECT_STREQ("UHD_Signal_Source", signal_source->implementation().c_str());
delete signal_source;
}
@ -79,12 +82,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateWrongSignalSource)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("SignalSource.implementation", "Pepito");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
GNSSBlockFactory *factory = new GNSSBlockFactory();
GNSSBlockInterface *signal_source = factory->GetSignalSource(configuration, queue);
EXPECT_EQ(NULL, signal_source);
delete factory;
// Example of a factory as a unique_ptr
std::unique_ptr<GNSSBlockFactory> factory;
// Example of a block as a unique_ptr
std::unique_ptr<GNSSBlockInterface> signal_source = factory->GetSignalSource(configuration, queue);
EXPECT_EQ(nullptr, signal_source);
}
@ -93,14 +95,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateSignalConditioner)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("SignalConditioner.implementation", "Signal_Conditioner");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *signal_conditioner = factory->GetSignalConditioner(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> signal_conditioner = factory->GetSignalConditioner(configuration, queue);
EXPECT_STREQ("SignalConditioner", signal_conditioner->role().c_str());
EXPECT_STREQ("Signal_Conditioner", signal_conditioner->implementation().c_str());
delete signal_conditioner;
}
@ -130,13 +128,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateFIRFilter)
configuration->set_property("InputFilter.filter_type", "bandpass");
configuration->set_property("InputFilter.grid_density", "16");
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *input_filter = factory->GetBlock(configuration, "InputFilter", "Fir_Filter", 1,1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> input_filter = factory->GetBlock(configuration, "InputFilter", "Fir_Filter", 1,1, queue);
EXPECT_STREQ("InputFilter", input_filter->role().c_str());
EXPECT_STREQ("Fir_Filter", input_filter->implementation().c_str());
delete input_filter;
}
TEST(GNSS_Block_Factory_Test, InstantiateFreqXlatingFIRFilter)
@ -167,14 +163,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateFreqXlatingFIRFilter)
configuration->set_property("InputFilter.sampling_frequency","4000000");
configuration->set_property("InputFilter.IF","34000");
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *input_filter = factory->GetBlock(configuration, "InputFilter", "Freq_Xlating_Fir_Filter", 1,1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> input_filter = factory->GetBlock(configuration, "InputFilter", "Freq_Xlating_Fir_Filter", 1,1, queue);
EXPECT_STREQ("InputFilter", input_filter->role().c_str());
EXPECT_STREQ("Freq_Xlating_Fir_Filter", input_filter->implementation().c_str());
delete input_filter;
}
TEST(GNSS_Block_Factory_Test, InstantiateDirectResampler)
@ -182,14 +175,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateDirectResampler)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Resampler.implementation", "Direct_Resampler");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *resampler = factory->GetBlock(configuration, "Resampler", "Direct_Resampler", 1,1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> resampler = factory->GetBlock(configuration, "Resampler", "Direct_Resampler", 1,1, queue);
EXPECT_STREQ("Resampler", resampler->role().c_str());
EXPECT_STREQ("Direct_Resampler", resampler->implementation().c_str());
delete resampler;
}
TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaPcpsAcquisition)
@ -197,14 +186,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaPcpsAcquisition)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Acquisition.implementation", "GPS_L1_CA_PCPS_Acquisition");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
AcquisitionInterface *acquisition = (AcquisitionInterface*)factory->GetBlock(configuration, "Acquisition", "GPS_L1_CA_PCPS_Acquisition", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> acq_ = factory->GetBlock(configuration, "Acquisition", "GPS_L1_CA_PCPS_Acquisition", 1, 1, queue);
std::shared_ptr<AcquisitionInterface> acquisition = std::dynamic_pointer_cast<AcquisitionInterface>(acq_);
EXPECT_STREQ("Acquisition", acquisition->role().c_str());
EXPECT_STREQ("GPS_L1_CA_PCPS_Acquisition", acquisition->implementation().c_str());
delete acquisition;
}
@ -213,14 +199,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGalileoE1PcpsAmbiguousAcquisition)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Acquisition.implementation", "Galileo_E1_PCPS_Ambiguous_Acquisition");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
AcquisitionInterface *acquisition = (AcquisitionInterface*)factory->GetBlock(configuration, "Acquisition", "Galileo_E1_PCPS_Ambiguous_Acquisition", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> acq_ = factory->GetBlock(configuration, "Acquisition", "Galileo_E1_PCPS_Ambiguous_Acquisition", 1, 1, queue);
std::shared_ptr<AcquisitionInterface> acquisition = std::dynamic_pointer_cast<AcquisitionInterface>(acq_);
EXPECT_STREQ("Acquisition", acquisition->role().c_str());
EXPECT_STREQ("Galileo_E1_PCPS_Ambiguous_Acquisition", acquisition->implementation().c_str());
delete acquisition;
}
@ -229,14 +212,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaDllFllPllTracking)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Tracking.implementation", "GPS_L1_CA_DLL_FLL_PLL_Tracking");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
TrackingInterface *tracking = (TrackingInterface*)factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_DLL_FLL_PLL_Tracking", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> trk_ = factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_DLL_FLL_PLL_Tracking", 1, 1, queue);
std::shared_ptr<TrackingInterface> tracking = std::dynamic_pointer_cast<TrackingInterface>(trk_);
EXPECT_STREQ("Tracking", tracking->role().c_str());
EXPECT_STREQ("GPS_L1_CA_DLL_FLL_PLL_Tracking", tracking->implementation().c_str());
delete tracking;
}
@ -245,14 +225,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaDllPllTracking)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Tracking.implementation", "GPS_L1_CA_DLL_PLL_Tracking");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
TrackingInterface *tracking = (TrackingInterface*)factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_DLL_PLL_Tracking", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> trk_ = factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_DLL_PLL_Tracking", 1, 1, queue);
std::shared_ptr<TrackingInterface> tracking = std::dynamic_pointer_cast<TrackingInterface>(trk_);
EXPECT_STREQ("Tracking", tracking->role().c_str());
EXPECT_STREQ("GPS_L1_CA_DLL_PLL_Tracking", tracking->implementation().c_str());
delete tracking;
}
@ -261,14 +238,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaTcpConnectorTracking)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Tracking.implementation", "GPS_L1_CA_TCP_CONNECTOR_Tracking");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
TrackingInterface *tracking = (TrackingInterface*)factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_TCP_CONNECTOR_Tracking", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> trk_ = factory->GetBlock(configuration, "Tracking", "GPS_L1_CA_TCP_CONNECTOR_Tracking", 1, 1, queue);
std::shared_ptr<TrackingInterface> tracking = std::dynamic_pointer_cast<TrackingInterface>(trk_);
EXPECT_STREQ("Tracking", tracking->role().c_str());
EXPECT_STREQ("GPS_L1_CA_TCP_CONNECTOR_Tracking", tracking->implementation().c_str());
delete tracking;
}
@ -277,14 +251,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGalileoE1DllPllVemlTracking)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Tracking.implementation", "Galileo_E1_DLL_PLL_VEML_Tracking");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
TrackingInterface *tracking = (TrackingInterface*)factory->GetBlock(configuration, "Tracking", "Galileo_E1_DLL_PLL_VEML_Tracking", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> trk_ = factory->GetBlock(configuration, "Tracking", "Galileo_E1_DLL_PLL_VEML_Tracking", 1, 1, queue);
std::shared_ptr<TrackingInterface> tracking = std::dynamic_pointer_cast<TrackingInterface>(trk_);
EXPECT_STREQ("Tracking", tracking->role().c_str());
EXPECT_STREQ("Galileo_E1_DLL_PLL_VEML_Tracking", tracking->implementation().c_str());
delete tracking;
}
@ -293,42 +264,29 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaTelemetryDecoder)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("TelemetryDecoder.implementation", "GPS_L1_CA_Telemetry_Decoder");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
TelemetryDecoderInterface *telemetry_decoder = (TelemetryDecoderInterface*)factory->GetBlock(configuration, "TelemetryDecoder", "GPS_L1_CA_Telemetry_Decoder", 1, 1, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> telemetry_decoder = factory->GetBlock(configuration, "TelemetryDecoder", "GPS_L1_CA_Telemetry_Decoder", 1, 1, queue);
EXPECT_STREQ("TelemetryDecoder", telemetry_decoder->role().c_str());
EXPECT_STREQ("GPS_L1_CA_Telemetry_Decoder", telemetry_decoder->implementation().c_str());
delete telemetry_decoder;
}
TEST(GNSS_Block_Factory_Test, InstantiateChannels)
{
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Channels.count", "2");
configuration->set_property("Channels.in_acquisition", "2");
configuration->set_property("Tracking.implementation","GPS_L1_CA_DLL_FLL_PLL_Tracking");
configuration->set_property("TelemetryDecoder.implementation","GPS_L1_CA_Telemetry_Decoder");
configuration->set_property("Channel0.item_type", "gr_complex");
configuration->set_property("Acquisition0.implementation", "GPS_L1_CA_PCPS_Acquisition");
configuration->set_property("Channel1.item_type", "gr_complex");
configuration->set_property("Acquisition1.implementation", "GPS_L1_CA_PCPS_Acquisition");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
std::vector<GNSSBlockInterface*>* channels = factory->GetChannels(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> channels = std::move(factory->GetChannels(configuration, queue));
EXPECT_EQ((unsigned int) 2, channels->size());
;
for(unsigned int i=0 ; i<channels->size() ; i++) delete channels->at(i);
channels->clear();
delete channels;
channels->erase(channels->begin(), channels->end());
}
@ -337,13 +295,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateObservables)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Observables.implementation", "Pass_Through");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
ObservablesInterface *observables = (ObservablesInterface*)factory->GetObservables(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
auto observables = factory->GetObservables(configuration, queue);
EXPECT_STREQ("Observables", observables->role().c_str());
EXPECT_STREQ("Pass_Through", observables->implementation().c_str());
delete observables;
}
@ -352,43 +307,24 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaObservables)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Observables.implementation", "GPS_L1_CA_Observables");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
ObservablesInterface *observables = (ObservablesInterface*)factory->GetObservables(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> observables = factory->GetObservables(configuration, queue);
EXPECT_STREQ("Observables", observables->role().c_str());
EXPECT_STREQ("GPS_L1_CA_Observables", observables->implementation().c_str());
delete observables;
}
TEST(GNSS_Block_Factory_Test, InstantiateWrongObservables)
{
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("Observables.implementation", "Pepito");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
ObservablesInterface *observables = (ObservablesInterface*)factory->GetObservables(configuration, queue);
EXPECT_EQ(NULL, observables);
delete observables;
}
TEST(GNSS_Block_Factory_Test, InstantiatePvt)
{
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("PVT.implementation", "Pass_Through");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
PvtInterface *pvt = (PvtInterface*)factory->GetPVT(configuration, queue);
EXPECT_STREQ("PVT", pvt->role().c_str());
EXPECT_STREQ("Pass_Through", pvt->implementation().c_str());
delete pvt;
std::unique_ptr<GNSSBlockFactory> factory;
auto pvt_ = factory->GetPVT(configuration, queue);
EXPECT_STREQ("PVT", pvt_->role().c_str());
EXPECT_STREQ("Pass_Through", pvt_->implementation().c_str());
}
@ -397,14 +333,11 @@ TEST(GNSS_Block_Factory_Test, InstantiateGpsL1CaPvt)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("PVT.implementation", "GPS_L1_CA_PVT");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
PvtInterface *pvt = (PvtInterface*)factory->GetPVT(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> pvt_ = factory->GetPVT(configuration, queue);
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());
delete pvt;
}
@ -413,13 +346,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateWrongPvt)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("PVT.implementation", "Pepito");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
PvtInterface *pvt = (PvtInterface*)factory->GetPVT(configuration, queue);
EXPECT_EQ(NULL, pvt);
delete pvt;
std::unique_ptr<GNSSBlockFactory> factory;
std::shared_ptr<GNSSBlockInterface> pvt_ = factory->GetPVT(configuration, queue);
std::shared_ptr<PvtInterface> pvt = std::dynamic_pointer_cast<PvtInterface>(pvt_);
EXPECT_EQ(nullptr, pvt);
}
@ -429,14 +359,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateNullSinkOutputFilter)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("OutputFilter.implementation", "Null_Sink_Output_Filter");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *output_filter = factory->GetOutputFilter(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> output_filter = factory->GetOutputFilter(configuration, queue);
EXPECT_STREQ("OutputFilter", output_filter->role().c_str());
EXPECT_STREQ("Null_Sink_Output_Filter", output_filter->implementation().c_str());
delete output_filter;
}
@ -445,14 +371,10 @@ TEST(GNSS_Block_Factory_Test, InstantiateFileOutputFilter)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("OutputFilter.implementation", "File_Output_Filter");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *output_filter = factory->GetOutputFilter(configuration, queue);
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> output_filter = factory->GetOutputFilter(configuration, queue);
EXPECT_STREQ("OutputFilter", output_filter->role().c_str());
EXPECT_STREQ("File_Output_Filter", output_filter->implementation().c_str());
delete output_filter;
}
@ -461,10 +383,7 @@ TEST(GNSS_Block_Factory_Test, InstantiateWrongOutputFilter)
std::shared_ptr<InMemoryConfiguration> configuration = std::make_shared<InMemoryConfiguration>();
configuration->set_property("OutputFilter.implementation", "Pepito");
gr::msg_queue::sptr queue = gr::msg_queue::make(0);
std::shared_ptr<GNSSBlockFactory> factory = std::make_shared<GNSSBlockFactory>();
GNSSBlockInterface *output_filter = factory->GetOutputFilter(configuration, queue);
EXPECT_EQ(NULL, output_filter);
delete output_filter;
std::unique_ptr<GNSSBlockFactory> factory;
std::unique_ptr<GNSSBlockInterface> output_filter = factory->GetOutputFilter(configuration, queue);
EXPECT_EQ(nullptr, output_filter);
}

View File

@ -42,8 +42,7 @@ TEST(Rtcm_Printer_Test, Instantiate)
std::string filename = "hello.rtcm";
bool flag_rtcm_tty_port = false;
std::string rtcm_dump_devname = "/dev/pts/4";
Rtcm_Printer *RTCM_printer = new Rtcm_Printer(filename, flag_rtcm_tty_port, rtcm_dump_devname);
delete RTCM_printer;
std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, flag_rtcm_tty_port, rtcm_dump_devname));
}
TEST(Rtcm_Printer_Test, Instantiate_and_Run)
@ -68,10 +67,9 @@ TEST(Rtcm_Printer_Test, Instantiate_and_Run)
bool flag_rtcm_tty_port = false;
std::string rtcm_dump_devname = "/dev/pts/4";
Rtcm_Printer *RTCM_printer = new Rtcm_Printer(filename, flag_rtcm_tty_port, rtcm_dump_devname);
std::unique_ptr<Rtcm_Printer> RTCM_printer(new Rtcm_Printer(filename, flag_rtcm_tty_port, rtcm_dump_devname));
std::string reference_msg = "D300133ED7D30202980EDEEF34B4BD62AC0941986F33360B98";
std::string testing_msg = RTCM_printer->print_M1005_test();
EXPECT_EQ(reference_msg, testing_msg);
delete RTCM_printer;
}

View File

@ -155,10 +155,10 @@ bool front_end_capture(std::shared_ptr<ConfigurationInterface> configuration)
queue = gr::msg_queue::make(0);
top_block = gr::make_top_block("Acquisition test");
GNSSBlockInterface *source;
std::shared_ptr<GNSSBlockInterface> source;
source = block_factory.GetSignalSource(configuration, queue);
GNSSBlockInterface *conditioner = block_factory.GetSignalConditioner(configuration,queue);
std::shared_ptr<GNSSBlockInterface> conditioner = block_factory.GetSignalConditioner(configuration,queue);
gr::block_sptr sink;
sink = gr::blocks::file_sink::make(sizeof(gr_complex), "tmp_capture.dat");
@ -192,7 +192,7 @@ bool front_end_capture(std::shared_ptr<ConfigurationInterface> configuration)
}
//delete conditioner;
delete source;
//delete source;
return true;
}