1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-01-05 15:00:33 +00:00

Merge branch 'next' of https://gitlab.com/gnss-sdr/gnss-sdr into next

This commit is contained in:
Carles Fernandez 2019-02-14 23:45:04 +01:00
commit cdd979115f
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
63 changed files with 194 additions and 195 deletions

View File

@ -1,5 +1,5 @@
--- ---
Checks: '-*,boost-use-to-string,cert-dcl21-cpp,cert-dcl58-cpp,cert-env33-c,cert-err52-cpp,cert-err60-cpp,cert-flp30-c,clang-analyzer-cplusplus*,cppcoreguidelines-pro-type-static-cast-downcast,cppcoreguidelines-slicing,google-build-namespaces,google-runtime-int,google-runtime-references,misc-misplaced-const,misc-new-delete-overloads,misc-non-copyable-objects,misc-static-assert,misc-throw-by-value-catch-by-reference,misc-uniqueptr-reset-release,modernize-loop-convert,modernize-pass-by-value,modernize-raw-string-literal,modernize-use-auto,modernize-use-bool-literals,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-noexcept,modernize-use-nullptr,performance-faster-string-find,performance-inefficient-algorithm,performance-move-const-arg,performance-type-promotion-in-math-fn,performance-unnecessary-copy-initialization,performance-unnecessary-value-param,readability-container-size-empty,readability-named-parameter,readability-non-const-parameter,readability-string-compare' Checks: '-*,boost-use-to-string,cert-dcl21-cpp,cert-dcl58-cpp,cert-env33-c,cert-err52-cpp,cert-err60-cpp,cert-flp30-c,clang-analyzer-cplusplus*,cppcoreguidelines-pro-type-static-cast-downcast,cppcoreguidelines-slicing,google-build-namespaces,google-runtime-int,misc-misplaced-const,misc-new-delete-overloads,misc-non-copyable-objects,misc-static-assert,misc-throw-by-value-catch-by-reference,misc-uniqueptr-reset-release,modernize-loop-convert,modernize-pass-by-value,modernize-raw-string-literal,modernize-use-auto,modernize-use-bool-literals,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-noexcept,modernize-use-nullptr,performance-faster-string-find,performance-inefficient-algorithm,performance-move-const-arg,performance-type-promotion-in-math-fn,performance-unnecessary-copy-initialization,performance-unnecessary-value-param,readability-container-size-empty,readability-named-parameter,readability-non-const-parameter,readability-string-compare'
WarningsAsErrors: '' WarningsAsErrors: ''
HeaderFilterRegex: '' HeaderFilterRegex: ''
AnalyzeTemporaryDtors: false AnalyzeTemporaryDtors: false
@ -21,8 +21,6 @@ CheckOptions:
value: '_t' value: '_t'
- key: google-runtime-int.UnsignedTypePrefix - key: google-runtime-int.UnsignedTypePrefix
value: uint value: uint
- key: google-runtime-references.WhiteListTypes
value: ''
- key: misc-throw-by-value-catch-by-reference.CheckThrowTemporaries - key: misc-throw-by-value-catch-by-reference.CheckThrowTemporaries
value: '1' value: '1'
- key: modernize-loop-convert.MaxCopySize - key: modernize-loop-convert.MaxCopySize

View File

@ -618,7 +618,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -704,7 +704,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -734,7 +734,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -764,7 +764,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -794,7 +794,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -824,7 +824,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -854,7 +854,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -914,7 +914,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -944,7 +944,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -974,7 +974,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -1004,7 +1004,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -1064,7 +1064,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -1124,7 +1124,7 @@ rtklib_pvt_cc::~rtklib_pvt_cc()
{ {
LOG(WARNING) << "Problem opening output XML file"; LOG(WARNING) << "Problem opening output XML file";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
} }
@ -1176,7 +1176,7 @@ bool rtklib_pvt_cc::save_gnss_synchro_map_xml(const std::string& file_name)
xml << boost::serialization::make_nvp("GNSS-SDR_gnss_synchro_map", gnss_observables_map); xml << boost::serialization::make_nvp("GNSS-SDR_gnss_synchro_map", gnss_observables_map);
LOG(INFO) << "Saved gnss_sychro map data"; LOG(INFO) << "Saved gnss_sychro map data";
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
LOG(WARNING) << e.what(); LOG(WARNING) << e.what();
return false; return false;
@ -1201,7 +1201,7 @@ bool rtklib_pvt_cc::load_gnss_synchro_map_xml(const std::string& file_name)
xml >> boost::serialization::make_nvp("GNSS-SDR_gnss_synchro_map", gnss_observables_map); xml >> boost::serialization::make_nvp("GNSS-SDR_gnss_synchro_map", gnss_observables_map);
//std::cout << "Loaded gnss_synchro map data with " << gnss_synchro_map.size() << " pseudoranges" << std::endl; //std::cout << "Loaded gnss_synchro map data with " << gnss_synchro_map.size() << " pseudoranges" << std::endl;
} }
catch (std::exception& e) catch (const std::exception& e)
{ {
std::cout << e.what() << "File: " << file_name; std::cout << e.what() << "File: " << file_name;
return false; return false;

View File

@ -34,7 +34,7 @@
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>
Monitor_Pvt_Udp_Sink::Monitor_Pvt_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port) : socket{io_service} Monitor_Pvt_Udp_Sink::Monitor_Pvt_Udp_Sink(std::vector<std::string> addresses, const uint16_t& port) : socket{io_service}
{ {
for (const auto& address : addresses) for (const auto& address : addresses)
{ {

View File

@ -38,7 +38,7 @@
class Monitor_Pvt_Udp_Sink class Monitor_Pvt_Udp_Sink
{ {
public: public:
Monitor_Pvt_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port); Monitor_Pvt_Udp_Sink(std::vector<std::string> addresses, const uint16_t &port);
bool write_monitor_pvt(Monitor_Pvt monitor_pvt); bool write_monitor_pvt(Monitor_Pvt monitor_pvt);
private: private:

View File

@ -269,7 +269,7 @@ bool Nmea_Printer::Print_Nmea_Line(const std::shared_ptr<rtklib_solver>& pvt_dat
} }
char Nmea_Printer::checkSum(const std::string& sentence) char Nmea_Printer::checkSum(std::string sentence)
{ {
char check = 0; char check = 0;
// iterate over the string, XOR each byte with the total sum: // iterate over the string, XOR each byte with the total sum:

View File

@ -82,7 +82,7 @@ private:
std::string get_UTC_NMEA_time(boost::posix_time::ptime d_position_UTC_time); std::string get_UTC_NMEA_time(boost::posix_time::ptime d_position_UTC_time);
std::string longitude_to_hm(double longitude); std::string longitude_to_hm(double longitude);
std::string latitude_to_hm(double lat); std::string latitude_to_hm(double lat);
char checkSum(const std::string& sentence); char checkSum(std::string sentence);
bool print_avg_pos; bool print_avg_pos;
bool d_flag_nmea_output_file; bool d_flag_nmea_output_file;
}; };

View File

@ -93,11 +93,11 @@ rtklib_solver::rtklib_solver(int nchannels, std::string dump_filename, bool flag
{ {
try try
{ {
d_dump_file.exceptions(std::ifstream::failbit | std::ifstream::badbit); d_dump_file.exceptions(std::ofstream::failbit | std::ofstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary); d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str(); LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str();
} }
catch (const std::ifstream::failure &e) catch (const std::ofstream::failure &e)
{ {
LOG(WARNING) << "Exception opening RTKLIB dump file " << e.what(); LOG(WARNING) << "Exception opening RTKLIB dump file " << e.what();
} }

View File

@ -39,16 +39,15 @@
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
BeidouB1iPcpsAcquisition::BeidouB1iPcpsAcquisition( BeidouB1iPcpsAcquisition::BeidouB1iPcpsAcquisition(
ConfigurationInterface* configuration, ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams) : role_(std::move(role)), unsigned int out_streams) : role_(role),
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {

View File

@ -55,7 +55,7 @@ class BeidouB1iPcpsAcquisition : public AcquisitionInterface
{ {
public: public:
BeidouB1iPcpsAcquisition(ConfigurationInterface* configuration, BeidouB1iPcpsAcquisition(ConfigurationInterface* configuration,
std::string role, unsigned int in_streams, const std::string& role, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);
virtual ~BeidouB1iPcpsAcquisition(); virtual ~BeidouB1iPcpsAcquisition();

View File

@ -37,7 +37,6 @@
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
@ -45,9 +44,9 @@ using google::LogMessage;
GalileoE1PcpsAmbiguousAcquisition::GalileoE1PcpsAmbiguousAcquisition( GalileoE1PcpsAmbiguousAcquisition::GalileoE1PcpsAmbiguousAcquisition(
ConfigurationInterface* configuration, ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams) : role_(std::move(role)), unsigned int out_streams) : role_(role),
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {

View File

@ -52,7 +52,7 @@ class GalileoE1PcpsAmbiguousAcquisition : public AcquisitionInterface
{ {
public: public:
GalileoE1PcpsAmbiguousAcquisition(ConfigurationInterface* configuration, GalileoE1PcpsAmbiguousAcquisition(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -41,7 +41,6 @@
#include "gps_sdr_signal_processing.h" #include "gps_sdr_signal_processing.h"
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
@ -49,9 +48,9 @@ using google::LogMessage;
GpsL1CaPcpsAcquisition::GpsL1CaPcpsAcquisition( GpsL1CaPcpsAcquisition::GpsL1CaPcpsAcquisition(
ConfigurationInterface* configuration, ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams) : role_(std::move(role)), unsigned int out_streams) : role_(role),
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {

View File

@ -56,7 +56,7 @@ class GpsL1CaPcpsAcquisition : public AcquisitionInterface
{ {
public: public:
GpsL1CaPcpsAcquisition(ConfigurationInterface* configuration, GpsL1CaPcpsAcquisition(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -39,7 +39,6 @@
#include "gps_l2c_signal.h" #include "gps_l2c_signal.h"
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
@ -47,9 +46,9 @@ using google::LogMessage;
GpsL2MPcpsAcquisition::GpsL2MPcpsAcquisition( GpsL2MPcpsAcquisition::GpsL2MPcpsAcquisition(
ConfigurationInterface* configuration, ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams) : role_(std::move(role)), unsigned int out_streams) : role_(role),
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {

View File

@ -53,7 +53,7 @@ class GpsL2MPcpsAcquisition : public AcquisitionInterface
{ {
public: public:
GpsL2MPcpsAcquisition(ConfigurationInterface* configuration, GpsL2MPcpsAcquisition(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -39,7 +39,6 @@
#include "gps_l5_signal.h" #include "gps_l5_signal.h"
#include <boost/math/distributions/exponential.hpp> #include <boost/math/distributions/exponential.hpp>
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
@ -47,9 +46,9 @@ using google::LogMessage;
GpsL5iPcpsAcquisition::GpsL5iPcpsAcquisition( GpsL5iPcpsAcquisition::GpsL5iPcpsAcquisition(
ConfigurationInterface* configuration, ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams) : role_(std::move(role)), unsigned int out_streams) : role_(role),
in_streams_(in_streams), in_streams_(in_streams),
out_streams_(out_streams) out_streams_(out_streams)
{ {

View File

@ -53,7 +53,7 @@ class GpsL5iPcpsAcquisition : public AcquisitionInterface
{ {
public: public:
GpsL5iPcpsAcquisition(ConfigurationInterface* configuration, GpsL5iPcpsAcquisition(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -53,14 +53,14 @@ galileo_e5a_noncoherentIQ_acquisition_caf_cc_sptr galileo_e5a_noncoherentIQ_make
int samples_per_ms, int samples_per_code, int samples_per_ms, int samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
bool both_signal_components_, bool both_signal_components_,
int CAF_window_hz_, int CAF_window_hz_,
int Zero_padding_) int Zero_padding_)
{ {
return galileo_e5a_noncoherentIQ_acquisition_caf_cc_sptr( return galileo_e5a_noncoherentIQ_acquisition_caf_cc_sptr(
new galileo_e5a_noncoherentIQ_acquisition_caf_cc(sampled_ms, max_dwells, doppler_max, fs_in, samples_per_ms, new galileo_e5a_noncoherentIQ_acquisition_caf_cc(sampled_ms, max_dwells, doppler_max, fs_in, samples_per_ms,
samples_per_code, bit_transition_flag, dump, dump_filename, both_signal_components_, CAF_window_hz_, Zero_padding_)); samples_per_code, bit_transition_flag, dump, std::move(dump_filename), both_signal_components_, CAF_window_hz_, Zero_padding_));
} }
@ -73,7 +73,7 @@ galileo_e5a_noncoherentIQ_acquisition_caf_cc::galileo_e5a_noncoherentIQ_acquisit
int samples_per_code, int samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
bool both_signal_components_, bool both_signal_components_,
int CAF_window_hz_, int CAF_window_hz_,
int Zero_padding_) : gr::block("galileo_e5a_noncoherentIQ_acquisition_caf_cc", int Zero_padding_) : gr::block("galileo_e5a_noncoherentIQ_acquisition_caf_cc",
@ -153,7 +153,7 @@ galileo_e5a_noncoherentIQ_acquisition_caf_cc::galileo_e5a_noncoherentIQ_acquisit
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_doppler_resolution = 0; d_doppler_resolution = 0;
d_threshold = 0; d_threshold = 0;

View File

@ -56,7 +56,7 @@ galileo_e5a_noncoherentIQ_make_acquisition_caf_cc(unsigned int sampled_ms,
int samples_per_ms, int samples_per_code, int samples_per_ms, int samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
bool both_signal_components_, bool both_signal_components_,
int CAF_window_hz_, int CAF_window_hz_,
int Zero_padding_); int Zero_padding_);
@ -78,7 +78,7 @@ private:
int samples_per_ms, int samples_per_code, int samples_per_ms, int samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
bool both_signal_components_, bool both_signal_components_,
int CAF_window_hz_, int CAF_window_hz_,
int Zero_padding_); int Zero_padding_);
@ -90,7 +90,7 @@ private:
int samples_per_ms, int samples_per_code, int samples_per_ms, int samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
bool both_signal_components_, bool both_signal_components_,
int CAF_window_hz_, int CAF_window_hz_,
int Zero_padding_); int Zero_padding_);

View File

@ -47,11 +47,11 @@ galileo_pcps_8ms_acquisition_cc_sptr galileo_pcps_8ms_make_acquisition_cc(
int64_t fs_in, int64_t fs_in,
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, const std::string &dump_filename) bool dump, std::string dump_filename)
{ {
return galileo_pcps_8ms_acquisition_cc_sptr( return galileo_pcps_8ms_acquisition_cc_sptr(
new galileo_pcps_8ms_acquisition_cc(sampled_ms, max_dwells, doppler_max, fs_in, samples_per_ms, new galileo_pcps_8ms_acquisition_cc(sampled_ms, max_dwells, doppler_max, fs_in, samples_per_ms,
samples_per_code, dump, dump_filename)); samples_per_code, dump, std::move(dump_filename)));
} }
@ -63,9 +63,9 @@ galileo_pcps_8ms_acquisition_cc::galileo_pcps_8ms_acquisition_cc(
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string &dump_filename) : gr::block("galileo_pcps_8ms_acquisition_cc", std::string dump_filename) : gr::block("galileo_pcps_8ms_acquisition_cc",
gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms), gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms),
gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms)) gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0ULL; // SAMPLE COUNTER d_sample_counter = 0ULL; // SAMPLE COUNTER
@ -95,7 +95,7 @@ galileo_pcps_8ms_acquisition_cc::galileo_pcps_8ms_acquisition_cc(
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_doppler_resolution = 0; d_doppler_resolution = 0;
d_threshold = 0; d_threshold = 0;

View File

@ -51,7 +51,7 @@ galileo_pcps_8ms_make_acquisition_cc(uint32_t sampled_ms,
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
/*! /*!
* \brief This class implements a Parallel Code Phase Search Acquisition for * \brief This class implements a Parallel Code Phase Search Acquisition for
@ -69,7 +69,7 @@ private:
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
galileo_pcps_8ms_acquisition_cc( galileo_pcps_8ms_acquisition_cc(
uint32_t sampled_ms, uint32_t sampled_ms,
@ -79,7 +79,7 @@ private:
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
void calculate_magnitudes( void calculate_magnitudes(
gr_complex* fft_begin, gr_complex* fft_begin,

View File

@ -49,20 +49,20 @@ using google::LogMessage;
pcps_assisted_acquisition_cc_sptr pcps_make_assisted_acquisition_cc( pcps_assisted_acquisition_cc_sptr pcps_make_assisted_acquisition_cc(
int32_t max_dwells, uint32_t sampled_ms, int32_t doppler_max, int32_t doppler_min, int32_t max_dwells, uint32_t sampled_ms, int32_t doppler_max, int32_t doppler_min,
int64_t fs_in, int32_t samples_per_ms, bool dump, int64_t fs_in, int32_t samples_per_ms, bool dump,
const std::string &dump_filename) std::string dump_filename)
{ {
return pcps_assisted_acquisition_cc_sptr( return pcps_assisted_acquisition_cc_sptr(
new pcps_assisted_acquisition_cc(max_dwells, sampled_ms, doppler_max, doppler_min, new pcps_assisted_acquisition_cc(max_dwells, sampled_ms, doppler_max, doppler_min,
fs_in, samples_per_ms, dump, dump_filename)); fs_in, samples_per_ms, dump, std::move(dump_filename)));
} }
pcps_assisted_acquisition_cc::pcps_assisted_acquisition_cc( pcps_assisted_acquisition_cc::pcps_assisted_acquisition_cc(
int32_t max_dwells, uint32_t sampled_ms, int32_t doppler_max, int32_t doppler_min, int32_t max_dwells, uint32_t sampled_ms, int32_t doppler_max, int32_t doppler_min,
int64_t fs_in, int32_t samples_per_ms, bool dump, int64_t fs_in, int32_t samples_per_ms, bool dump,
const std::string &dump_filename) : gr::block("pcps_assisted_acquisition_cc", std::string dump_filename) : gr::block("pcps_assisted_acquisition_cc",
gr::io_signature::make(1, 1, sizeof(gr_complex)), gr::io_signature::make(1, 1, sizeof(gr_complex)),
gr::io_signature::make(0, 0, sizeof(gr_complex))) gr::io_signature::make(0, 0, sizeof(gr_complex)))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0ULL; // SAMPLE COUNTER d_sample_counter = 0ULL; // SAMPLE COUNTER
@ -90,7 +90,7 @@ pcps_assisted_acquisition_cc::pcps_assisted_acquisition_cc(
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_doppler_resolution = 0; d_doppler_resolution = 0;
d_threshold = 0; d_threshold = 0;

View File

@ -67,7 +67,7 @@ pcps_make_assisted_acquisition_cc(
int32_t doppler_min, int32_t doppler_min,
int64_t fs_in, int64_t fs_in,
int32_t samples_per_ms, int32_t samples_per_ms,
bool dump, const std::string& dump_filename); bool dump, std::string dump_filename);
/*! /*!
* \brief This class implements a Parallel Code Phase Search Acquisition. * \brief This class implements a Parallel Code Phase Search Acquisition.
@ -82,12 +82,12 @@ private:
pcps_make_assisted_acquisition_cc(int32_t max_dwells, uint32_t sampled_ms, pcps_make_assisted_acquisition_cc(int32_t max_dwells, uint32_t sampled_ms,
int32_t doppler_max, int32_t doppler_min, int64_t fs_in, int32_t doppler_max, int32_t doppler_min, int64_t fs_in,
int32_t samples_per_ms, bool dump, int32_t samples_per_ms, bool dump,
const std::string& dump_filename); std::string dump_filename);
pcps_assisted_acquisition_cc(int32_t max_dwells, uint32_t sampled_ms, pcps_assisted_acquisition_cc(int32_t max_dwells, uint32_t sampled_ms,
int32_t doppler_max, int32_t doppler_min, int64_t fs_in, int32_t doppler_max, int32_t doppler_min, int64_t fs_in,
int32_t samples_per_ms, bool dump, int32_t samples_per_ms, bool dump,
const std::string& dump_filename); std::string dump_filename);
void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift, void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift,
int32_t doppler_offset); int32_t doppler_offset);

View File

@ -53,11 +53,11 @@ pcps_cccwsr_acquisition_cc_sptr pcps_cccwsr_make_acquisition_cc(
int64_t fs_in, int64_t fs_in,
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, const std::string &dump_filename) bool dump, std::string dump_filename)
{ {
return pcps_cccwsr_acquisition_cc_sptr( return pcps_cccwsr_acquisition_cc_sptr(
new pcps_cccwsr_acquisition_cc(sampled_ms, max_dwells, doppler_max, fs_in, new pcps_cccwsr_acquisition_cc(sampled_ms, max_dwells, doppler_max, fs_in,
samples_per_ms, samples_per_code, dump, dump_filename)); samples_per_ms, samples_per_code, dump, std::move(dump_filename)));
} }
@ -69,9 +69,9 @@ pcps_cccwsr_acquisition_cc::pcps_cccwsr_acquisition_cc(
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string &dump_filename) : gr::block("pcps_cccwsr_acquisition_cc", std::string dump_filename) : gr::block("pcps_cccwsr_acquisition_cc",
gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms), gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms),
gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms)) gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0ULL; // SAMPLE COUNTER d_sample_counter = 0ULL; // SAMPLE COUNTER
@ -105,7 +105,7 @@ pcps_cccwsr_acquisition_cc::pcps_cccwsr_acquisition_cc(
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_doppler_resolution = 0; d_doppler_resolution = 0;
d_threshold = 0; d_threshold = 0;

View File

@ -58,7 +58,7 @@ pcps_cccwsr_make_acquisition_cc(
int32_t samples_per_ms, int32_t samples_per_ms,
int32_t samples_per_code, int32_t samples_per_code,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
/*! /*!
* \brief This class implements a Parallel Code Phase Search Acquisition with * \brief This class implements a Parallel Code Phase Search Acquisition with
@ -71,12 +71,12 @@ private:
pcps_cccwsr_make_acquisition_cc(uint32_t sampled_ms, uint32_t max_dwells, pcps_cccwsr_make_acquisition_cc(uint32_t sampled_ms, uint32_t max_dwells,
uint32_t doppler_max, int64_t fs_in, uint32_t doppler_max, int64_t fs_in,
int32_t samples_per_ms, int32_t samples_per_code, int32_t samples_per_ms, int32_t samples_per_code,
bool dump, const std::string& dump_filename); bool dump, std::string dump_filename);
pcps_cccwsr_acquisition_cc(uint32_t sampled_ms, uint32_t max_dwells, pcps_cccwsr_acquisition_cc(uint32_t sampled_ms, uint32_t max_dwells,
uint32_t doppler_max, int64_t fs_in, uint32_t doppler_max, int64_t fs_in,
int32_t samples_per_ms, int32_t samples_per_code, int32_t samples_per_ms, int32_t samples_per_code,
bool dump, const std::string& dump_filename); bool dump, std::string dump_filename);
void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift, void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift,
int32_t doppler_offset); int32_t doppler_offset);

View File

@ -52,7 +52,7 @@ pcps_quicksync_acquisition_cc_sptr pcps_quicksync_make_acquisition_cc(
int32_t samples_per_code, int32_t samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename) std::string dump_filename)
{ {
return pcps_quicksync_acquisition_cc_sptr( return pcps_quicksync_acquisition_cc_sptr(
new pcps_quicksync_acquisition_cc( new pcps_quicksync_acquisition_cc(
@ -61,7 +61,7 @@ pcps_quicksync_acquisition_cc_sptr pcps_quicksync_make_acquisition_cc(
fs_in, samples_per_ms, fs_in, samples_per_ms,
samples_per_code, samples_per_code,
bit_transition_flag, bit_transition_flag,
dump, dump_filename)); dump, std::move(dump_filename)));
} }
@ -72,9 +72,9 @@ pcps_quicksync_acquisition_cc::pcps_quicksync_acquisition_cc(
int32_t samples_per_ms, int32_t samples_per_code, int32_t samples_per_ms, int32_t samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename) : gr::block("pcps_quicksync_acquisition_cc", std::string dump_filename) : gr::block("pcps_quicksync_acquisition_cc",
gr::io_signature::make(1, 1, (sizeof(gr_complex) * sampled_ms * samples_per_ms)), gr::io_signature::make(1, 1, (sizeof(gr_complex) * sampled_ms * samples_per_ms)),
gr::io_signature::make(0, 0, (sizeof(gr_complex) * sampled_ms * samples_per_ms))) gr::io_signature::make(0, 0, (sizeof(gr_complex) * sampled_ms * samples_per_ms)))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0ULL; // SAMPLE COUNTER d_sample_counter = 0ULL; // SAMPLE COUNTER
@ -114,7 +114,7 @@ pcps_quicksync_acquisition_cc::pcps_quicksync_acquisition_cc(
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_corr_acumulator = nullptr; d_corr_acumulator = nullptr;
d_signal_folded = nullptr; d_signal_folded = nullptr;

View File

@ -76,7 +76,7 @@ pcps_quicksync_make_acquisition_cc(
int32_t samples_per_code, int32_t samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
/*! /*!
* \brief This class implements a Parallel Code Phase Search Acquisition with * \brief This class implements a Parallel Code Phase Search Acquisition with
@ -95,7 +95,7 @@ private:
int32_t samples_per_ms, int32_t samples_per_code, int32_t samples_per_ms, int32_t samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
pcps_quicksync_acquisition_cc(uint32_t folding_factor, pcps_quicksync_acquisition_cc(uint32_t folding_factor,
uint32_t sampled_ms, uint32_t max_dwells, uint32_t sampled_ms, uint32_t max_dwells,
@ -103,7 +103,7 @@ private:
int32_t samples_per_ms, int32_t samples_per_code, int32_t samples_per_ms, int32_t samples_per_code,
bool bit_transition_flag, bool bit_transition_flag,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift, void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift,
int32_t doppler_offset); int32_t doppler_offset);

View File

@ -69,11 +69,11 @@ pcps_tong_acquisition_cc_sptr pcps_tong_make_acquisition_cc(
uint32_t tong_init_val, uint32_t tong_init_val,
uint32_t tong_max_val, uint32_t tong_max_val,
uint32_t tong_max_dwells, uint32_t tong_max_dwells,
bool dump, const std::string &dump_filename) bool dump, std::string dump_filename)
{ {
return pcps_tong_acquisition_cc_sptr( return pcps_tong_acquisition_cc_sptr(
new pcps_tong_acquisition_cc(sampled_ms, doppler_max, fs_in, samples_per_ms, samples_per_code, new pcps_tong_acquisition_cc(sampled_ms, doppler_max, fs_in, samples_per_ms, samples_per_code,
tong_init_val, tong_max_val, tong_max_dwells, dump, dump_filename)); tong_init_val, tong_max_val, tong_max_dwells, dump, std::move(dump_filename)));
} }
@ -87,9 +87,9 @@ pcps_tong_acquisition_cc::pcps_tong_acquisition_cc(
uint32_t tong_max_val, uint32_t tong_max_val,
uint32_t tong_max_dwells, uint32_t tong_max_dwells,
bool dump, bool dump,
const std::string &dump_filename) : gr::block("pcps_tong_acquisition_cc", std::string dump_filename) : gr::block("pcps_tong_acquisition_cc",
gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms), gr::io_signature::make(1, 1, sizeof(gr_complex) * sampled_ms * samples_per_ms),
gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms)) gr::io_signature::make(0, 0, sizeof(gr_complex) * sampled_ms * samples_per_ms))
{ {
this->message_port_register_out(pmt::mp("events")); this->message_port_register_out(pmt::mp("events"));
d_sample_counter = 0ULL; // SAMPLE COUNTER d_sample_counter = 0ULL; // SAMPLE COUNTER
@ -121,7 +121,7 @@ pcps_tong_acquisition_cc::pcps_tong_acquisition_cc(
// For dumping samples into a file // For dumping samples into a file
d_dump = dump; d_dump = dump;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_doppler_resolution = 0; d_doppler_resolution = 0;
d_threshold = 0; d_threshold = 0;

View File

@ -74,7 +74,7 @@ pcps_tong_make_acquisition_cc(
uint32_t tong_max_val, uint32_t tong_max_val,
uint32_t tong_max_dwells, uint32_t tong_max_dwells,
bool dump, bool dump,
const std::string& dump_filename); std::string dump_filename);
/*! /*!
* \brief This class implements a Parallel Code Phase Search Acquisition with * \brief This class implements a Parallel Code Phase Search Acquisition with
@ -88,13 +88,13 @@ private:
int64_t fs_in, int32_t samples_per_ms, int64_t fs_in, int32_t samples_per_ms,
int32_t samples_per_code, uint32_t tong_init_val, int32_t samples_per_code, uint32_t tong_init_val,
uint32_t tong_max_val, uint32_t tong_max_dwells, uint32_t tong_max_val, uint32_t tong_max_dwells,
bool dump, const std::string& dump_filename); bool dump, std::string dump_filename);
pcps_tong_acquisition_cc(uint32_t sampled_ms, uint32_t doppler_max, pcps_tong_acquisition_cc(uint32_t sampled_ms, uint32_t doppler_max,
int64_t fs_in, int32_t samples_per_ms, int64_t fs_in, int32_t samples_per_ms,
int32_t samples_per_code, uint32_t tong_init_val, int32_t samples_per_code, uint32_t tong_init_val,
uint32_t tong_max_val, uint32_t tong_max_dwells, uint32_t tong_max_val, uint32_t tong_max_dwells,
bool dump, const std::string& dump_filename); bool dump, std::string dump_filename);
void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift, void calculate_magnitudes(gr_complex* fft_begin, int32_t doppler_shift,
int32_t doppler_offset); int32_t doppler_offset);

View File

@ -250,10 +250,10 @@ void write_results(const std::vector<volk_gnsssdr_test_results_t> *results, bool
const fs::path config_path(path); const fs::path config_path(path);
// Until we can update the config on a kernel by kernel basis // Until we can update the config on a kernel by kernel basis
// do not overwrite volk_gnsssdr_config when using a regex. // do not overwrite volk_gnsssdr_config when using a regex.
if (!fs::exists(config_path.branch_path())) if (!fs::exists(config_path.parent_path()))
{ {
std::cout << "Creating " << config_path.branch_path() << " ..." << std::endl; std::cout << "Creating " << config_path.parent_path() << " ..." << std::endl;
fs::create_directories(config_path.branch_path()); fs::create_directories(config_path.parent_path());
} }
std::ofstream config; std::ofstream config;

View File

@ -48,12 +48,12 @@
* a boost shared_ptr. This is effectively the public constructor. * a boost shared_ptr. This is effectively the public constructor.
*/ */
signal_generator_c_sptr signal_generator_c_sptr
signal_make_generator_c(const std::vector<std::string> &signal1, const std::vector<std::string> &system, const std::vector<unsigned int> &PRN, signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN,
const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz, const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz,
const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag, const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag,
unsigned int fs_in, unsigned int vector_length, float BW_BB) unsigned int fs_in, unsigned int vector_length, float BW_BB)
{ {
return gnuradio::get_initial_sptr(new signal_generator_c(signal1, system, PRN, CN0_dB, doppler_Hz, delay_chips, delay_sec, return gnuradio::get_initial_sptr(new signal_generator_c(std::move(signal1), std::move(system), PRN, CN0_dB, doppler_Hz, delay_chips, delay_sec,
data_flag, noise_flag, fs_in, vector_length, BW_BB)); data_flag, noise_flag, fs_in, vector_length, BW_BB));
} }

View File

@ -61,7 +61,7 @@ using signal_generator_c_sptr = boost::shared_ptr<signal_generator_c>;
* interface for creating new instances. * interface for creating new instances.
*/ */
signal_generator_c_sptr signal_generator_c_sptr
signal_make_generator_c(const std::vector<std::string> &signal1, const std::vector<std::string> &system, const std::vector<unsigned int> &PRN, signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN,
const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz, const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz,
const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag, const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag,
unsigned int fs_in, unsigned int vector_length, float BW_BB); unsigned int fs_in, unsigned int vector_length, float BW_BB);
@ -80,7 +80,7 @@ private:
/* Create the signal_generator_c object*/ /* Create the signal_generator_c object*/
friend signal_generator_c_sptr friend signal_generator_c_sptr
signal_make_generator_c(const std::vector<std::string> &signal1, const std::vector<std::string> &system, const std::vector<unsigned int> &PRN, signal_make_generator_c(std::vector<std::string> signal1, std::vector<std::string> system, const std::vector<unsigned int> &PRN,
const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz, const std::vector<float> &CN0_dB, const std::vector<float> &doppler_Hz,
const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag, const std::vector<unsigned int> &delay_chips, const std::vector<unsigned int> &delay_sec, bool data_flag, bool noise_flag,
unsigned int fs_in, unsigned int vector_length, float BW_BB); unsigned int fs_in, unsigned int vector_length, float BW_BB);

View File

@ -42,15 +42,14 @@
#include "configuration_interface.h" #include "configuration_interface.h"
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
GlonassL1CaDllPllCAidTracking::GlonassL1CaDllPllCAidTracking( GlonassL1CaDllPllCAidTracking::GlonassL1CaDllPllCAidTracking(
ConfigurationInterface* configuration, std::string role, ConfigurationInterface* configuration, const std::string& role,
unsigned int in_streams, unsigned int out_streams) : role_(std::move(role)), in_streams_(in_streams), out_streams_(out_streams) unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{ {
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ######################## //################# CONFIGURATION PARAMETERS ########################

View File

@ -54,7 +54,7 @@ class GlonassL1CaDllPllCAidTracking : public TrackingInterface
{ {
public: public:
GlonassL1CaDllPllCAidTracking(ConfigurationInterface* configuration, GlonassL1CaDllPllCAidTracking(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -40,15 +40,14 @@
#include "configuration_interface.h" #include "configuration_interface.h"
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
GlonassL2CaDllPllCAidTracking::GlonassL2CaDllPllCAidTracking( GlonassL2CaDllPllCAidTracking::GlonassL2CaDllPllCAidTracking(
ConfigurationInterface* configuration, std::string role, ConfigurationInterface* configuration, const std::string& role,
unsigned int in_streams, unsigned int out_streams) : role_(std::move(role)), in_streams_(in_streams), out_streams_(out_streams) unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{ {
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ######################## //################# CONFIGURATION PARAMETERS ########################

View File

@ -52,7 +52,7 @@ class GlonassL2CaDllPllCAidTracking : public TrackingInterface
{ {
public: public:
GlonassL2CaDllPllCAidTracking(ConfigurationInterface* configuration, GlonassL2CaDllPllCAidTracking(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -41,15 +41,14 @@
#include "configuration_interface.h" #include "configuration_interface.h"
#include "gnss_sdr_flags.h" #include "gnss_sdr_flags.h"
#include <glog/logging.h> #include <glog/logging.h>
#include <utility>
using google::LogMessage; using google::LogMessage;
GpsL1CaDllPllCAidTracking::GpsL1CaDllPllCAidTracking( GpsL1CaDllPllCAidTracking::GpsL1CaDllPllCAidTracking(
ConfigurationInterface* configuration, std::string role, ConfigurationInterface* configuration, const std::string& role,
unsigned int in_streams, unsigned int out_streams) : role_(std::move(role)), in_streams_(in_streams), out_streams_(out_streams) unsigned int in_streams, unsigned int out_streams) : role_(role), in_streams_(in_streams), out_streams_(out_streams)
{ {
DLOG(INFO) << "role " << role; DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ######################## //################# CONFIGURATION PARAMETERS ########################

View File

@ -53,7 +53,7 @@ class GpsL1CaDllPllCAidTracking : public TrackingInterface
{ {
public: public:
GpsL1CaDllPllCAidTracking(ConfigurationInterface* configuration, GpsL1CaDllPllCAidTracking(ConfigurationInterface* configuration,
std::string role, const std::string& role,
unsigned int in_streams, unsigned int in_streams,
unsigned int out_streams); unsigned int out_streams);

View File

@ -65,7 +65,7 @@ glonass_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -74,7 +74,7 @@ glonass_l1_ca_dll_pll_c_aid_make_tracking_cc(
float early_late_space_chips) float early_late_space_chips)
{ {
return glonass_l1_ca_dll_pll_c_aid_tracking_cc_sptr(new glonass_l1_ca_dll_pll_c_aid_tracking_cc( return glonass_l1_ca_dll_pll_c_aid_tracking_cc_sptr(new glonass_l1_ca_dll_pll_c_aid_tracking_cc(
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips)); fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips));
} }
@ -88,13 +88,13 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items,
} }
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(const pmt::pmt_t &msg) void glonass_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); //pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) //avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(msg); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
d_preamble_synchronized = false; d_preamble_synchronized = false;
} }
@ -105,7 +105,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc::glonass_l1_ca_dll_pll_c_aid_tracking_cc
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -125,7 +125,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc::glonass_l1_ca_dll_pll_c_aid_tracking_cc
d_dump = dump; d_dump = dump;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_correlation_length_samples = static_cast<int32_t>(d_vector_length); d_correlation_length_samples = static_cast<int32_t>(d_vector_length);
// Initialize tracking ========================================== // Initialize tracking ==========================================

View File

@ -59,7 +59,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc_sptr
glonass_l1_ca_dll_pll_c_aid_make_tracking_cc( glonass_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -90,7 +90,7 @@ private:
glonass_l1_ca_dll_pll_c_aid_make_tracking_cc( glonass_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -101,7 +101,7 @@ private:
glonass_l1_ca_dll_pll_c_aid_tracking_cc( glonass_l1_ca_dll_pll_c_aid_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -169,7 +169,7 @@ private:
int32_t d_extend_correlation_ms; int32_t d_extend_correlation_ms;
bool d_enable_extended_integration; bool d_enable_extended_integration;
bool d_preamble_synchronized; bool d_preamble_synchronized;
void msg_handler_preamble_index(const pmt::pmt_t& msg); void msg_handler_preamble_index(pmt::pmt_t msg);
//Integration period in samples //Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;

View File

@ -62,13 +62,13 @@ glonass_l1_ca_dll_pll_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips) float early_late_space_chips)
{ {
return glonass_l1_ca_dll_pll_tracking_cc_sptr(new Glonass_L1_Ca_Dll_Pll_Tracking_cc( return glonass_l1_ca_dll_pll_tracking_cc_sptr(new Glonass_L1_Ca_Dll_Pll_Tracking_cc(
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, early_late_space_chips)); fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, early_late_space_chips));
} }
@ -86,7 +86,7 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips) : gr::block("Glonass_L1_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)), float early_late_space_chips) : gr::block("Glonass_L1_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
@ -98,7 +98,7 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
d_dump = dump; d_dump = dump;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_current_prn_length_samples = static_cast<int32_t>(d_vector_length); d_current_prn_length_samples = static_cast<int32_t>(d_vector_length);

View File

@ -56,7 +56,7 @@ glonass_l1_ca_dll_pll_tracking_cc_sptr
glonass_l1_ca_dll_pll_make_tracking_cc( glonass_l1_ca_dll_pll_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);
@ -84,7 +84,7 @@ private:
glonass_l1_ca_dll_pll_make_tracking_cc( glonass_l1_ca_dll_pll_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);
@ -92,7 +92,7 @@ private:
Glonass_L1_Ca_Dll_Pll_Tracking_cc( Glonass_L1_Ca_Dll_Pll_Tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);

View File

@ -62,7 +62,7 @@ glonass_l2_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -71,7 +71,7 @@ glonass_l2_ca_dll_pll_c_aid_make_tracking_cc(
float early_late_space_chips) float early_late_space_chips)
{ {
return glonass_l2_ca_dll_pll_c_aid_tracking_cc_sptr(new glonass_l2_ca_dll_pll_c_aid_tracking_cc( return glonass_l2_ca_dll_pll_c_aid_tracking_cc_sptr(new glonass_l2_ca_dll_pll_c_aid_tracking_cc(
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips)); fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips));
} }
@ -85,13 +85,13 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items,
} }
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(const pmt::pmt_t &msg) void glonass_l2_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); //pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) //avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(msg); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
d_preamble_synchronized = false; d_preamble_synchronized = false;
} }
@ -102,7 +102,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc::glonass_l2_ca_dll_pll_c_aid_tracking_cc
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -122,7 +122,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc::glonass_l2_ca_dll_pll_c_aid_tracking_cc
d_dump = dump; d_dump = dump;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_correlation_length_samples = static_cast<int32_t>(d_vector_length); d_correlation_length_samples = static_cast<int32_t>(d_vector_length);
// Initialize tracking ========================================== // Initialize tracking ==========================================

View File

@ -57,7 +57,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc_sptr
glonass_l2_ca_dll_pll_c_aid_make_tracking_cc( glonass_l2_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -88,7 +88,7 @@ private:
glonass_l2_ca_dll_pll_c_aid_make_tracking_cc( glonass_l2_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -99,7 +99,7 @@ private:
glonass_l2_ca_dll_pll_c_aid_tracking_cc( glonass_l2_ca_dll_pll_c_aid_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -167,7 +167,7 @@ private:
int32_t d_extend_correlation_ms; int32_t d_extend_correlation_ms;
bool d_enable_extended_integration; bool d_enable_extended_integration;
bool d_preamble_synchronized; bool d_preamble_synchronized;
void msg_handler_preamble_index(const pmt::pmt_t& msg); void msg_handler_preamble_index(pmt::pmt_t msg);
//Integration period in samples //Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;

View File

@ -62,13 +62,13 @@ glonass_l2_ca_dll_pll_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips) float early_late_space_chips)
{ {
return glonass_l2_ca_dll_pll_tracking_cc_sptr(new Glonass_L2_Ca_Dll_Pll_Tracking_cc( return glonass_l2_ca_dll_pll_tracking_cc_sptr(new Glonass_L2_Ca_Dll_Pll_Tracking_cc(
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, early_late_space_chips)); fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, early_late_space_chips));
} }
@ -86,7 +86,7 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips) : gr::block("Glonass_L2_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)), float early_late_space_chips) : gr::block("Glonass_L2_Ca_Dll_Pll_Tracking_cc", gr::io_signature::make(1, 1, sizeof(gr_complex)),
@ -98,7 +98,7 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
d_dump = dump; d_dump = dump;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_current_prn_length_samples = static_cast<int32_t>(d_vector_length); d_current_prn_length_samples = static_cast<int32_t>(d_vector_length);

View File

@ -54,7 +54,7 @@ glonass_l2_ca_dll_pll_tracking_cc_sptr
glonass_l2_ca_dll_pll_make_tracking_cc( glonass_l2_ca_dll_pll_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);
@ -82,7 +82,7 @@ private:
glonass_l2_ca_dll_pll_make_tracking_cc( glonass_l2_ca_dll_pll_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);
@ -90,7 +90,7 @@ private:
Glonass_L2_Ca_Dll_Pll_Tracking_cc( Glonass_L2_Ca_Dll_Pll_Tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips); float early_late_space_chips);

View File

@ -54,7 +54,7 @@ gps_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -63,7 +63,7 @@ gps_l1_ca_dll_pll_c_aid_make_tracking_cc(
float early_late_space_chips) float early_late_space_chips)
{ {
return gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr(new gps_l1_ca_dll_pll_c_aid_tracking_cc( return gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr(new gps_l1_ca_dll_pll_c_aid_tracking_cc(
fs_in, vector_length, dump, dump_filename, pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips)); fs_in, vector_length, dump, std::move(dump_filename), pll_bw_hz, dll_bw_hz, pll_bw_narrow_hz, dll_bw_narrow_hz, extend_correlation_ms, early_late_space_chips));
} }
@ -77,13 +77,13 @@ void gps_l1_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items,
} }
void gps_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(const pmt::pmt_t &msg) void gps_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); //pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) //avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(msg); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
d_preamble_synchronized = false; d_preamble_synchronized = false;
} }
@ -94,7 +94,7 @@ gps_l1_ca_dll_pll_c_aid_tracking_cc::gps_l1_ca_dll_pll_c_aid_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -114,7 +114,7 @@ gps_l1_ca_dll_pll_c_aid_tracking_cc::gps_l1_ca_dll_pll_c_aid_tracking_cc(
d_dump = dump; d_dump = dump;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_correlation_length_samples = static_cast<int32_t>(d_vector_length); d_correlation_length_samples = static_cast<int32_t>(d_vector_length);
// Initialize tracking ========================================== // Initialize tracking ==========================================

View File

@ -57,7 +57,7 @@ gps_l1_ca_dll_pll_c_aid_tracking_cc_sptr
gps_l1_ca_dll_pll_c_aid_make_tracking_cc( gps_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -88,7 +88,7 @@ private:
gps_l1_ca_dll_pll_c_aid_make_tracking_cc( gps_l1_ca_dll_pll_c_aid_make_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -99,7 +99,7 @@ private:
gps_l1_ca_dll_pll_c_aid_tracking_cc( gps_l1_ca_dll_pll_c_aid_tracking_cc(
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float dll_bw_hz, float dll_bw_hz,
float pll_bw_narrow_hz, float pll_bw_narrow_hz,
@ -163,7 +163,7 @@ private:
int32_t d_extend_correlation_ms; int32_t d_extend_correlation_ms;
bool d_enable_extended_integration; bool d_enable_extended_integration;
bool d_preamble_synchronized; bool d_preamble_synchronized;
void msg_handler_preamble_index(const pmt::pmt_t& msg); void msg_handler_preamble_index(pmt::pmt_t msg);
//Integration period in samples //Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;

View File

@ -64,7 +64,7 @@ gps_l1_ca_kf_make_tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips, float early_late_space_chips,
bool bce_run, bool bce_run,
@ -74,7 +74,7 @@ gps_l1_ca_kf_make_tracking_cc(
int32_t bce_kappa) int32_t bce_kappa)
{ {
return gps_l1_ca_kf_tracking_cc_sptr(new Gps_L1_Ca_Kf_Tracking_cc(order, if_freq, return gps_l1_ca_kf_tracking_cc_sptr(new Gps_L1_Ca_Kf_Tracking_cc(order, if_freq,
fs_in, vector_length, dump, dump_filename, dll_bw_hz, early_late_space_chips, fs_in, vector_length, dump, std::move(dump_filename), dll_bw_hz, early_late_space_chips,
bce_run, bce_ptrans, bce_strans, bce_nu, bce_kappa)); bce_run, bce_ptrans, bce_strans, bce_nu, bce_kappa));
} }
@ -95,7 +95,7 @@ Gps_L1_Ca_Kf_Tracking_cc::Gps_L1_Ca_Kf_Tracking_cc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
bool dump, bool dump,
const std::string &dump_filename, std::string dump_filename,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips, float early_late_space_chips,
bool bce_run, bool bce_run,
@ -115,7 +115,7 @@ Gps_L1_Ca_Kf_Tracking_cc::Gps_L1_Ca_Kf_Tracking_cc(
d_if_freq = if_freq; d_if_freq = if_freq;
d_fs_in = fs_in; d_fs_in = fs_in;
d_vector_length = vector_length; d_vector_length = vector_length;
d_dump_filename = dump_filename; d_dump_filename = std::move(dump_filename);
d_current_prn_length_samples = static_cast<int>(d_vector_length); d_current_prn_length_samples = static_cast<int>(d_vector_length);

View File

@ -60,7 +60,7 @@ gps_l1_ca_kf_make_tracking_cc(uint32_t order,
int64_t if_freq, int64_t if_freq,
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float pll_bw_hz, float pll_bw_hz,
float early_late_space_chips, float early_late_space_chips,
bool bce_run, bool bce_run,
@ -93,7 +93,7 @@ private:
int64_t if_freq, int64_t if_freq,
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips, float early_late_space_chips,
bool bce_run, bool bce_run,
@ -106,7 +106,7 @@ private:
int64_t if_freq, int64_t if_freq,
int64_t fs_in, uint32_t vector_length, int64_t fs_in, uint32_t vector_length,
bool dump, bool dump,
const std::string& dump_filename, std::string dump_filename,
float dll_bw_hz, float dll_bw_hz,
float early_late_space_chips, float early_late_space_chips,
bool bce_run, bool bce_run,

View File

@ -64,7 +64,7 @@ int INIReader::ParseError()
} }
std::string INIReader::Get(const std::string& section, const std::string& name, const std::string& default_value) std::string INIReader::Get(const std::string& section, const std::string& name, std::string default_value)
{ {
std::string key = MakeKey(section, name); std::string key = MakeKey(section, name);
return _values.count(key) ? _values[key] : default_value; return _values.count(key) ? _values[key] : default_value;

View File

@ -67,7 +67,7 @@ public:
//! Get a string value from INI file, returning default_value if not found. //! Get a string value from INI file, returning default_value if not found.
std::string Get(const std::string& section, const std::string& name, std::string Get(const std::string& section, const std::string& name,
const std::string& default_value); std::string default_value);
//! Get an integer (long) value from INI file, returning default_value if not found. //! Get an integer (long) value from INI file, returning default_value if not found.
int64_t GetInteger(const std::string& section, const std::string& name, int64_t default_value); int64_t GetInteger(const std::string& section, const std::string& name, int64_t default_value);

View File

@ -35,7 +35,7 @@
#include <iostream> #include <iostream>
#include <sstream> #include <sstream>
Gnss_Synchro_Udp_Sink::Gnss_Synchro_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port) : socket{io_service} Gnss_Synchro_Udp_Sink::Gnss_Synchro_Udp_Sink(std::vector<std::string> addresses, const uint16_t& port) : socket{io_service}
{ {
for (const auto& address : addresses) for (const auto& address : addresses)
{ {

View File

@ -42,7 +42,7 @@
class Gnss_Synchro_Udp_Sink class Gnss_Synchro_Udp_Sink
{ {
public: public:
Gnss_Synchro_Udp_Sink(const std::vector<std::string>& addresses, const uint16_t& port); Gnss_Synchro_Udp_Sink(std::vector<std::string> addresses, const uint16_t& port);
bool write_gnss_synchro(const std::vector<Gnss_Synchro>& stocks); bool write_gnss_synchro(const std::vector<Gnss_Synchro>& stocks);
private: private:

View File

@ -53,7 +53,7 @@ gr::message::sptr ControlMessageFactory::GetQueueMessage(unsigned int who, unsig
} }
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> ControlMessageFactory::GetControlMessages(const gr::message::sptr& queue_message) std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> ControlMessageFactory::GetControlMessages(const gr::message::sptr queue_message) // NOLINT(performance-unnecessary-value-param)
{ {
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> control_messages = std::make_shared<std::vector<std::shared_ptr<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); unsigned int control_messages_count = queue_message->length() / sizeof(ControlMessage);

View File

@ -58,7 +58,7 @@ public:
virtual ~ControlMessageFactory(); virtual ~ControlMessageFactory();
gr::message::sptr GetQueueMessage(unsigned int who, unsigned int what); gr::message::sptr GetQueueMessage(unsigned int who, unsigned int what);
std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> GetControlMessages(const gr::message::sptr& queue_message); std::shared_ptr<std::vector<std::shared_ptr<ControlMessage>>> GetControlMessages(const gr::message::sptr queue_message); // NOLINT(performance-unnecessary-value-param)
}; };
#endif /*GNSS_SDR_CONTROL_MESSAGE_FACTORY_H_*/ #endif /*GNSS_SDR_CONTROL_MESSAGE_FACTORY_H_*/

View File

@ -285,11 +285,16 @@ int ControlThread::run()
flowgraph_->disconnect(); flowgraph_->disconnect();
// Join keyboard thread // Join keyboard thread
keyboard_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000)); try
sysv_queue_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000)); {
cmd_interface_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000)); keyboard_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000));
sysv_queue_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000));
LOG(INFO) << "Flowgraph stopped"; cmd_interface_thread_.try_join_until(boost::chrono::steady_clock::now() + boost::chrono::milliseconds(1000));
}
catch (const boost::thread_interrupted &interrupt)
{
DLOG(INFO) << "Thread interrupted";
}
if (restart_) if (restart_)
{ {
@ -300,7 +305,7 @@ int ControlThread::run()
} }
void ControlThread::set_control_queue(const gr::msg_queue::sptr &control_queue) void ControlThread::set_control_queue(const gr::msg_queue::sptr control_queue) // NOLINT(performance-unnecessary-value-param)
{ {
if (flowgraph_->running()) if (flowgraph_->running())
{ {

View File

@ -93,7 +93,7 @@ public:
* *
* \param[in] boost::shared_ptr<gr::msg_queue> control_queue * \param[in] boost::shared_ptr<gr::msg_queue> control_queue
*/ */
void set_control_queue(const gr::msg_queue::sptr& control_queue); void set_control_queue(const gr::msg_queue::sptr control_queue); // NOLINT(performance-unnecessary-value-param)
unsigned int processed_control_messages() unsigned int processed_control_messages()

View File

@ -182,7 +182,7 @@ GNSSBlockFactory::~GNSSBlockFactory() = default;
std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetSignalSource( std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetSignalSource(
const std::shared_ptr<ConfigurationInterface>& configuration, const gr::msg_queue::sptr& queue, int ID) const std::shared_ptr<ConfigurationInterface>& configuration, const gr::msg_queue::sptr queue, int ID) // NOLINT(performance-unnecessary-value-param)
{ {
std::string default_implementation = "File_Signal_Source"; std::string default_implementation = "File_Signal_Source";
std::string role = "SignalSource"; //backwards compatibility for old conf files std::string role = "SignalSource"; //backwards compatibility for old conf files
@ -851,7 +851,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetChannel_B1(
} }
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GNSSBlockFactory::GetChannels( std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GNSSBlockFactory::GetChannels(
const std::shared_ptr<ConfigurationInterface>& configuration, const gr::msg_queue::sptr& queue) const std::shared_ptr<ConfigurationInterface>& configuration, const gr::msg_queue::sptr queue) // NOLINT(performance-unnecessary-value-param)
{ {
std::string default_implementation = "Pass_Through"; std::string default_implementation = "Pass_Through";
std::string tracking_implementation; std::string tracking_implementation;
@ -1139,7 +1139,7 @@ std::unique_ptr<GNSSBlockInterface> GNSSBlockFactory::GetBlock(
const std::shared_ptr<ConfigurationInterface>& configuration, const std::shared_ptr<ConfigurationInterface>& configuration,
const std::string& role, const std::string& role,
const std::string& implementation, unsigned int in_streams, const std::string& implementation, unsigned int in_streams,
unsigned int out_streams, const gr::msg_queue::sptr& queue) unsigned int out_streams, const gr::msg_queue::sptr queue) // NOLINT(performance-unnecessary-value-param)
{ {
std::unique_ptr<GNSSBlockInterface> block; std::unique_ptr<GNSSBlockInterface> block;

View File

@ -58,7 +58,7 @@ public:
GNSSBlockFactory(); GNSSBlockFactory();
virtual ~GNSSBlockFactory(); virtual ~GNSSBlockFactory();
std::unique_ptr<GNSSBlockInterface> GetSignalSource(const std::shared_ptr<ConfigurationInterface>& configuration, std::unique_ptr<GNSSBlockInterface> GetSignalSource(const std::shared_ptr<ConfigurationInterface>& configuration,
const gr::msg_queue::sptr& queue, int ID = -1); const gr::msg_queue::sptr queue, int ID = -1); // NOLINT(performance-unnecessary-value-param)
std::unique_ptr<GNSSBlockInterface> GetSignalConditioner(const std::shared_ptr<ConfigurationInterface>& configuration, int ID = -1); std::unique_ptr<GNSSBlockInterface> GetSignalConditioner(const std::shared_ptr<ConfigurationInterface>& configuration, int ID = -1);
@ -67,7 +67,7 @@ public:
std::unique_ptr<GNSSBlockInterface> GetObservables(const std::shared_ptr<ConfigurationInterface>& configuration); std::unique_ptr<GNSSBlockInterface> GetObservables(const std::shared_ptr<ConfigurationInterface>& configuration);
std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GetChannels(const std::shared_ptr<ConfigurationInterface>& configuration, std::unique_ptr<std::vector<std::unique_ptr<GNSSBlockInterface>>> GetChannels(const std::shared_ptr<ConfigurationInterface>& configuration,
const gr::msg_queue::sptr& queue); const gr::msg_queue::sptr queue); // NOLINT(performance-unnecessary-value-param)
/* /*
* \brief Returns the block with the required configuration and implementation * \brief Returns the block with the required configuration and implementation
@ -75,7 +75,7 @@ public:
std::unique_ptr<GNSSBlockInterface> GetBlock(const std::shared_ptr<ConfigurationInterface>& configuration, std::unique_ptr<GNSSBlockInterface> GetBlock(const std::shared_ptr<ConfigurationInterface>& configuration,
const std::string& role, const std::string& implementation, const std::string& role, const std::string& implementation,
unsigned int in_streams, unsigned int out_streams, unsigned int in_streams, unsigned int out_streams,
const gr::msg_queue::sptr& queue = nullptr); const gr::msg_queue::sptr queue = nullptr); // NOLINT(performance-unnecessary-value-param)
private: private:
std::unique_ptr<GNSSBlockInterface> GetChannel_1C(const std::shared_ptr<ConfigurationInterface>& configuration, std::unique_ptr<GNSSBlockInterface> GetChannel_1C(const std::shared_ptr<ConfigurationInterface>& configuration,

View File

@ -62,7 +62,7 @@
using google::LogMessage; using google::LogMessage;
GNSSFlowgraph::GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, const gr::msg_queue::sptr& queue) GNSSFlowgraph::GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, const gr::msg_queue::sptr queue) // NOLINT(performance-unnecessary-value-param)
{ {
connected_ = false; connected_ = false;
running_ = false; running_ = false;
@ -839,6 +839,10 @@ void GNSSFlowgraph::disconnect()
for (unsigned int i = 0; i < channels_count_; i++) for (unsigned int i = 0; i < channels_count_; i++)
{ {
top_block_->disconnect(observables_->get_right_block(), i, pvt_->get_left_block(), i); top_block_->disconnect(observables_->get_right_block(), i, pvt_->get_left_block(), i);
if (enable_monitor_)
{
top_block_->disconnect(observables_->get_right_block(), i, GnssSynchroMonitor_, i);
}
top_block_->msg_disconnect(channels_.at(i)->get_right_block(), pmt::mp("telemetry"), pvt_->get_left_block(), pmt::mp("telemetry")); top_block_->msg_disconnect(channels_.at(i)->get_right_block(), pmt::mp("telemetry"), pvt_->get_left_block(), pmt::mp("telemetry"));
} }
} }
@ -1340,7 +1344,7 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
} }
void GNSSFlowgraph::priorize_satellites(const std::vector<std::pair<int, Gnss_Satellite>>& visible_satellites) void GNSSFlowgraph::priorize_satellites(std::vector<std::pair<int, Gnss_Satellite>> visible_satellites)
{ {
size_t old_size; size_t old_size;
Gnss_Signal gs; Gnss_Signal gs;

View File

@ -72,7 +72,7 @@ public:
/*! /*!
* \brief Constructor that initializes the receiver flow graph * \brief Constructor that initializes the receiver flow graph
*/ */
GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, const gr::msg_queue::sptr& queue); GNSSFlowgraph(std::shared_ptr<ConfigurationInterface> configuration, const gr::msg_queue::sptr queue); // NOLINT(performance-unnecessary-value-param)
/*! /*!
* \brief Destructor * \brief Destructor
@ -141,7 +141,7 @@ public:
/*! /*!
* \brief Priorize visible satellites in the specified vector * \brief Priorize visible satellites in the specified vector
*/ */
void priorize_satellites(const std::vector<std::pair<int, Gnss_Satellite>>& visible_satellites); void priorize_satellites(std::vector<std::pair<int, Gnss_Satellite>> visible_satellites);
private: private:
void init(); // Populates the SV PRN list available for acquisition and tracking void init(); // Populates the SV PRN list available for acquisition and tracking

View File

@ -70,7 +70,7 @@ class GpsL1CaPcpsAcquisitionTest_msg_rx : public gr::block
{ {
private: private:
friend GpsL1CaPcpsAcquisitionTest_msg_rx_sptr GpsL1CaPcpsAcquisitionTest_msg_rx_make(); friend GpsL1CaPcpsAcquisitionTest_msg_rx_sptr GpsL1CaPcpsAcquisitionTest_msg_rx_make();
void msg_handler_events(const pmt::pmt_t &msg); void msg_handler_events(pmt::pmt_t msg);
GpsL1CaPcpsAcquisitionTest_msg_rx(); GpsL1CaPcpsAcquisitionTest_msg_rx();
public: public:
@ -85,11 +85,11 @@ GpsL1CaPcpsAcquisitionTest_msg_rx_sptr GpsL1CaPcpsAcquisitionTest_msg_rx_make()
} }
void GpsL1CaPcpsAcquisitionTest_msg_rx::msg_handler_events(const pmt::pmt_t &msg) void GpsL1CaPcpsAcquisitionTest_msg_rx::msg_handler_events(pmt::pmt_t msg)
{ {
try try
{ {
int64_t message = pmt::to_long(msg); int64_t message = pmt::to_long(std::move(msg));
rx_message = message; rx_message = message;
} }
catch (boost::bad_any_cast &e) catch (boost::bad_any_cast &e)
@ -236,14 +236,14 @@ void GpsL1CaPcpsAcquisitionTest::plot_grid()
} }
TEST_F(GpsL1CaPcpsAcquisitionTest /*unused*/, Instantiate /*unused*/) TEST_F(GpsL1CaPcpsAcquisitionTest, Instantiate)
{ {
init(); init();
boost::shared_ptr<GpsL1CaPcpsAcquisition> acquisition = boost::make_shared<GpsL1CaPcpsAcquisition>(config.get(), "Acquisition_1C", 1, 0); boost::shared_ptr<GpsL1CaPcpsAcquisition> acquisition = boost::make_shared<GpsL1CaPcpsAcquisition>(config.get(), "Acquisition_1C", 1, 0);
} }
TEST_F(GpsL1CaPcpsAcquisitionTest /*unused*/, ConnectAndRun /*unused*/) TEST_F(GpsL1CaPcpsAcquisitionTest, ConnectAndRun)
{ {
int fs_in = 4000000; int fs_in = 4000000;
int nsamples = 4000; int nsamples = 4000;
@ -276,7 +276,7 @@ TEST_F(GpsL1CaPcpsAcquisitionTest /*unused*/, ConnectAndRun /*unused*/)
} }
TEST_F(GpsL1CaPcpsAcquisitionTest /*unused*/, ValidationOfResults /*unused*/) TEST_F(GpsL1CaPcpsAcquisitionTest, ValidationOfResults)
{ {
std::chrono::time_point<std::chrono::system_clock> start, end; std::chrono::time_point<std::chrono::system_clock> start, end;
std::chrono::duration<double> elapsed_seconds(0.0); std::chrono::duration<double> elapsed_seconds(0.0);