Cleaning the terminal output and dumping most of the information in the log file. Better use of the glog library, logging can be seen also in Release, in real time by doing './gnss-sdr --logtostderr=1'. Update to latest version of Armadillo.

git-svn-id: https://svn.code.sf.net/p/gnss-sdr/code/trunk@486 64b25241-fba3-4117-9849-534c7e92360d
This commit is contained in:
Carles Fernandez 2014-03-16 19:58:29 +00:00
parent 26d2bc70b3
commit 39f8754217
96 changed files with 728 additions and 868 deletions

View File

@ -594,8 +594,8 @@ if(NOT ARMADILLO_FOUND)
INSTALL_COMMAND ""
)
else(OLD_GCC)
set(armadillo_RELEASE 4.000.2)
set(armadillo_MD5 "b2891c7b59b96337c154c5d961fd40fb")
set(armadillo_RELEASE 4.100.2)
set(armadillo_MD5 "dd422706778cde656d531b3c3919766e")
if(EXISTS ${CMAKE_CURRENT_BINARY_DIR}/download/armadillo-${armadillo_RELEASE}/armadillo-${armadillo_RELEASE}.tar.gz)
set(ARMADILLO_PATCH_FILE ${CMAKE_CURRENT_BINARY_DIR}/armadillo-${armadillo_RELEASE}/armadillo_no.patch)
file(WRITE ${ARMADILLO_PATCH_FILE} "")

19
README
View File

@ -45,9 +45,9 @@ $ sudo apt-get install libblas-dev liblapack-dev gfortran # For Debian/Ubuntu/
$ sudo yum install lapack-devel blas-devel gcc-fortran # For Fedora/CentOS/RHEL
$ sudo zypper install lapack-devel blas-devel gcc-fortran # For OpenSUSE
$ wget http://sourceforge.net/projects/arma/files/armadillo-4.000.0.tar.gz
$ tar xvfz armadillo-4.000.0.tar.gz
$ cd armadillo-4.000.0
$ wget http://sourceforge.net/projects/arma/files/armadillo-4.100.2.tar.gz
$ tar xvfz armadillo-4.100.2.tar.gz
$ cd armadillo-4.100.2
$ cmake .
$ make
$ sudo make install
@ -289,19 +289,10 @@ $ CXXFLAGS="-stdlib=libc++" CC=clang CXX=clang++ ./configure
$ make
$ sudo make install
Install Glog manually from the trunk, after applying a patch:
Install Glog manually from the subversion repository. Revision 142 is known to work well:
$ svn checkout -r139 http://google-glog.googlecode.com/svn/trunk/ google-glog
$ svn checkout -r142 http://google-glog.googlecode.com/svn/trunk/ google-glog
$ cd google-glog
Open your browser and go to: http://code.google.com/p/google-glog/issues/detail?id=121
Download libc++.diff (from comment #3)
$ mv $HOME/Downloads/libc++.diff .
$ cd src
$ patch < ../libc++.diff
$ cd ..
$ CXXFLAGS="-stdlib=libc++" CC=clang CXX=clang++ ./configure
$ make
$ sudo make install

View File

@ -32,10 +32,10 @@
#include "galileo_e1_pvt.h"
#include <glog/logging.h>
#include "configuration_interface.h"
#include "galileo_e1_pvt_cc.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;

View File

@ -32,10 +32,9 @@
#include "gps_l1_ca_pvt.h"
#include <glog/logging.h>
#include "configuration_interface.h"
#include "gps_l1_ca_pvt_cc.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;

View File

@ -38,7 +38,6 @@
#include <boost/date_time/posix_time/posix_time.hpp>
#include <gnuradio/gr_complex.h>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "gnss_synchro.h"
@ -103,11 +102,11 @@ galileo_e1_pvt_cc::galileo_e1_pvt_cc(unsigned int nchannels, boost::shared_ptr<g
{
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "PVT dump enabled Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "PVT dump enabled Log file: " << d_dump_filename.c_str();
}
catch (const std::ifstream::failure& e)
{
std::cout << "Exception opening PVT dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception opening PVT dump file " << e.what();
}
}
}
@ -219,13 +218,17 @@ int galileo_e1_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_it
if (((d_sample_counter % d_display_rate_ms) == 0) and d_ls_pvt->b_valid_position == true)
{
std::cout << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl;
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl;
std::cout << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is HDOP = " << d_ls_pvt->d_HDOP << " VDOP = " <<
d_ls_pvt->d_VDOP <<" TDOP = " << d_ls_pvt->d_TDOP <<
" GDOP = " << d_ls_pvt->d_GDOP <<std::endl;
LOG(INFO) << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]";
LOG(INFO) << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is HDOP = " << d_ls_pvt->d_HDOP << " VDOP = "
<< d_ls_pvt->d_VDOP <<" TDOP = " << d_ls_pvt->d_TDOP
<< " GDOP = " << d_ls_pvt->d_GDOP;
}
// MULTIPLEXED FILE RECORDING - Record results to file
@ -245,7 +248,7 @@ int galileo_e1_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_it
}
catch (const std::ifstream::failure& e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing observables dump file " << e.what();
}
}
}

View File

@ -37,7 +37,6 @@
#include <boost/date_time/posix_time/posix_time.hpp>
#include <gnuradio/gr_complex.h>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "gnss_synchro.h"
@ -118,11 +117,11 @@ gps_l1_ca_pvt_cc::gps_l1_ca_pvt_cc(unsigned int nchannels,
{
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "PVT dump enabled Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "PVT dump enabled Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "Exception opening PVT dump file " << e.what() << std::endl;
LOG(INFO) << "Exception opening PVT dump file " << e.what();
}
}
}
@ -275,13 +274,16 @@ int gps_l1_ca_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_ite
if (((d_sample_counter % d_display_rate_ms) == 0) and d_ls_pvt->b_valid_position == true)
{
std::cout << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl;
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]" << std::endl;
std::cout << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is HDOP = " << d_ls_pvt->d_HDOP << " VDOP = " <<
d_ls_pvt->d_VDOP <<" TDOP = " << d_ls_pvt->d_TDOP <<
" GDOP = " << d_ls_pvt->d_GDOP << std::endl;
LOG(INFO) << "Position at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is Lat = " << d_ls_pvt->d_latitude_d << " [deg], Long = " << d_ls_pvt->d_longitude_d
<< " [deg], Height= " << d_ls_pvt->d_height_m << " [m]";
LOG(INFO) << "Dilution of Precision at " << boost::posix_time::to_simple_string(d_ls_pvt->d_position_UTC_time)
<< " is HDOP = " << d_ls_pvt->d_HDOP << " VDOP = "
<< d_ls_pvt->d_VDOP <<" TDOP = " << d_ls_pvt->d_TDOP << " GDOP = " << d_ls_pvt->d_GDOP;
}
// MULTIPLEXED FILE RECORDING - Record results to file
if(d_dump == true)
@ -300,7 +302,7 @@ int gps_l1_ca_pvt_cc::general_work (int noutput_items, gr_vector_int &ninput_ite
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing observables dump file " << e.what();
}
}
}

View File

@ -30,7 +30,6 @@
*/
#include "galileo_e1_ls_pvt.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "Galileo_E1.h"
@ -56,11 +55,11 @@ galileo_e1_ls_pvt::galileo_e1_ls_pvt(int nchannels, std::string dump_filename, b
{
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "PVT lib dump enabled Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "Exception opening PVT lib dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception opening PVT lib dump file " << e.what();
}
}
}
@ -299,11 +298,11 @@ bool galileo_e1_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map
// 22 August 1999 00:00 last Galileo start GST epoch (ICD sec 5.1.2)
boost::posix_time::ptime p_time(boost::gregorian::date(1999, 8, 22), t);
d_position_UTC_time = p_time;
DLOG(INFO) << "Galileo RX time at " << boost::posix_time::to_simple_string(p_time);
LOG(INFO) << "Galileo RX time at " << boost::posix_time::to_simple_string(p_time);
//end debug
// SV ECEF DEBUG OUTPUT
DLOG(INFO) << "ECEF satellite SV ID=" << galileo_ephemeris_iter->second.i_satellite_PRN
LOG(INFO) << "ECEF satellite SV ID=" << galileo_ephemeris_iter->second.i_satellite_PRN
<< " X=" << galileo_ephemeris_iter->second.d_satpos_X
<< " [m] Y=" << galileo_ephemeris_iter->second.d_satpos_Y
<< " [m] Z=" << galileo_ephemeris_iter->second.d_satpos_Z
@ -322,7 +321,7 @@ bool galileo_e1_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map
// ****** SOLVE LEAST SQUARES******************************************************
// ********************************************************************************
d_valid_observations = valid_obs;
DLOG(INFO) << "Galileo PVT: valid observations=" << valid_obs;
LOG(INFO) << "Galileo PVT: valid observations=" << valid_obs;
if (valid_obs >= 4)
{
@ -340,7 +339,7 @@ bool galileo_e1_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map
// 22 August 1999 00:00 last Galileo start GST epoch (ICD sec 5.1.2)
boost::posix_time::ptime p_time(boost::gregorian::date(1999, 8, 22), t);
d_position_UTC_time = p_time;
DLOG(INFO) << "Galileo Position at TOW=" << galileo_current_time << " in ECEF (X,Y,Z) = " << mypos;
LOG(INFO) << "Galileo Position at TOW=" << galileo_current_time << " in ECEF (X,Y,Z) = " << mypos;
cart2geo((double)mypos(0), (double)mypos(1), (double)mypos(2), 4);
//ToDo: Find an Observables/PVT random bug with some satellite configurations that gives an erratic PVT solution (i.e. height>50 km)
@ -349,9 +348,13 @@ bool galileo_e1_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map
b_valid_position = false;
return false;
}
DLOG(INFO) << "Galileo Position at " << boost::posix_time::to_simple_string(p_time)
<< " is Lat = " << d_latitude_d << " [deg], Long = " << d_longitude_d
<< " [deg], Height= " << d_height_m << " [m]";
LOG(INFO) << "Galileo Position at " << boost::posix_time::to_simple_string(p_time)
<< " is Lat = " << d_latitude_d << " [deg], Long = " << d_longitude_d
<< " [deg], Height= " << d_height_m << " [m]";
std::cout << "Galileo Position at " << boost::posix_time::to_simple_string(p_time)
<< " is Lat = " << d_latitude_d << " [deg], Long = " << d_longitude_d
<< " [deg], Height= " << d_height_m << " [m]" << std::endl;
// ###### Compute DOPs ########
// 1- Rotation matrix from ECEF coordinates to ENU coordinates
@ -425,7 +428,7 @@ bool galileo_e1_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map
}
catch (const std::ifstream::failure& e)
{
std::cout << "Exception writing PVT LS dump file "<< e.what() << std::endl;
LOG(WARNING) << "Exception writing PVT LS dump file "<< e.what();
}
}
@ -522,7 +525,7 @@ void galileo_e1_ls_pvt::cart2geo(double X, double Y, double Z, int elipsoid_sele
iterations = iterations + 1;
if (iterations > 100)
{
std::cout << "Failed to approximate h with desired precision. h-oldh= " << h - oldh << std::endl;
LOG(WARNING) << "Failed to approximate h with desired precision. h-oldh= " << h - oldh;
break;
}
}
@ -644,7 +647,7 @@ void galileo_e1_ls_pvt::togeod(double *dphi, double *dlambda, double *h, double
}
if (i == (maxit - 1))
{
DLOG(INFO) << "The computation of geodetic coordinates did not converge";
LOG(WARNING) << "The computation of geodetic coordinates did not converge";
}
}
*dphi = (*dphi) * rtd;

View File

@ -27,13 +27,15 @@
*
* -------------------------------------------------------------------------
*/
#define GLOG_NO_ABBREVIATED_SEVERITIES
#include "gps_l1_ca_ls_pvt.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
gps_l1_ca_ls_pvt::gps_l1_ca_ls_pvt(int nchannels,std::string dump_filename, bool flag_dump_to_file)
{
// init empty ephemeris for all the available GNSS channels
@ -53,11 +55,11 @@ gps_l1_ca_ls_pvt::gps_l1_ca_ls_pvt(int nchannels,std::string dump_filename, bool
{
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "PVT lib dump enabled Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "PVT lib dump enabled Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "Exception opening PVT lib dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception opening PVT lib dump file " << e.what();
}
}
}
@ -276,7 +278,7 @@ bool gps_l1_ca_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map,
valid_obs++;
// SV ECEF DEBUG OUTPUT
DLOG(INFO) << "(new)ECEF satellite SV ID=" << gps_ephemeris_iter->second.i_satellite_PRN
LOG(INFO) << "(new)ECEF satellite SV ID=" << gps_ephemeris_iter->second.i_satellite_PRN
<< " X=" << gps_ephemeris_iter->second.d_satpos_X
<< " [m] Y=" << gps_ephemeris_iter->second.d_satpos_Y
<< " [m] Z=" << gps_ephemeris_iter->second.d_satpos_Z
@ -300,16 +302,16 @@ bool gps_l1_ca_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map,
// ****** SOLVE LEAST SQUARES******************************************************
// ********************************************************************************
d_valid_observations = valid_obs;
DLOG(INFO) << "(new)PVT: valid observations=" << valid_obs;
LOG(INFO) << "(new)PVT: valid observations=" << valid_obs;
if (valid_obs >= 4)
{
arma::vec mypos;
DLOG(INFO) << "satpos=" << satpos;
DLOG(INFO) << "obs=" << obs;
DLOG(INFO) << "W=" << W;
LOG(INFO) << "satpos=" << satpos;
LOG(INFO) << "obs=" << obs;
LOG(INFO) << "W=" << W;
mypos = leastSquarePos(satpos, obs, W);
DLOG(INFO) << "(new)Position at TOW=" << GPS_current_time << " in ECEF (X,Y,Z) = " << mypos;
LOG(INFO) << "(new)Position at TOW=" << GPS_current_time << " in ECEF (X,Y,Z) = " << mypos;
gps_l1_ca_ls_pvt::cart2geo(mypos(0), mypos(1), mypos(2), 4);
//ToDo: Find an Observables/PVT random bug with some satellite configurations that gives an erratic PVT solution (i.e. height>50 km)
if (d_height_m > 50000)
@ -324,9 +326,9 @@ bool gps_l1_ca_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map,
boost::posix_time::ptime p_time(boost::gregorian::date(1999, 8, 22), t);
d_position_UTC_time = p_time;
DLOG(INFO) << "(new)Position at " << boost::posix_time::to_simple_string(p_time)
<< " is Lat = " << d_latitude_d << " [deg], Long = " << d_longitude_d
<< " [deg], Height= " << d_height_m << " [m]";
LOG(INFO) << "(new)Position at " << boost::posix_time::to_simple_string(p_time)
<< " is Lat = " << d_latitude_d << " [deg], Long = " << d_longitude_d
<< " [deg], Height= " << d_height_m << " [m]";
// ###### Compute DOPs ########
@ -401,7 +403,7 @@ bool gps_l1_ca_ls_pvt::get_PVT(std::map<int,Gnss_Synchro> gnss_pseudoranges_map,
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing PVT LS dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing PVT LS dump file " << e.what();
}
}
@ -497,7 +499,7 @@ void gps_l1_ca_ls_pvt::cart2geo(double X, double Y, double Z, int elipsoid_selec
iterations = iterations + 1;
if (iterations > 100)
{
std::cout << "Failed to approximate h with desired precision. h-oldh= " << h - oldh << std::endl;
LOG(WARNING) << "Failed to approximate h with desired precision. h-oldh= " << h - oldh;
break;
}
}
@ -617,7 +619,7 @@ void gps_l1_ca_ls_pvt::togeod(double *dphi, double *dlambda, double *h, double a
}
if (i == (maxit - 1))
{
DLOG(INFO) << "The computation of geodetic coordinates did not converge";
LOG(WARNING) << "The computation of geodetic coordinates did not converge";
}
}
*dphi = (*dphi) * rtd;

View File

@ -31,9 +31,9 @@
#include "kml_printer.h"
#include <ctime>
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
bool Kml_Printer::set_headers(std::string filename)
{

View File

@ -37,7 +37,6 @@
#include <fcntl.h>
#include <termios.h>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gflags/gflags.h>
#include "GPS_L1_CA.h"

View File

@ -39,9 +39,8 @@
#include <boost/date_time/gregorian/gregorian.hpp>
#include <boost/date_time/local_time/local_time.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include "sbas_telemetry_data.h"
#include "gps_navigation_message.h"
#include "gps_ephemeris.h"
@ -157,7 +156,7 @@ Rinex_Printer::Rinex_Printer()
}
else
{
LOG_AT_LEVEL(ERROR) << "Unknown RINEX version " << FLAGS_RINEX_version << " (must be 2.11 or 3.01)" << std::endl;
LOG(ERROR) << "Unknown RINEX version " << FLAGS_RINEX_version << " (must be 2.11 or 3.01)" << std::endl;
}
numberTypesObservations = 2; // Number of available types of observable in the system
@ -197,7 +196,7 @@ void Rinex_Printer::lengthCheck(std::string line)
{
if (line.length() != 80)
{
LOG_AT_LEVEL(ERROR) << "Bad defined RINEX line: "
LOG(ERROR) << "Bad defined RINEX line: "
<< line.length() << " characters (must be 80)" << std::endl
<< line << std::endl
<< "----|---1|0---|---2|0---|---3|0---|---4|0---|---5|0---|---6|0---|---7|0---|---8|" << std::endl;
@ -712,9 +711,9 @@ void Rinex_Printer::log_rinex_nav(std::ofstream& out, std::map<int,Gps_Ephemeris
// }
//else
// {
// LOG_AT_LEVEL(ERROR) << "Discontinued reception of Frame 2 and 3 " << std::endl;
// LOG(ERROR) << "Discontinued reception of Frame 2 and 3 " << std::endl;
// }
double d_IODE_SF2=0;
double d_IODE_SF2 = 0;
line += Rinex_Printer::doub2for(d_IODE_SF2, 18, 2);
line += std::string(1, ' ');
line += Rinex_Printer::doub2for(gps_ephemeris_iter->second.d_Crs, 18, 2);

View File

@ -34,7 +34,6 @@
#include <string>
#include <boost/lexical_cast.hpp>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "galileo_e1_signal_processing.h"
#include "Galileo_E1.h"
@ -66,7 +65,7 @@ GalileoE1Pcps8msAmbiguousAcquisition::GalileoE1Pcps8msAmbiguousAcquisition(
if (sampled_ms_ % 4 != 0)
{
sampled_ms_ = (int)(sampled_ms_/4) * 4;
LOG_AT_LEVEL(WARNING) << "coherent_integration_time should be multiple of "
LOG(WARNING) << "coherent_integration_time should be multiple of "
<< "Galileo code length (4 ms). coherent_integration_time = "
<< sampled_ms_ << " ms will be used.";
@ -104,7 +103,7 @@ GalileoE1Pcps8msAmbiguousAcquisition::GalileoE1Pcps8msAmbiguousAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unknown acquisition item type";
}
}
@ -260,20 +259,20 @@ GalileoE1Pcps8msAmbiguousAcquisition::reset()
float GalileoE1Pcps8msAmbiguousAcquisition::calculate_threshold(float pfa)
{
unsigned int frequency_bins = 0;
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)
{
frequency_bins++;
}
unsigned int frequency_bins = 0;
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)
{
frequency_bins++;
}
DLOG(INFO) <<"Channel "<<channel_<<" Pfa = "<< pfa;
DLOG(INFO) << "Channel " << channel_ << " Pfa = " << pfa;
unsigned int ncells = vector_length_*frequency_bins;
double exponent = 1/(double)ncells;
double val = pow(1.0-pfa,exponent);
double exponent = 1/(double)ncells;
double val = pow(1.0 - pfa,exponent);
double lambda = double(vector_length_);
boost::math::exponential_distribution<double> mydist (lambda);
float threshold = (float)quantile(mydist,val);
boost::math::exponential_distribution<double> mydist (lambda);
float threshold = (float)quantile(mydist,val);
return threshold;
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "galileo_e1_signal_processing.h"
#include "Galileo_E1.h"
@ -65,7 +64,7 @@ GalileoE1PcpsAmbiguousAcquisition::GalileoE1PcpsAmbiguousAcquisition(
if (sampled_ms_ % 4 != 0)
{
sampled_ms_ = (int)(sampled_ms_/4) * 4;
LOG_AT_LEVEL(WARNING) << "coherent_integration_time should be multiple of "
LOG(WARNING) << "coherent_integration_time should be multiple of "
<< "Galileo code length (4 ms). coherent_integration_time = "
<< sampled_ms_ << " ms will be used.";
@ -114,7 +113,7 @@ GalileoE1PcpsAmbiguousAcquisition::GalileoE1PcpsAmbiguousAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unknown acquisition item type";
}
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <volk/volk.h>
#include "galileo_e1_signal_processing.h"
@ -66,7 +65,7 @@ GalileoE1PcpsCccwsrAmbiguousAcquisition::GalileoE1PcpsCccwsrAmbiguousAcquisition
if (sampled_ms_ % 4 != 0)
{
sampled_ms_ = (int)(sampled_ms_/4) * 4;
LOG_AT_LEVEL(WARNING) << "coherent_integration_time should be multiple of "
LOG(WARNING) << "coherent_integration_time should be multiple of "
<< "Galileo code length (4 ms). coherent_integration_time = "
<< sampled_ms_ << " ms will be used.";
}
@ -104,7 +103,7 @@ GalileoE1PcpsCccwsrAmbiguousAcquisition::GalileoE1PcpsCccwsrAmbiguousAcquisition
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unknown acquisition item type";
}
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "galileo_e1_signal_processing.h"
#include "Galileo_E1.h"
@ -65,7 +64,7 @@ GalileoE1PcpsTongAmbiguousAcquisition::GalileoE1PcpsTongAmbiguousAcquisition(
if (sampled_ms_ % 4 != 0)
{
sampled_ms_ = (int)(sampled_ms_/4) * 4;
LOG_AT_LEVEL(WARNING) << "coherent_integration_time should be multiple of "
LOG(WARNING) << "coherent_integration_time should be multiple of "
<< "Galileo code length (4 ms). coherent_integration_time = "
<< sampled_ms_ << " ms will be used.";
@ -105,7 +104,7 @@ GalileoE1PcpsTongAmbiguousAcquisition::GalileoE1PcpsTongAmbiguousAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unknown acquisition item type";
}
}
@ -134,9 +133,9 @@ GalileoE1PcpsTongAmbiguousAcquisition::set_threshold(float threshold)
float pfa = configuration_->property(role_+ boost::lexical_cast<std::string>(channel_) + ".pfa", 0.0);
if(pfa==0.0) pfa = configuration_->property(role_+".pfa", 0.0);
if(pfa == 0.0) pfa = configuration_->property(role_+".pfa", 0.0);
if(pfa==0.0)
if(pfa == 0.0)
{
threshold_ = threshold;
}

View File

@ -37,7 +37,6 @@
#include <iostream>
#include <stdexcept>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include "gps_sdr_signal_processing.h"
@ -106,7 +105,7 @@ GpsL1CaPcpsAcquisition::GpsL1CaPcpsAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unknown acquisition item type";
}
}
@ -132,11 +131,11 @@ void GpsL1CaPcpsAcquisition::set_threshold(float threshold)
{
float pfa = configuration_->property(role_ + boost::lexical_cast<std::string>(channel_) + ".pfa", 0.0);
if(pfa==0.0)
if(pfa == 0.0)
{
pfa = configuration_->property(role_+".pfa", 0.0);
}
if(pfa==0.0)
if(pfa == 0.0)
{
threshold_ = threshold;
}
@ -248,24 +247,21 @@ void GpsL1CaPcpsAcquisition::reset()
float GpsL1CaPcpsAcquisition::calculate_threshold(float pfa)
{
//Calculate the threshold
unsigned int frequency_bins = 0;
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)
{
frequency_bins++;
}
DLOG(INFO) <<"Channel "<<channel_<<" Pfa = "<< pfa;
unsigned int ncells = vector_length_*frequency_bins;
double exponent = 1/(double)ncells;
double val = pow(1.0-pfa,exponent);
double lambda = double(vector_length_);
//Calculate the threshold
unsigned int frequency_bins = 0;
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)
{
frequency_bins++;
}
DLOG(INFO) << "Channel " << channel_<< " Pfa = " << pfa;
unsigned int ncells = vector_length_*frequency_bins;
double exponent = 1/(double)ncells;
double val = pow(1.0 - pfa, exponent);
double lambda = double(vector_length_);
boost::math::exponential_distribution<double> mydist (lambda);
float threshold = (float)quantile(mydist,val);
float threshold = (float)quantile(mydist,val);
return threshold;
return threshold;
}

View File

@ -34,7 +34,6 @@
#include "gps_l1_ca_pcps_acquisition_fine_doppler.h"
#include <iostream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "gps_sdr_signal_processing.h"
@ -85,8 +84,7 @@ GpsL1CaPcpsAcquisitionFineDoppler::GpsL1CaPcpsAcquisitionFineDoppler(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unknown acquisition item type";
LOG(WARNING) << item_type_ << " unknown acquisition item type";
}
}

View File

@ -34,7 +34,6 @@
#include "gps_l1_ca_pcps_assisted_acquisition.h"
#include <iostream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gps_sdr_signal_processing.h"
#include "GPS_L1_CA.h"
@ -84,8 +83,7 @@ GpsL1CaPcpsAssistedAcquisition::GpsL1CaPcpsAssistedAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unknown acquisition item type";
LOG(WARNING) << item_type_ << " unknown acquisition item type";
}
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <stdexcept>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include "gps_sdr_signal_processing.h"
@ -102,8 +101,7 @@ GpsL1CaPcpsMultithreadAcquisition::GpsL1CaPcpsMultithreadAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unknown acquisition item type";
LOG(WARNING) << item_type_ << " unknown acquisition item type";
}
}
@ -128,11 +126,11 @@ void GpsL1CaPcpsMultithreadAcquisition::set_threshold(float threshold)
{
float pfa = configuration_->property(role_ + boost::lexical_cast<std::string>(channel_) + ".pfa", 0.0);
if(pfa==0.0)
if(pfa == 0.0)
{
pfa = configuration_->property(role_+".pfa", 0.0);
}
if(pfa==0.0)
if(pfa == 0.0)
{
threshold_ = threshold;
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <stdexcept>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include "gps_sdr_signal_processing.h"
@ -101,8 +100,7 @@ GpsL1CaPcpsOpenClAcquisition::GpsL1CaPcpsOpenClAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unknown acquisition item type";
LOG(WARNING) << item_type_ << " unknown acquisition item type";
}
}

View File

@ -33,7 +33,6 @@
#include <iostream>
#include <stdexcept>
#include <boost/math/distributions/exponential.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include "gps_sdr_signal_processing.h"
@ -94,8 +93,7 @@ GpsL1CaPcpsTongAcquisition::GpsL1CaPcpsTongAcquisition(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unknown acquisition item type";
LOG(WARNING) << item_type_ << " unknown acquisition item type";
}
}

View File

@ -31,7 +31,6 @@
#include "galileo_pcps_8ms_acquisition_cc.h"
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -36,7 +36,6 @@
#include <sys/time.h>
#include <sstream>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <volk/volk.h>
#include "gnss_signal_processing.h"

View File

@ -33,7 +33,6 @@
#include "pcps_acquisition_fine_doppler_cc.h"
#include <algorithm> // std::rotate
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -32,7 +32,6 @@
#include "pcps_assisted_acquisition_cc.h"
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -36,7 +36,6 @@
#include "pcps_cccwsr_acquisition_cc.h"
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -34,7 +34,6 @@
#include "pcps_multithread_acquisition_cc.h"
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -54,7 +54,6 @@
#include <fstream>
#include <iostream>
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -50,7 +50,6 @@
#include "pcps_tong_acquisition_cc.h"
#include <sstream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <volk/volk.h>

View File

@ -34,7 +34,6 @@
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <boost/thread/thread.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include <gnuradio/message.h>
@ -120,7 +119,7 @@ void Channel::connect(gr::top_block_sptr top_block)
{
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "channel already connected internally";
LOG(WARNING) << "channel already connected internally";
return;
}
pass_through_->connect(top_block);
@ -143,7 +142,7 @@ void Channel::disconnect(gr::top_block_sptr top_block)
{
if (!connected_)
{
LOG_AT_LEVEL(WARNING) << "Channel already disconnected internally";
LOG(WARNING) << "Channel already disconnected internally";
return;
}
top_block->disconnect(pass_through_->get_right_block(), 0, acq_->get_left_block(), 0);
@ -267,7 +266,7 @@ void Channel::process_channel_messages()
}
break;
default:
LOG_AT_LEVEL(WARNING) << "Default case, invalid message.";
LOG(WARNING) << "Default case, invalid message.";
break;
}
}

View File

@ -30,7 +30,6 @@
#include "gps_l1_ca_channel_fsm.h"
#include <list>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "channel.h"

View File

@ -36,7 +36,6 @@
#include <boost/thread/thread.hpp>
#include <gnuradio/io_signature.h>
#include <gnuradio/message.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gnss_flowgraph.h"
@ -70,7 +69,7 @@ void ArraySignalConditioner::connect(gr::top_block_sptr top_block)
// note: the array signal conditioner do not have data type adapter, and must use the array input filter (multichannel)
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "Array Signal conditioner already connected internally";
LOG(WARNING) << "Array Signal conditioner already connected internally";
return;
}
//data_type_adapt_->connect(top_block);
@ -95,7 +94,7 @@ void ArraySignalConditioner::disconnect(gr::top_block_sptr top_block)
{
if (!connected_)
{
LOG_AT_LEVEL(WARNING) << "Array Signal conditioner already disconnected internally";
LOG(WARNING) << "Array Signal conditioner already disconnected internally";
return;
}

View File

@ -36,7 +36,6 @@
#include <boost/thread/thread.hpp>
#include <gnuradio/io_signature.h>
#include <gnuradio/message.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gnss_flowgraph.h"
@ -69,7 +68,7 @@ void SignalConditioner::connect(gr::top_block_sptr top_block)
{
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "Signal conditioner already connected internally";
LOG(WARNING) << "Signal conditioner already connected internally";
return;
}
data_type_adapt_->connect(top_block);
@ -95,7 +94,7 @@ void SignalConditioner::disconnect(gr::top_block_sptr top_block)
{
if (!connected_)
{
LOG_AT_LEVEL(WARNING) << "Signal conditioner already disconnected internally";
LOG(WARNING) << "Signal conditioner already disconnected internally";
return;
}

View File

@ -29,7 +29,6 @@
*/
#include "ishort_to_complex.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"

View File

@ -29,7 +29,6 @@
*/
#include "beamformer_filter.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include "beamformer.h"
@ -60,7 +59,7 @@ BeamformerFilter::BeamformerFilter(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unrecognized item type for beamformer";
item_size_ = sizeof(gr_complex);
}

View File

@ -31,7 +31,6 @@
#include "fir_filter.h"
#include <boost/lexical_cast.hpp>
#include <gnuradio/filter/pm_remez.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"
@ -59,7 +58,7 @@ FirFilter::FirFilter(ConfigurationInterface* configuration, std::string role,
}
else
{
LOG_AT_LEVEL(ERROR) << taps_item_type_ << " unknown input filter item type";
LOG(ERROR) << taps_item_type_ << " unknown input filter item type";
}
}

View File

@ -32,7 +32,6 @@
#include <boost/lexical_cast.hpp>
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/filter/pm_remez.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"
@ -68,7 +67,7 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration
}
else
{
LOG_AT_LEVEL(ERROR) << taps_item_type_ << " unknown input filter item type";
LOG(ERROR) << taps_item_type_ << " unknown input filter item type";
item_size = sizeof(gr_complex); //avoids unitialization
}

View File

@ -32,13 +32,9 @@
#include "gnss_sdr_valve.h"
#include <algorithm> // for min
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "control_message_factory.h"
using google::LogMessage;
gnss_sdr_valve::gnss_sdr_valve (size_t sizeof_stream_item,
unsigned long long nitems,
gr::msg_queue::sptr queue) : gr::sync_block("valve",

View File

@ -34,7 +34,6 @@
#include "pass_through.h"
#include <iostream>
//#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"
@ -64,7 +63,7 @@ Pass_Through::Pass_Through(ConfigurationInterface* configuration, std::string ro
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " unrecognized item type. Using float";
LOG(WARNING) << item_type_ << " unrecognized item type. Using float";
item_size_ = sizeof(float);
}
kludge_copy_ = gr::blocks::copy::make(item_size_);

View File

@ -30,7 +30,6 @@
*/
#include "file_output_filter.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "configuration_interface.h"
@ -63,7 +62,7 @@ FileOutputFilter::FileOutputFilter(ConfigurationInterface* configuration,
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " Unrecognized item type. Using short.";
LOG(WARNING) << item_type_ << " Unrecognized item type. Using short.";
item_size_ = sizeof(short);
}
file_sink_ = gr::blocks::file_sink::make(item_size_, filename_.c_str());

View File

@ -30,7 +30,6 @@
*/
#include "null_sink_output_filter.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "configuration_interface.h"
@ -61,7 +60,7 @@ NullSinkOutputFilter::NullSinkOutputFilter(ConfigurationInterface* configuration
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " unrecognized item type. Using float";
LOG(WARNING) << item_type_ << " unrecognized item type. Using float";
item_size_ = sizeof(float);
}
sink_ = gr::blocks::null_sink::make(item_size_);
@ -98,7 +97,7 @@ gr::basic_block_sptr NullSinkOutputFilter::get_left_block()
gr::basic_block_sptr NullSinkOutputFilter::get_right_block()
{
LOG_AT_LEVEL(WARNING) << "Right block of a signal sink should not be retrieved";
LOG(WARNING) << "Right block of a signal sink should not be retrieved";
//return gr::blocks::sptr::make();
return sink_;
}

View File

@ -30,7 +30,6 @@
*/
#include "direct_resampler_conditioner.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include "direct_resampler_conditioner_cc.h"
@ -73,8 +72,7 @@ DirectResamplerConditioner::DirectResamplerConditioner(
// }
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unrecognized item type for resampler";
LOG(WARNING) << item_type_ << " unrecognized item type for resampler";
item_size_ = sizeof(short);
}
if (dump_)

View File

@ -36,7 +36,6 @@
#include <algorithm>
#include <iostream>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;

View File

@ -36,7 +36,6 @@
#include <algorithm>
#include <iostream>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gps_sdr_signal_processing.h"

View File

@ -30,11 +30,11 @@
*/
#include "signal_generator.h"
#include <glog/logging.h>
#include "configuration_interface.h"
#include "Galileo_E1.h"
#include "GPS_L1_CA.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
@ -103,7 +103,7 @@ SignalGenerator::SignalGenerator(ConfigurationInterface* configuration,
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " unrecognized item type for resampler";
LOG(WARNING) << item_type_ << " unrecognized item type for resampler";
item_size_ = sizeof(short);
}
@ -155,7 +155,7 @@ void SignalGenerator::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr SignalGenerator::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Left block of a signal source should not be retrieved";
LOG(WARNING) << "Left block of a signal source should not be retrieved";
return gr::block_sptr();
}

View File

@ -52,6 +52,9 @@ if($ENV{GN3S_DRIVER})
endif($ENV{GN3S_DRIVER})
if($ENV{RAW_ARRAY_DRIVER})
set(RAW_ARRAY_DRIVER ON)
endif($ENV{RAW_ARRAY_DRIVER})
if(RAW_ARRAY_DRIVER)
##############################################
# GRDBFCTTC GNSS EXPERIMENTAL ARRAY PROTOTYPE
##############################################
@ -65,6 +68,7 @@ if($ENV{RAW_ARRAY_DRIVER})
BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR}/../../../../gr-dbfcttc
UPDATE_COMMAND ""
PATCH_COMMAND ""
CMAKE_ARGS -DCMAKE_CXX_COMPILER=/usr/bin/clang++
INSTALL_COMMAND ""
)
@ -76,8 +80,7 @@ if($ENV{RAW_ARRAY_DRIVER})
set(OPT_LIBRARIES ${OPT_LIBRARIES} ${GRDBFCTTC_LIBRARIES})
set(OPT_DRIVER_INCLUDE_DIRS ${OPT_DRIVER_INCLUDE_DIRS} ${GRDBFCTTC_INCLUDE_DIRS})
set(OPT_DRIVER_SOURCES ${OPT_DRIVER_SOURCES} raw_array_signal_source.cc)
endif($ENV{RAW_ARRAY_DRIVER})
endif(RAW_ARRAY_DRIVER)
if($ENV{RTLSDR_DRIVER})

View File

@ -36,13 +36,13 @@
#include <iomanip>
#include <exception>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gnss_sdr_valve.h"
#include "configuration_interface.h"
using google::LogMessage;
DEFINE_string(signal_source, "-",
"If defined, path to the file containing the signal samples (overrides the configuration file)");
@ -83,7 +83,7 @@ FileSignalSource::FileSignalSource(ConfigurationInterface* configuration,
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unrecognized item type. Using gr_complex.";
item_size_ = sizeof(gr_complex);
}
@ -108,7 +108,7 @@ FileSignalSource::FileSignalSource(ConfigurationInterface* configuration,
<< std::endl
<<"gnss-sdr --config_file=my_GNSS_SDR_configuration.conf"
<< std::endl;
LOG_AT_LEVEL(INFO) << "file_signal_source: Unable to open the samples file "
LOG(INFO) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
@ -133,7 +133,7 @@ FileSignalSource::FileSignalSource(ConfigurationInterface* configuration,
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << std::endl;
LOG_AT_LEVEL(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << (double)size << " [bytes]" << std::endl;
@ -297,7 +297,7 @@ void FileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr FileSignalSource::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Left block of a signal source should not be retrieved";
LOG(WARNING) << "Left block of a signal source should not be retrieved";
return gr::blocks::file_source::sptr();
}

View File

@ -31,14 +31,12 @@
*/
#include "gen_signal_source.h"
//#include "gnss_flowgraph.h"
#include <iostream>
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <boost/thread/thread.hpp>
#include <gnuradio/io_signature.h>
#include <gnuradio/message.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
@ -68,7 +66,7 @@ void GenSignalSource::connect(gr::top_block_sptr top_block)
{
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "Signal conditioner already connected internally";
LOG(WARNING) << "Signal conditioner already connected internally";
return;
}
@ -88,7 +86,7 @@ void GenSignalSource::disconnect(gr::top_block_sptr top_block)
{
if (!connected_)
{
LOG_AT_LEVEL(WARNING) << "Signal conditioner already disconnected internally";
LOG(WARNING) << "Signal conditioner already disconnected internally";
return;
}

View File

@ -31,10 +31,10 @@
#include "gn3s_signal_source.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/msg_queue.h>
#include <glog/logging.h>
#include <gn3s/gn3s_source_cc.h>
#include "configuration_interface.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
@ -64,7 +64,7 @@ Gn3sSignalSource::Gn3sSignalSource(ConfigurationInterface* configuration,
// }
else
{
LOG_AT_LEVEL(WARNING) << item_type_
LOG(WARNING) << item_type_
<< " unrecognized item type for resampler";
item_size_ = sizeof(short);
}

View File

@ -36,7 +36,6 @@
#include <iomanip>
#include <iostream>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gnss_sdr_valve.h"
#include "configuration_interface.h"
@ -76,8 +75,7 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unrecognized item type. Using byte.";
LOG(WARNING) << item_type_ << " unrecognized item type. Using byte.";
item_size_ = sizeof(char);
}
try
@ -102,8 +100,8 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
<< std::endl
<<"gnss-sdr --config_file=my_GNSS_SDR_configuration.conf"
<< std::endl;
LOG_AT_LEVEL(INFO) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
LOG(WARNING) << "file_signal_source: Unable to open the samples file "
<< filename_.c_str() << ", exiting the program.";
throw(e);
}
@ -122,28 +120,28 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
if (file.is_open())
{
size = file.tellg();
DLOG(INFO) << "Total samples in the file= " << floor((double)size / (double)item_size());
LOG(INFO) << "Total samples in the file= " << floor((double)size / (double)item_size());
}
else
{
std::cout << "file_signal_source: Unable to open the samples file " << filename_.c_str() << std::endl;
LOG_AT_LEVEL(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
LOG(ERROR) << "file_signal_source: Unable to open the samples file " << filename_.c_str();
}
std::cout << std::setprecision(16);
std::cout << "Processing file " << filename_ << ", which contains " << (double)size << " [bytes]" << std::endl;
if (size > 0)
{
int sample_packet_factor=4; // 1 byte -> 4 samples
samples_ = floor((double)size / (double)item_size())*sample_packet_factor;
samples_=samples_- ceil(0.002 * (double)sampling_frequency_); //process all the samples available in the file excluding the last 2 ms
int sample_packet_factor = 4; // 1 byte -> 4 samples
samples_ = floor((double)size / (double)item_size())*sample_packet_factor;
samples_ = samples_- ceil(0.002 * (double)sampling_frequency_); //process all the samples available in the file excluding the last 2 ms
}
}
CHECK(samples_ > 0) << "File does not contain enough samples to process.";
double signal_duration_s;
signal_duration_s = (double)samples_ * ( 1 /(double)sampling_frequency_);
DLOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
LOG(INFO) << "Total number samples to be processed= " << samples_ << " GNSS signal duration= " << signal_duration_s << " [s]";
std::cout << "GNSS signal recorded time to be processed: " << signal_duration_s << " [s]" << std::endl;
valve_ = gnss_sdr_make_valve(sizeof(float), samples_, queue_);
@ -159,7 +157,6 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
if (enable_throttle_control_)
{
throttle_ = gr::blocks::throttle::make(sizeof(float), sampling_frequency_);
}
DLOG(INFO) << "File source filename " << filename_;
DLOG(INFO) << "Samples " << samples_;
@ -188,7 +185,6 @@ void NsrFileSignalSource::connect(gr::top_block_sptr top_block)
{
top_block->connect(file_source_, 0, unpack_byte_, 0);
top_block->connect(unpack_byte_, 0,throttle_,0);
DLOG(INFO) << "connected file source to throttle";
top_block->connect(throttle_, 0, valve_, 0);
DLOG(INFO) << "connected throttle to valve";
@ -275,8 +271,8 @@ void NsrFileSignalSource::disconnect(gr::top_block_sptr top_block)
{
if (enable_throttle_control_ == true)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, throttle_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to throttle";
if (dump_)
@ -289,8 +285,8 @@ void NsrFileSignalSource::disconnect(gr::top_block_sptr top_block)
{
if (dump_)
{
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(file_source_, 0, unpack_byte_, 0);
DLOG(INFO) << "disconnected file source to unpack_byte_";
top_block->disconnect(unpack_byte_, 0, sink_, 0);
DLOG(INFO) << "disconnected unpack_byte_ to sink";
}
@ -304,7 +300,7 @@ void NsrFileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr NsrFileSignalSource::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Left block of a signal source should not be retrieved";
LOG(WARNING) << "Left block of a signal source should not be retrieved";
//return gr_block_sptr();
return gr::blocks::file_source::sptr();
}

View File

@ -31,10 +31,10 @@
#include "raw_array_signal_source.h"
#include <gnuradio/blocks/file_sink.h>
#include <gnuradio/msg_queue.h>
#include <glog/logging.h>
#include <dbfcttc/raw_array.h>
#include "configuration_interface.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
using google::LogMessage;
@ -83,8 +83,7 @@ RawArraySignalSource::RawArraySignalSource(ConfigurationInterface* configuration
// }
else
{
LOG_AT_LEVEL(WARNING) << item_type_
<< " unrecognized item type for raw_array_source_";
LOG(WARNING) << item_type_ << " unrecognized item type for raw_array_source_";
item_size_ = sizeof(gr_complex);
}
if (dump_)
@ -134,7 +133,7 @@ void RawArraySignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr RawArraySignalSource::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Left block of a signal source should not be retrieved";
LOG(WARNING) << "Left block of a signal source should not be retrieved";
return gr::block_sptr();
}

View File

@ -32,7 +32,6 @@
#include "rtlsdr_signal_source.h"
#include <iostream>
#include <boost/format.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/blocks/file_sink.h>
#include "configuration_interface.h"
@ -117,7 +116,7 @@ RtlsdrSignalSource::RtlsdrSignalSource(ConfigurationInterface* configuration,
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " unrecognized item type. Using short.";
LOG(WARNING) << item_type_ << " unrecognized item type. Using short.";
item_size_ = sizeof(short);
}
@ -190,7 +189,7 @@ void RtlsdrSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr RtlsdrSignalSource::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Trying to get signal source left block.";
LOG(WARNING) << "Trying to get signal source left block.";
return gr::basic_block_sptr();
}

View File

@ -96,7 +96,7 @@ private:
bool dump_;
std::string dump_filename_;
boost::shared_ptr<osmosdr::source> rtlsdr_source_;
osmosdr::source::sptr rtlsdr_source_;
boost::shared_ptr<gr::block> valve_;
gr::blocks::file_sink::sptr file_sink_;

View File

@ -32,7 +32,6 @@
#include <iostream>
#include <uhd/types/device_addr.hpp>
#include <uhd/exception.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"
#include "gnss_sdr_valve.h"
@ -159,20 +158,20 @@ UhdSignalSource::UhdSignalSource(ConfigurationInterface* configuration,
}
else
{
LOG_AT_LEVEL(WARNING) << item_type_ << " unrecognized item type. Using short.";
LOG(WARNING) << item_type_ << " unrecognized item type. Using short.";
item_size_ = sizeof(short);
}
if (samples_ != 0)
{
DLOG(INFO) << "Send STOP signal after " << samples_ << " samples";
LOG(INFO) << "Send STOP signal after " << samples_ << " samples";
valve_ = gnss_sdr_make_valve(item_size_, samples_, queue_);
DLOG(INFO) << "valve(" << valve_->unique_id() << ")";
}
if (dump_)
{
DLOG(INFO) << "Dumping output into file " << dump_filename_;
LOG(INFO) << "Dumping output into file " << dump_filename_;
//file_sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
file_sink_ = gr::blocks::file_sink::make(item_size_, dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << file_sink_->unique_id() << ")";
@ -215,7 +214,7 @@ void UhdSignalSource::disconnect(gr::top_block_sptr top_block)
if (samples_ != 0)
{
top_block->disconnect(uhd_source_, 0, valve_, 0);
DLOG(INFO) << "usrp source disconnected";
LOG(INFO) << "UHD source disconnected";
if (dump_)
{
top_block->disconnect(valve_, 0, file_sink_, 0);
@ -234,7 +233,7 @@ void UhdSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr UhdSignalSource::get_left_block()
{
LOG_AT_LEVEL(WARNING) << "Trying to get signal source left block.";
LOG(WARNING) << "Trying to get signal source left block.";
//return gr_basic_block_sptr();
return gr::uhd::usrp_source::sptr();
}

View File

@ -32,16 +32,14 @@
#include "galileo_e1b_telemetry_decoder.h"
#include "configuration_interface.h"
#include "galileo_e1b_telemetry_decoder_cc.h"
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "galileo_ephemeris.h"
#include "galileo_almanac.h"
#include "galileo_iono.h"
#include "galileo_utc_model.h"
#include "configuration_interface.h"
#include "galileo_e1b_telemetry_decoder_cc.h"
extern concurrent_queue<Galileo_Ephemeris> global_galileo_ephemeris_queue;
extern concurrent_queue<Galileo_Iono> global_galileo_iono_queue;

View File

@ -31,16 +31,14 @@
#include "gps_l1_ca_telemetry_decoder.h"
#include "configuration_interface.h"
#include "gps_l1_ca_telemetry_decoder_cc.h"
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gps_ephemeris.h"
#include "gps_almanac.h"
#include "gps_iono.h"
#include "gps_utc_model.h"
#include "configuration_interface.h"
#include "gps_l1_ca_telemetry_decoder_cc.h"
extern concurrent_queue<Gps_Ephemeris> global_gps_ephemeris_queue;
extern concurrent_queue<Gps_Iono> global_gps_iono_queue;

View File

@ -31,16 +31,14 @@
#include "sbas_l1_telemetry_decoder.h"
#include "configuration_interface.h"
#include "sbas_l1_telemetry_decoder_cc.h"
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "sbas_telemetry_data.h"
#include "sbas_ionospheric_correction.h"
#include "sbas_satellite_correction.h"
#include "sbas_ephemeris.h"
#include "configuration_interface.h"
#include "sbas_l1_telemetry_decoder_cc.h"
extern concurrent_queue<Sbas_Raw_Msg> global_sbas_raw_msg_queue;
extern concurrent_queue<Sbas_Ionosphere_Correction> global_sbas_iono_queue;

View File

@ -37,7 +37,6 @@
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "galileo_navigation_message.h"
@ -130,7 +129,7 @@ galileo_e1b_telemetry_decoder_cc::galileo_e1b_telemetry_decoder_cc(
d_queue = queue;
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "GALILEO E1B TELEMETRY PROCESSING: satellite " << d_satellite;
LOG(INFO) << "GALILEO E1B TELEMETRY PROCESSING: satellite " << d_satellite;
d_vector_length = vector_length;
d_samples_per_symbol = ( Galileo_E1_CODE_CHIP_RATE_HZ / Galileo_E1_B_CODE_LENGTH_CHIPS ) / Galileo_E1_B_SYMBOL_RATE_BPS;
d_fs_in = fs_in;
@ -226,11 +225,13 @@ void galileo_e1b_telemetry_decoder_cc::decode_word(double *page_part_symbols,int
d_nav.split_page(page_String, flag_even_word_arrived);
if(d_nav.flag_CRC_test == true)
{
LOG(INFO) << "Galileo CRC correct on channel " << d_channel;
std::cout << "Galileo CRC correct on channel " << d_channel << std::endl;
}
else
{
std::cout << "Galileo CRC error on channel " << d_channel << std::endl;
LOG(INFO)<< "Galileo CRC error on channel " << d_channel;
}
flag_even_word_arrived = 0;
}
@ -299,7 +300,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
if (abs(corr_value) >= d_symbols_per_preamble)
{
d_preamble_index = d_sample_counter;//record the preamble sample stamp
std::cout << "Preamble detection for Galileo SAT " << this->d_satellite << std::endl;
LOG(INFO) << "Preamble detection for Galileo SAT " << this->d_satellite << std::endl;
d_stat = 1; // enter into frame pre-detection status
}
}
@ -312,7 +313,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
if (abs(preamble_diff - GALILEO_INAV_PREAMBLE_PERIOD_SYMBOLS) == 0)
{
//try to decode frame
std::cout << "Starting page decoder for Galileo SAT " << this->d_satellite << std::endl;
LOG(INFO) << "Starting page decoder for Galileo SAT " << this->d_satellite << std::endl;
d_preamble_index = d_sample_counter; //record the preamble sample stamp
d_stat = 2;
}
@ -371,7 +372,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
if (!d_flag_frame_sync)
{
d_flag_frame_sync = true;
std::cout <<" Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]" << std::endl;
LOG(INFO) <<" Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]";
}
}
else
@ -380,7 +381,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
d_preamble_index = d_sample_counter; //record the preamble sample stamp
if (d_CRC_error_counter > CRC_ERROR_LIMIT)
{
std::cout << "Lost of frame sync SAT " << this->d_satellite << std::endl;
LOG(INFO) << "Lost of frame sync SAT " << this->d_satellite;
d_flag_frame_sync = false;
d_stat = 0;
}
@ -464,7 +465,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
}
catch (const std::ifstream::failure& e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing observables dump file " << e.what();
}
}
//3. Make the output (copy the object contents to the GNURadio reserved memory)
@ -476,7 +477,7 @@ int galileo_e1b_telemetry_decoder_cc::general_work (int noutput_items, gr_vector
void galileo_e1b_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
@ -484,7 +485,7 @@ void galileo_e1b_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
void galileo_e1b_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
DLOG(INFO) << "Navigation channel set to " << channel;
LOG(INFO) << "Navigation channel set to " << channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -497,13 +498,11 @@ void galileo_e1b_telemetry_decoder_cc::set_channel(int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Telemetry decoder dump enabled on channel " << d_channel << " Log file: "
<< d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Telemetry decoder dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (const std::ifstream::failure& e)
{
std::cout << "channel " << d_channel
<< " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -39,7 +39,6 @@
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "control_message_factory.h"
#include "gnss_synchro.h"
@ -87,7 +86,7 @@ gps_l1_ca_telemetry_decoder_cc::gps_l1_ca_telemetry_decoder_cc(
d_queue = queue;
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "TELEMETRY PROCESSING: satellite " << d_satellite;
LOG(INFO) << "TELEMETRY PROCESSING: satellite " << d_satellite;
d_vector_length = vector_length;
d_samples_per_bit = ( GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS ) / GPS_CA_TELEMETRY_RATE_BITS_SECOND;
d_fs_in = fs_in;
@ -202,7 +201,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_i
{
d_GPS_FSM.Event_gps_word_preamble();
d_preamble_index = d_sample_counter;//record the preamble sample stamp
std::cout << "Preamble detection for SAT " << this->d_satellite << std::endl;
LOG(INFO) << "Preamble detection for SAT " << this->d_satellite;
d_symbol_accumulator = 0; //sync the symbol to bits integrator
d_symbol_accumulator_counter = 0;
d_frame_bit_index = 8;
@ -221,7 +220,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_i
if (!d_flag_frame_sync)
{
d_flag_frame_sync = true;
std::cout <<" Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]" << std::endl;
LOG(INFO) <<" Frame sync SAT " << this->d_satellite << " with preamble start at " << d_preamble_time_seconds << " [s]";
}
}
}
@ -233,7 +232,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_i
preamble_diff = d_sample_counter - d_preamble_index;
if (preamble_diff > 6001)
{
std::cout << "Lost of frame sync SAT " << this->d_satellite << " preamble_diff= " << preamble_diff << std::endl;
LOG(INFO) << "Lost of frame sync SAT " << this->d_satellite << " preamble_diff= " << preamble_diff;
d_stat = 0; //lost of frame sync
d_flag_frame_sync = false;
flag_TOW_set=false;
@ -339,7 +338,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_i
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing observables dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing observables dump file " << e.what();
}
}
//3. Make the output (copy the object contents to the GNURadio reserved memory)
@ -351,7 +350,7 @@ int gps_l1_ca_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_i
void gps_l1_ca_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
LOG(INFO) << "Setting decoder Finite State Machine to satellite " << d_satellite;
d_GPS_FSM.i_satellite_PRN = d_satellite.get_PRN();
DLOG(INFO) << "Navigation Satellite set to " << d_satellite;
}
@ -374,13 +373,12 @@ void gps_l1_ca_telemetry_decoder_cc::set_channel(int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Telemetry decoder dump enabled on channel " << d_channel
<< " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Telemetry decoder dump enabled on channel " << d_channel
<< " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel
<< " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -31,7 +31,6 @@
#include <iostream>
#include <sstream>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <boost/lexical_cast.hpp>
#include "control_message_factory.h"
@ -73,7 +72,7 @@ sbas_l1_telemetry_decoder_cc::sbas_l1_telemetry_decoder_cc(
// initialize internal vars
d_dump = dump;
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "SBAS L1 TELEMETRY PROCESSING: satellite " << d_satellite;
LOG(INFO) << "SBAS L1 TELEMETRY PROCESSING: satellite " << d_satellite;
d_fs_in = fs_in;
d_block_size = d_samples_per_symbol * d_symbols_per_bit * d_block_size_in_bits;
set_output_multiple (1);
@ -195,7 +194,7 @@ int sbas_l1_telemetry_decoder_cc::general_work (int noutput_items, gr_vector_int
void sbas_l1_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
{
d_satellite = Gnss_Satellite(satellite.get_system(), satellite.get_PRN());
DLOG(INFO) << "SBAS telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
LOG(INFO) << "SBAS telemetry decoder in channel " << this->d_channel << " set to satellite " << d_satellite;
}
@ -203,7 +202,7 @@ void sbas_l1_telemetry_decoder_cc::set_satellite(Gnss_Satellite satellite)
void sbas_l1_telemetry_decoder_cc::set_channel(int channel)
{
d_channel = channel;
DLOG(INFO) << "SBAS channel set to " << channel;
LOG(INFO) << "SBAS channel set to " << channel;
}

View File

@ -31,7 +31,6 @@
#include "viterbi_decoder.h"
#include <iostream>
#include <glog/log_severity.h>
#include <glog/logging.h>
// logging

View File

@ -35,7 +35,6 @@
*/
#include "galileo_e1_dll_pll_veml_tracking.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "Galileo_E1.h"
@ -51,12 +50,8 @@ GalileoE1DllPllVemlTracking::GalileoE1DllPllVemlTracking(
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//DLOG(INFO) << "vector length " << vector_length;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -82,6 +77,7 @@ GalileoE1DllPllVemlTracking::GalileoE1DllPllVemlTracking(
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
vector_length = std::round(fs_in / (Galileo_E1_CODE_CHIP_RATE_HZ / Galileo_E1_B_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0)
{
@ -100,15 +96,14 @@ GalileoE1DllPllVemlTracking::GalileoE1DllPllVemlTracking(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GalileoE1DllPllVemlTracking::~GalileoE1DllPllVemlTracking()
{
}
{}
void GalileoE1DllPllVemlTracking::start_tracking()
{

View File

@ -36,7 +36,6 @@
*/
#include "galileo_e1_tcp_connector_tracking.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "Galileo_E1.h"
@ -52,12 +51,8 @@ GalileoE1TcpConnectorTracking::GalileoE1TcpConnectorTracking(
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//DLOG(INFO) << "vector length " << vector_length;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -70,7 +65,6 @@ GalileoE1TcpConnectorTracking::GalileoE1TcpConnectorTracking(
float early_late_space_chips;
float very_early_late_space_chips;
size_t port_ch0;
item_type = configuration->property(role + ".item_type",default_item_type);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
f_if = configuration->property(role + ".if", 0);
@ -80,10 +74,8 @@ GalileoE1TcpConnectorTracking::GalileoE1TcpConnectorTracking(
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.15);
very_early_late_space_chips = configuration->property(role + ".very_early_late_space_chips", 0.6);
port_ch0 = configuration->property(role + ".port_ch0", 2060);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); //unused!
vector_length = std::round(fs_in / (Galileo_E1_CODE_CHIP_RATE_HZ / Galileo_E1_B_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
@ -91,7 +83,7 @@ GalileoE1TcpConnectorTracking::GalileoE1TcpConnectorTracking(
{
item_size_ = sizeof(gr_complex);
tracking_ = galileo_e1_tcp_connector_make_tracking_cc(
f_if,
f_if,
fs_in,
vector_length,
queue_,
@ -105,15 +97,16 @@ GalileoE1TcpConnectorTracking::GalileoE1TcpConnectorTracking(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GalileoE1TcpConnectorTracking::~GalileoE1TcpConnectorTracking()
{
}
{}
void GalileoE1TcpConnectorTracking::start_tracking()
{

View File

@ -36,7 +36,6 @@
*/
#include "gps_l1_ca_dll_fll_pll_tracking.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
@ -55,12 +54,8 @@ GpsL1CaDllFllPllTracking::GpsL1CaDllFllPllTracking(
out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//DLOG(INFO) << "vector length " << vector_length;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -73,7 +68,6 @@ GpsL1CaDllFllPllTracking::GpsL1CaDllFllPllTracking(
float dll_bw_hz;
float early_late_space_chips;
int order;
item_type = configuration->property(role + ".item_type",default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
@ -84,41 +78,40 @@ GpsL1CaDllFllPllTracking::GpsL1CaDllFllPllTracking(
fll_bw_hz = configuration->property(role + ".fll_bw_hz", 100.0);
dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0)
{
item_size_ = sizeof(gr_complex);
tracking_ = gps_l1_ca_dll_fll_pll_make_tracking_cc(
f_if,
fs_in,
vector_length,
queue_,
dump,
dump_filename,
order,
fll_bw_hz,
pll_bw_hz,
dll_bw_hz,
early_late_space_chips);
}
{
item_size_ = sizeof(gr_complex);
tracking_ = gps_l1_ca_dll_fll_pll_make_tracking_cc(
f_if,
fs_in,
vector_length,
queue_,
dump,
dump_filename,
order,
fll_bw_hz,
pll_bw_hz,
dll_bw_hz,
early_late_space_chips);
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
}
{
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GpsL1CaDllFllPllTracking::~GpsL1CaDllFllPllTracking()
{
}
{}
void GpsL1CaDllFllPllTracking::start_tracking()
{
@ -135,9 +128,7 @@ void GpsL1CaDllFllPllTracking::set_channel_queue(
concurrent_queue<int> *channel_internal_queue)
{
channel_internal_queue_ = channel_internal_queue;
tracking_->set_channel_queue(channel_internal_queue_);
}
void GpsL1CaDllFllPllTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)

View File

@ -37,12 +37,11 @@
*/
#include "gps_l1_ca_dll_pll_optim_tracking.h"
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
#include <boost/math/special_functions/round.hpp>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
using google::LogMessage;
@ -53,11 +52,8 @@ GpsL1CaDllPllOptimTracking::GpsL1CaDllPllOptimTracking(
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -68,7 +64,6 @@ GpsL1CaDllPllOptimTracking::GpsL1CaDllPllOptimTracking(
float pll_bw_hz;
float dll_bw_hz;
float early_late_space_chips;
item_type = configuration->property(role + ".item_type",default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
@ -77,18 +72,16 @@ GpsL1CaDllPllOptimTracking::GpsL1CaDllPllOptimTracking(
pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0);
dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); //unused!
vector_length = round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0)
{
item_size_ = sizeof(gr_complex);
tracking_ = gps_l1_ca_dll_pll_make_optim_tracking_cc(
f_if,
f_if,
fs_in,
vector_length,
queue_,
@ -100,15 +93,15 @@ GpsL1CaDllPllOptimTracking::GpsL1CaDllPllOptimTracking(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GpsL1CaDllPllOptimTracking::~GpsL1CaDllPllOptimTracking()
{
}
{}
void GpsL1CaDllPllOptimTracking::start_tracking()
{
@ -131,9 +124,7 @@ void GpsL1CaDllPllOptimTracking::set_channel_queue(
concurrent_queue<int> *channel_internal_queue)
{
channel_internal_queue_ = channel_internal_queue;
tracking_->set_channel_queue(channel_internal_queue_);
}
void GpsL1CaDllPllOptimTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)

View File

@ -36,9 +36,8 @@
*/
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gps_l1_ca_dll_pll_tracking.h"
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
@ -49,15 +48,11 @@ GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams,
boost::shared_ptr<gr::msg_queue> queue) :
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//DLOG(INFO) << "vector length " << vector_length;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -68,7 +63,6 @@ GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
float pll_bw_hz;
float dll_bw_hz;
float early_late_space_chips;
item_type = configuration->property(role + ".item_type", default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
@ -77,7 +71,6 @@ GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
pll_bw_hz = configuration->property(role + ".pll_bw_hz", 50.0);
dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
@ -88,7 +81,7 @@ GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
{
item_size_ = sizeof(gr_complex);
tracking_ = gps_l1_ca_dll_pll_make_tracking_cc(
f_if,
f_if,
fs_in,
vector_length,
queue_,
@ -100,15 +93,15 @@ GpsL1CaDllPllTracking::GpsL1CaDllPllTracking(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GpsL1CaDllPllTracking::~GpsL1CaDllPllTracking()
{
}
{}
void GpsL1CaDllPllTracking::start_tracking()
{
@ -131,9 +124,7 @@ void GpsL1CaDllPllTracking::set_channel_queue(
concurrent_queue<int> *channel_internal_queue)
{
channel_internal_queue_ = channel_internal_queue;
tracking_->set_channel_queue(channel_internal_queue_);
}
void GpsL1CaDllPllTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)

View File

@ -36,7 +36,6 @@
*/
#include "gps_l1_ca_tcp_connector_tracking.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "GPS_L1_CA.h"
#include "configuration_interface.h"
@ -48,15 +47,11 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
ConfigurationInterface* configuration, std::string role,
unsigned int in_streams, unsigned int out_streams,
boost::shared_ptr<gr::msg_queue> queue) :
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
role_(role), in_streams_(in_streams), out_streams_(out_streams),
queue_(queue)
{
DLOG(INFO) << "role " << role;
//DLOG(INFO) << "vector length " << vector_length;
//################# CONFIGURATION PARAMETERS ########################
int fs_in;
int vector_length;
int f_if;
@ -68,7 +63,6 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
float dll_bw_hz;
float early_late_space_chips;
size_t port_ch0;
item_type = configuration->property(role + ".item_type",default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048);
fs_in = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
@ -78,10 +72,8 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
dll_bw_hz = configuration->property(role + ".dll_bw_hz", 2.0);
early_late_space_chips = configuration->property(role + ".early_late_space_chips", 0.5);
port_ch0 = configuration->property(role + ".port_ch0", 2060);
std::string default_dump_filename = "./track_ch";
dump_filename = configuration->property(role + ".dump_filename",
default_dump_filename); //unused!
dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); //unused!
vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ###################
@ -89,7 +81,7 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
{
item_size_ = sizeof(gr_complex);
tracking_ = gps_l1_ca_tcp_connector_make_tracking_cc(
f_if,
f_if,
fs_in,
vector_length,
queue_,
@ -102,15 +94,15 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
}
else
{
LOG_AT_LEVEL(WARNING) << item_type << " unknown tracking item type.";
LOG(WARNING) << item_type << " unknown tracking item type.";
}
DLOG(INFO) << "tracking(" << tracking_->unique_id() << ")";
}
GpsL1CaTcpConnectorTracking::~GpsL1CaTcpConnectorTracking()
{
}
{}
void GpsL1CaTcpConnectorTracking::start_tracking()
{
@ -133,9 +125,7 @@ void GpsL1CaTcpConnectorTracking::set_channel_queue(
concurrent_queue<int> *channel_internal_queue)
{
channel_internal_queue_ = channel_internal_queue;
tracking_->set_channel_queue(channel_internal_queue_);
}
void GpsL1CaTcpConnectorTracking::set_gnss_synchro(Gnss_Synchro* p_gnss_synchro)

View File

@ -34,20 +34,21 @@
* -------------------------------------------------------------------------
*/
#include "gnss_synchro.h"
#include "galileo_e1_dll_pll_veml_tracking_cc.h"
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "galileo_e1_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
#include "Galileo_E1.h"
#include "control_message_factory.h"
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <sstream>
#include <cmath>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
/*!
* \todo Include in definition header file
@ -211,16 +212,15 @@ void galileo_e1_dll_pll_veml_tracking_cc::start_tracking()
sys = sys_.substr(0, 1);
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel
<< " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " received";
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples << std::endl;
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
}
@ -420,7 +420,8 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items,gr_vect
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl ;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr())
{
@ -465,7 +466,7 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items,gr_vect
tmp_str_stream << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", Doppler=" << d_carrier_doppler_hz << " [Hz] CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
std::cout << tmp_str_stream.rdbuf() << std::flush;
LOG(INFO) << tmp_str_stream.rdbuf() << std::flush;
//if (d_channel == 0 || d_last_seg==5) d_carrier_lock_fail_counter=500; //DEBUG: force unlock!
}
}
@ -530,7 +531,7 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items,gr_vect
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing trk dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing trk dump file " << e.what() << std::endl;
}
}
consume_each(d_current_prn_length_samples); // this is required for gr_block derivates
@ -543,7 +544,7 @@ int galileo_e1_dll_pll_veml_tracking_cc::general_work (int noutput_items,gr_vect
void galileo_e1_dll_pll_veml_tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
LOG_AT_LEVEL(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -555,11 +556,11 @@ void galileo_e1_dll_pll_veml_tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
}
}
}

View File

@ -13,7 +13,7 @@
*
* -------------------------------------------------------------------------
*
* 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,8 +36,15 @@
* -------------------------------------------------------------------------
*/
#include "gnss_synchro.h"
#include "galileo_e1_tcp_connector_tracking_cc.h"
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/asio.hpp>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "galileo_e1_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
@ -45,14 +52,6 @@
#include "Galileo_E1.h"
#include "control_message_factory.h"
#include "tcp_communication.h"
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <sstream>
#include <cmath>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <boost/asio.hpp>
#include "tcp_packet_data.h"
/*!
@ -119,11 +118,11 @@ Galileo_E1_Tcp_Connector_Tracking_cc::Galileo_E1_Tcp_Connector_Tracking_cc(
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
d_very_early_late_spc_chips = very_early_late_space_chips; // Define very-early-late offset (in chips)
//--- TCP CONNECTOR variables --------------------------------------------------------
d_port_ch0 = port_ch0;
d_port = 0;
d_listen_connection = true;
d_control_id = 0;
//--- TCP CONNECTOR variables --------------------------------------------------------
d_port_ch0 = port_ch0;
d_port = 0;
d_listen_connection = true;
d_control_id = 0;
// Initialization of local code replica
// Get space for a vector with the sinboc(1,1) replica sampled 2x/chip
@ -213,14 +212,13 @@ void Galileo_E1_Tcp_Connector_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " received";
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples << std::endl;
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz << " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
}
@ -438,7 +436,8 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_ve
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl ;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr())
{
@ -473,8 +472,8 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_ve
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Current input signal time = " << d_last_seg << " [s]" << std::endl;
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
else
@ -482,9 +481,9 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_ve
if (floor(d_sample_counter / d_fs_in) != d_last_seg)
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Tracking CH " << d_channel
LOG(INFO) << "Tracking CH " << d_channel
<< ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
}
@ -559,7 +558,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_ve
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing trk dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing trk dump file " << e.what();
}
}
consume_each(d_current_prn_length_samples); // this is needed in gr::block derivates
@ -572,9 +571,9 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_ve
void Galileo_E1_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
LOG_AT_LEVEL(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump==true)
if (d_dump == true)
{
if (d_dump_file.is_open() == false)
{
@ -584,11 +583,11 @@ void Galileo_E1_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -34,15 +34,14 @@
* -------------------------------------------------------------------------
*/
#include "gps_l1_ca_dll_fll_pll_tracking_cc.h"
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/io_signature.h>
#include "gnss_synchro.h"
#include "gps_l1_ca_dll_fll_pll_tracking_cc.h"
#include "gps_sdr_signal_processing.h"
#include "GPS_L1_CA.h"
#include "tracking_discriminators.h"
@ -234,13 +233,13 @@ void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << d_acquisition_gnss_synchro->System << " "<< d_acquisition_gnss_synchro->PRN << " received ";
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking Gnss_Satellite(systemName[&d_acquisition_gnss_synchro->System], d_acquisition_gnss_synchro->PRN)
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]= " << d_carrier_doppler_hz
LOG(INFO) << "PULL-IN Doppler [Hz]= " << d_carrier_doppler_hz
<< " Code Phase correction [samples]=" << delay_correction_samples
<< " PULL-IN Code Phase [samples]= " << d_acq_code_phase_samples << std::endl;
}
@ -251,11 +250,11 @@ void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::start_tracking()
void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::update_local_code()
{
double tcode_chips;
double rem_code_phase_chips;
double code_phase_step_chips;
int early_late_spc_samples;
int epl_loop_length_samples;
double tcode_chips;
double rem_code_phase_chips;
double code_phase_step_chips;
int early_late_spc_samples;
int epl_loop_length_samples;
int associated_chip_index;
int code_length_chips = (int)GPS_L1_CA_CODE_LENGTH_CHIPS;
@ -267,25 +266,25 @@ void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::update_local_code()
early_late_spc_samples = round(d_early_late_spc_chips/code_phase_step_chips);
epl_loop_length_samples = d_current_prn_length_samples + early_late_spc_samples*2;
for (int i = 0; i < epl_loop_length_samples; i++)
{
associated_chip_index = 1 + round(fmod(tcode_chips - d_early_late_spc_chips, code_length_chips));
d_early_code[i] = d_ca_code[associated_chip_index];
tcode_chips = tcode_chips + code_phase_step_chips;
}
{
associated_chip_index = 1 + round(fmod(tcode_chips - d_early_late_spc_chips, code_length_chips));
d_early_code[i] = d_ca_code[associated_chip_index];
tcode_chips = tcode_chips + code_phase_step_chips;
}
memcpy(d_prompt_code,&d_early_code[early_late_spc_samples],d_current_prn_length_samples* sizeof(gr_complex));
memcpy(d_late_code,&d_early_code[early_late_spc_samples*2],d_current_prn_length_samples* sizeof(gr_complex));
// for (int i=0; i<d_current_prn_length_samples; i++)
// {
// associated_chip_index = 1 + round(fmod(tcode_chips - d_early_late_spc_chips, code_length_chips));
// d_early_code[i] = d_ca_code[associated_chip_index];
// associated_chip_index = 1 + round(fmod(tcode_chips, code_length_chips));
// d_prompt_code[i] = d_ca_code[associated_chip_index];
// associated_chip_index = 1 + round(fmod(tcode_chips + d_early_late_spc_chips, code_length_chips));
// d_late_code[i] = d_ca_code[associated_chip_index];
// tcode_chips = tcode_chips + code_phase_step_chips;
// }
// for (int i=0; i<d_current_prn_length_samples; i++)
// {
// associated_chip_index = 1 + round(fmod(tcode_chips - d_early_late_spc_chips, code_length_chips));
// d_early_code[i] = d_ca_code[associated_chip_index];
// associated_chip_index = 1 + round(fmod(tcode_chips, code_length_chips));
// d_prompt_code[i] = d_ca_code[associated_chip_index];
// associated_chip_index = 1 + round(fmod(tcode_chips + d_early_late_spc_chips, code_length_chips));
// d_late_code[i] = d_ca_code[associated_chip_index];
// tcode_chips = tcode_chips + code_phase_step_chips;
// }
}
@ -395,7 +394,7 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
{
const int samples_available = ninput_items[0];
d_sample_counter = d_sample_counter + samples_available;
LOG_AT_LEVEL(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
LOG(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
consume_each(samples_available);
// make an output to not stop the rest of the processing blocks
@ -473,7 +472,8 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr())
{
@ -496,7 +496,7 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
{
d_last_seg = floor(d_sample_counter/d_fs_in);
std::cout << "Current input signal time = " << d_last_seg << " [s]" << std::endl;
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
else
@ -504,7 +504,7 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
if (floor(d_sample_counter/d_fs_in) != d_last_seg)
{
d_last_seg = floor(d_sample_counter/d_fs_in);
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
@ -608,7 +608,7 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing trk dump file "<< e.what() << std::endl;
LOG(INFO) << "Exception writing trk dump file "<< e.what() << std::endl;
}
}
consume_each(d_current_prn_length_samples); // this is necessary in gr::block derivates
@ -620,7 +620,7 @@ int Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::general_work (int noutput_items, gr_vecto
void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
DLOG(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -632,11 +632,11 @@ void Gps_L1_Ca_Dll_Fll_Pll_Tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions ( std::ifstream::failbit | std::ifstream::badbit );
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -11,7 +11,7 @@
*
* -------------------------------------------------------------------------
*
* 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
@ -34,20 +34,20 @@
* -------------------------------------------------------------------------
*/
#include "gnss_synchro.h"
#include "gps_l1_ca_dll_pll_optim_tracking_cc.h"
#include <iostream>
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "gps_sdr_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
#include "GPS_L1_CA.h"
#include "nco_lib.h"
#include "control_message_factory.h"
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <sstream>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
/*!
@ -182,7 +182,7 @@ void Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::start_tracking()
unsigned long int acq_trk_diff_samples;
float acq_trk_diff_seconds;
acq_trk_diff_samples = d_sample_counter - d_acq_sample_stamp; //-d_vector_length;
std::cout << "acq_trk_diff_samples=" << acq_trk_diff_samples << std::endl;
LOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = (float)acq_trk_diff_samples / (float)d_fs_in;
//doppler effect
// Fd=(C/(C+Vr))*F
@ -263,13 +263,13 @@ void Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " received";
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " Code Phase correction [samples]=" << delay_correction_samples
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples << std::endl;
}
@ -450,7 +450,8 @@ int Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::general_work (int noutput_items, gr_vec
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr())
{
@ -484,13 +485,14 @@ int Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::general_work (int noutput_items, gr_vec
if (d_channel == 0)
{
// debug: Second counter in channel 0
tmp_str_stream << "Current input signal time = " << d_last_seg << " [s]" << std::endl << std::flush;
std::cout << tmp_str_stream.rdbuf() << std::flush;
tmp_str_stream << "Current input signal time = " << d_last_seg << " [s]" << std::endl;
std::cout << tmp_str_stream.rdbuf();
LOG(INFO) << tmp_str_stream.rdbuf();
}
tmp_str_stream << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", Doppler=" << d_carrier_doppler_hz << " [Hz] CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
std::cout << tmp_str_stream.rdbuf() << std::flush;
//std::cout << tmp_str_stream.rdbuf() << std::flush;
LOG(INFO) << tmp_str_stream.rdbuf();
//if (d_channel == 0 || d_last_seg==5) d_carrier_lock_fail_counter=500; //DEBUG: force unlock!
}
@ -557,7 +559,7 @@ int Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::general_work (int noutput_items, gr_vec
}
catch (std::ifstream::failure& e)
{
std::cout << "Exception writing trk dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing trk dump file " << e.what();
}
}
@ -571,7 +573,7 @@ int Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::general_work (int noutput_items, gr_vec
void Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
LOG_AT_LEVEL(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -583,11 +585,11 @@ void Gps_L1_Ca_Dll_Pll_Optim_Tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure& e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -7,11 +7,11 @@
* Code DLL + carrier PLL according to the algorithms described in:
* [1] K.Borre, D.M.Akos, N.Bertelsen, P.Rinder, and S.H.Jensen,
* A Software-Defined GPS and Galileo Receiver. A Single-Frequency
* Approach, Birkha user, 2007
* Approach, Birkhauser, 2007
*
* -------------------------------------------------------------------------
*
* Copyright (C) 2010-2011 (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
@ -34,20 +34,20 @@
* -------------------------------------------------------------------------
*/
#include "gnss_synchro.h"
#include "gps_l1_ca_dll_pll_tracking_cc.h"
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "gps_sdr_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
#include "GPS_L1_CA.h"
#include "control_message_factory.h"
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <sstream>
#include <cmath>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
/*!
* \todo Include in definition header file
@ -181,7 +181,7 @@ void Gps_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
unsigned long int acq_trk_diff_samples;
float acq_trk_diff_seconds;
acq_trk_diff_samples = d_sample_counter - d_acq_sample_stamp;//-d_vector_length;
std::cout << "acq_trk_diff_samples=" << acq_trk_diff_samples << std::endl;
LOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = (float)acq_trk_diff_samples / (float)d_fs_in;
//doppler effect
// Fd=(C/(C+Vr))*F
@ -238,15 +238,16 @@ void Gps_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " received";
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " Code Phase correction [samples]=" << delay_correction_samples
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples << std::endl;
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
}
@ -380,7 +381,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
{
const int samples_available = ninput_items[0];
d_sample_counter = d_sample_counter + samples_available;
LOG_AT_LEVEL(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
LOG(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
consume_each(samples_available);
// make an output to not stop the rest of the processing blocks
@ -461,7 +462,8 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl ;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr())
{
@ -495,8 +497,8 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Current input signal time = " << d_last_seg << " [s]" << std::endl;
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
//if (d_last_seg==5) d_carrier_lock_fail_counter=500; //DEBUG: force unlock!
}
}
@ -505,8 +507,8 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
if (floor(d_sample_counter / d_fs_in) != d_last_seg)
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
//std::cout<<"TRK CH "<<d_channel<<" Carrier_lock_test="<<d_carrier_lock_test<< std::endl;
}
}
@ -573,7 +575,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing trk dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing trk dump file " << e.what();
}
}
@ -587,7 +589,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_cc::general_work (int noutput_items, gr_vector_in
void Gps_L1_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
LOG_AT_LEVEL(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -599,11 +601,11 @@ void Gps_L1_Ca_Dll_Pll_Tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
}
}
}

View File

@ -12,7 +12,7 @@
*
* -------------------------------------------------------------------------
*
* 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,22 +35,21 @@
* -------------------------------------------------------------------------
*/
#include "gnss_synchro.h"
#include "gps_l1_ca_tcp_connector_tracking_cc.h"
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/asio.hpp>
#include <boost/lexical_cast.hpp>
#include <gnuradio/io_signature.h>
#include <glog/logging.h>
#include "gnss_synchro.h"
#include "gps_sdr_signal_processing.h"
#include "tracking_discriminators.h"
#include "lock_detectors.h"
#include "GPS_L1_CA.h"
#include "control_message_factory.h"
#include "tcp_communication.h"
#include <boost/lexical_cast.hpp>
#include <iostream>
#include <sstream>
#include <cmath>
#include <gnuradio/io_signature.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <boost/asio.hpp>
#include "tcp_packet_data.h"
/*!
@ -119,11 +118,11 @@ Gps_L1_Ca_Tcp_Connector_Tracking_cc::Gps_L1_Ca_Tcp_Connector_Tracking_cc(
//--- DLL variables --------------------------------------------------------
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
//--- TCP CONNECTOR variables --------------------------------------------------------
d_port_ch0 = port_ch0;
d_port = 0;
d_listen_connection = true;
d_control_id = 0;
//--- TCP CONNECTOR variables --------------------------------------------------------
d_port_ch0 = port_ch0;
d_port = 0;
d_listen_connection = true;
d_control_id = 0;
// Initialization of local code replica
// Get space for a vector with the C/A code replica sampled 1x/chip
@ -179,7 +178,6 @@ Gps_L1_Ca_Tcp_Connector_Tracking_cc::Gps_L1_Ca_Tcp_Connector_Tracking_cc(
systemName["S"] = std::string("SBAS");
systemName["E"] = std::string("Galileo");
systemName["C"] = std::string("Compass");
}
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
@ -261,15 +259,15 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
// DEBUG OUTPUT
std::cout << "Tracking start on channel " << d_channel << " for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << std::endl;
DLOG(INFO) << "Start tracking for satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " received" << std::endl;
LOG(INFO) << "Starting tracking of satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN) << " on channel " << d_channel;
// enable tracking
d_pull_in = true;
d_enable_tracking = true;
std::cout << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
LOG(INFO) << "PULL-IN Doppler [Hz]=" << d_carrier_doppler_hz
<< " Code Phase correction [samples]=" << delay_correction_samples
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples << std::endl;
<< " PULL-IN Code Phase [samples]=" << d_acq_code_phase_samples;
}
@ -278,7 +276,6 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::update_local_code()
{
double tcode_chips;
double rem_code_phase_chips;
int associated_chip_index;
@ -415,7 +412,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
{
const int samples_available = ninput_items[0];
d_sample_counter = d_sample_counter + samples_available;
LOG_AT_LEVEL(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
LOG(WARNING) << "Detected NaN samples at sample number " << d_sample_counter;
consume_each(samples_available);
// make an output to not stop the rest of the processing blocks
@ -510,7 +507,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
}
if (d_carrier_lock_fail_counter > MAXIMUM_LOCK_FAIL_COUNTER)
{
std::cout << "Channel " << d_channel << " loss of lock!" << std::endl ;
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
ControlMessageFactory* cmf = new ControlMessageFactory();
if (d_queue != gr::msg_queue::sptr()) {
d_queue->handle(cmf->GetQueueMessage(d_channel, 2));
@ -544,8 +542,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Current input signal time = " << d_last_seg << " [s]" << std::endl;
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
else
@ -553,8 +551,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
if (floor(d_sample_counter / d_fs_in) != d_last_seg)
{
d_last_seg = floor(d_sample_counter / d_fs_in);
std::cout << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]" << std::endl;
LOG(INFO) << "Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN)
<< ", CN0 = " << d_CN0_SNV_dB_Hz << " [dB-Hz]";
}
}
}
@ -622,7 +620,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
}
catch (std::ifstream::failure e)
{
std::cout << "Exception writing trk dump file " << e.what() << std::endl;
LOG(WARNING) << "Exception writing trk dump file " << e.what();
}
}
@ -637,7 +635,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work (int noutput_items, gr_vec
void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
{
d_channel = channel;
LOG_AT_LEVEL(INFO) << "Tracking Channel set to " << d_channel;
LOG(INFO) << "Tracking Channel set to " << d_channel;
// ############# ENABLE DATA FILE LOG #################
if (d_dump == true)
{
@ -649,11 +647,11 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::set_channel(unsigned int channel)
d_dump_filename.append(".dat");
d_dump_file.exceptions (std::ifstream::failbit | std::ifstream::badbit);
d_dump_file.open(d_dump_filename.c_str(), std::ios::out | std::ios::binary);
std::cout << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str() << std::endl;
LOG(INFO) << "Tracking dump enabled on channel " << d_channel << " Log file: " << d_dump_filename.c_str();
}
catch (std::ifstream::failure e)
{
std::cout << "channel " << d_channel << " Exception opening trk dump file " << e.what() << std::endl;
LOG(WARNING) << "channel " << d_channel << " Exception opening trk dump file " << e.what();
}
}
}

View File

@ -355,7 +355,7 @@ bool gnss_sdr_supl_client::load_ephemeris_xml(const std::string file_name)
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << e.what() << "File: " << file_name;
LOG(ERROR) << e.what() << "File: " << file_name;
return false;
}
return true;
@ -373,7 +373,7 @@ bool gnss_sdr_supl_client::save_ephemeris_xml(const std::string file_name)
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << e.what();
LOG(ERROR) << e.what();
return false;
}
return true;

View File

@ -41,7 +41,6 @@
#include <boost/archive/xml_oarchive.hpp>
#include <boost/archive/xml_iarchive.hpp>
#include <boost/serialization/map.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
extern "C" {
#include "supl.h"

View File

@ -5,7 +5,7 @@
*
* -------------------------------------------------------------------------
*
* 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
@ -29,10 +29,8 @@
*/
#include "control_message_factory.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <vector>
#include "string.h"
using google::LogMessage;
@ -40,34 +38,33 @@ using google::LogMessage;
ControlMessageFactory::ControlMessageFactory()
{}
// Destructor
ControlMessageFactory::~ControlMessageFactory()
{}
boost::shared_ptr<gr::message> ControlMessageFactory::GetQueueMessage(unsigned int who, unsigned int what)
{
ControlMessage *control_message = new ControlMessage;
control_message->who = who;
control_message->what = what;
boost::shared_ptr<gr::message> queue_message = gr::message::make(0, 0, 0, sizeof(ControlMessage));
memcpy(queue_message->msg(), control_message, sizeof(ControlMessage));
delete control_message;
return queue_message;
}
std::vector<ControlMessage*>* ControlMessageFactory::GetControlMessages(boost::shared_ptr<gr::message> queue_message)
{
std::vector<ControlMessage*>* control_messages = new std::vector<ControlMessage*>();
unsigned int control_messages_count = queue_message->length() / sizeof(ControlMessage);
if(queue_message->length() % sizeof(ControlMessage) != 0)
{
LOG_AT_LEVEL(WARNING) << "Queue message has size " << queue_message->length() << " which is not" <<
" multiple of control message size " << sizeof(ControlMessage);
LOG_AT_LEVEL(WARNING) << "Ignoring this queue message to prevent unexpected results.";
LOG(WARNING) << "Queue message has size " << queue_message->length() << ", which is not"
<< " multiple of control message size " << sizeof(ControlMessage);
LOG(WARNING) << "Ignoring this queue message to prevent unexpected results.";
return control_messages;
}
for(unsigned int i=0; i<control_messages_count; i++)

View File

@ -34,14 +34,13 @@
#include "control_thread.h"
#include <unistd.h>
#include <iostream>
#include <map>
#include <string>
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <boost/thread/thread.hpp>
#include <gnuradio/message.h>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "gps_ephemeris.h"
#include "gps_iono.h"
@ -135,22 +134,22 @@ void ControlThread::run()
flowgraph_->connect();
if (flowgraph_->connected())
{
LOG_AT_LEVEL(INFO) << "Flowgraph connected";
LOG(INFO) << "Flowgraph connected";
}
else
{
LOG_AT_LEVEL(ERROR) << "Unable to connect flowgraph";
LOG(ERROR) << "Unable to connect flowgraph";
return;
}
// Start the flowgraph
flowgraph_->start();
if (flowgraph_->running())
{
LOG_AT_LEVEL(INFO) << "Flowgraph started";
LOG(INFO) << "Flowgraph started";
}
else
{
LOG_AT_LEVEL(ERROR) << "Unable to start flowgraph";
LOG(ERROR) << "Unable to start flowgraph";
return;
}
// start the keyboard_listener thread
@ -188,7 +187,7 @@ void ControlThread::run()
//Join keyboard threads
keyboard_thread_.timed_join(boost::posix_time::seconds(1));
LOG_AT_LEVEL(INFO) << "Flowgraph stopped";
LOG(INFO) << "Flowgraph stopped";
}
@ -197,7 +196,7 @@ void ControlThread::set_control_queue(boost::shared_ptr<gr::msg_queue> control_q
{
if (flowgraph_->running())
{
LOG_AT_LEVEL(WARNING) << "Unable to set control queue while flowgraph is running";
LOG(WARNING) << "Unable to set control queue while flowgraph is running";
return;
}
control_queue_ = control_queue;
@ -728,7 +727,7 @@ void ControlThread::gps_ephemeris_data_write_to_XML()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << e.what();
LOG(ERROR) << e.what();
}
}
}
@ -754,7 +753,7 @@ void ControlThread::gps_utc_model_data_write_to_XML()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << e.what();
LOG(ERROR) << e.what();
}
}
}
@ -782,7 +781,7 @@ void ControlThread::gps_iono_data_write_to_XML()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << e.what();
LOG(ERROR) << e.what();
}
}
}

View File

@ -35,7 +35,6 @@
#include "file_configuration.h"
#include <string>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "INIReader.h"
#include "string_converter.h"
@ -59,7 +58,7 @@ FileConfiguration::FileConfiguration()
FileConfiguration::~FileConfiguration()
{
LOG_AT_LEVEL(INFO) << "Destructor called";
LOG(INFO) << "Destructor called";
delete ini_reader_;
delete converter_;
delete overrided_;
@ -186,11 +185,11 @@ void FileConfiguration::init()
}
else if(error_ > 0)
{
LOG_AT_LEVEL(WARNING) << "Configuration file " << filename_ << " contains errors in line " << error_;
LOG(WARNING) << "Configuration file " << filename_ << " contains errors in line " << error_;
}
else
{
LOG_AT_LEVEL(WARNING) << "Unable to open configuration file " << filename_;
LOG(WARNING) << "Unable to open configuration file " << filename_;
}
}

View File

@ -10,7 +10,7 @@
*
* -------------------------------------------------------------------------
*
* 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
@ -38,7 +38,6 @@
#include <sstream>
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "configuration_interface.h"
#include "gnss_block_interface.h"
@ -112,8 +111,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetSignalSource(
std::string default_implementation = "File_Signal_Source";
std::string implementation = configuration->property(
"SignalSource.implementation", default_implementation);
DLOG(INFO) << "Getting SignalSource with implementation "
<< implementation;
LOG(INFO) << "Getting SignalSource with implementation " << implementation;
return GetBlock(configuration, "SignalSource", implementation, 0, 1,
queue);
}
@ -145,28 +143,29 @@ GNSSBlockInterface* GNSSBlockFactory::GetSignalConditioner(
"Resampler.implementation", default_implementation);
}
DLOG(INFO) << "Getting SignalConditioner with DataTypeAdapter implementation: "
LOG(INFO) << "Getting SignalConditioner with DataTypeAdapter implementation: "
<< data_type_adapter << ", InputFilter implementation: "
<< input_filter << ", and Resampler implementation: "
<< resampler;
if(signal_conditioner.compare("Array_Signal_Conditioner") == 0)
{
//instantiate the array version
return new ArraySignalConditioner(configuration, 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);
}else{
//normal version
return new SignalConditioner(configuration, 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);
}
{
//instantiate the array version
return new ArraySignalConditioner(configuration, 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);
}
else
{
//normal version
return new SignalConditioner(configuration, 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);
}
}
@ -175,15 +174,10 @@ GNSSBlockInterface* GNSSBlockFactory::GetObservables(
ConfigurationInterface *configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "GPS_L1_CA_Observables";
std::string implementation = configuration->property(
"Observables.implementation", default_implementation);
DLOG(INFO) << "Getting Observables with implementation "
<< implementation;
unsigned int channel_count =
configuration->property("Channels.count", 12);
return GetBlock(configuration, "Observables", implementation,
channel_count, channel_count, queue);
std::string implementation = configuration->property("Observables.implementation", default_implementation);
LOG(INFO) << "Getting Observables with implementation " << implementation;
unsigned int channel_count = configuration->property("Channels.count", 12);
return GetBlock(configuration, "Observables", implementation, channel_count, channel_count, queue);
}
@ -192,12 +186,10 @@ GNSSBlockInterface* GNSSBlockFactory::GetPVT(
ConfigurationInterface *configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Pass_Through";
std::string implementation = configuration->property(
"PVT.implementation", default_implementation);
DLOG(INFO) << "Getting PVT with implementation " << implementation;
std::string implementation = configuration->property("PVT.implementation", default_implementation);
LOG(INFO) << "Getting PVT with implementation " << implementation;
unsigned int channel_count = configuration->property("Channels.count", 12);
return GetBlock(configuration, "PVT", implementation, channel_count, 1,
queue);
return GetBlock(configuration, "PVT", implementation, channel_count, 1, queue);
}
@ -206,11 +198,9 @@ GNSSBlockInterface* GNSSBlockFactory::GetOutputFilter(
ConfigurationInterface *configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Null_Sink_Output_Filter";
std::string implementation = configuration->property(
"OutputFilter.implementation", default_implementation);
DLOG(INFO) << "Getting OutputFilter with implementation " << implementation;
return GetBlock(configuration, "OutputFilter", implementation, 1, 0,
queue);
std::string implementation = configuration->property("OutputFilter.implementation", default_implementation);
LOG(INFO) << "Getting OutputFilter with implementation " << implementation;
return GetBlock(configuration, "OutputFilter", implementation, 1, 0, queue);
}
@ -222,10 +212,8 @@ GNSSBlockInterface* GNSSBlockFactory::GetChannel(
std::stringstream stream;
stream << channel;
std::string id = stream.str();
DLOG(INFO) << "Instantiating channel " << id;
DLOG(INFO) << "Getting Channel " << id << " with" << std::endl << " Acquisition Implementation: "
<< acq << std::endl << " Tracking Implementation: " << trk << std::endl << " Telemetry "
"Decoder implementation: " << tlm;
LOG(INFO) << "Instantiating Channel " << id << " with Acquisition Implementation: "
<< acq << ", Tracking Implementation: " << trk << ", Telemetry Decoder implementation: " << tlm;
return new Channel(configuration, channel, GetBlock(configuration,
"Channel", "Pass_Through", 1, 1, queue),
@ -243,17 +231,12 @@ std::vector<GNSSBlockInterface*>* GNSSBlockFactory::GetChannels(
ConfigurationInterface *configuration, boost::shared_ptr<gr::msg_queue> queue)
{
std::string default_implementation = "Pass_Through";
unsigned int channel_count =
configuration->property("Channels.count", 12);
DLOG(INFO) << "Getting " << channel_count << " channels";
std::vector<GNSSBlockInterface*>* channels = new std::vector<
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);
unsigned int channel_count = configuration->property("Channels.count", 12);
LOG(INFO) << "Getting " << channel_count << " channels";
std::vector<GNSSBlockInterface*>* channels = new std::vector<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);
for (unsigned int i = 0; i < channel_count; i++)
{
@ -272,11 +255,11 @@ std::vector<GNSSBlockInterface*>* GNSSBlockFactory::GetChannels(
}
/*
* Returns the block with the required configuration and implementation
*
* PLEASE ADD YOUR NEW BLOCK HERE!!
*/
/*
* Returns the block with the required configuration and implementation
*
* PLEASE ADD YOUR NEW BLOCK HERE!!
*/
GNSSBlockInterface* GNSSBlockFactory::GetBlock(
ConfigurationInterface *configuration, std::string role,
std::string implementation, unsigned int in_streams,
@ -301,8 +284,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
catch (const std::exception &e)
{
std::cout << "GNSS-SDR program ended." << std::endl;
LOG_AT_LEVEL(INFO) << implementation
<< ": Source file not found";
LOG(ERROR) << implementation << ": Source file not found";
exit(1);
}
}
@ -316,8 +298,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
catch (const std::exception &e)
{
std::cout << "GNSS-SDR program ended." << std::endl;
LOG_AT_LEVEL(INFO) << implementation
<< ": Source file not found";
LOG(ERROR) << implementation << ": Source file not found";
exit(1);
}
}
@ -524,8 +505,7 @@ GNSSBlockInterface* GNSSBlockFactory::GetBlock(
else
{
// Log fatal. This causes execution to stop.
LOG_AT_LEVEL(ERROR) << implementation
<< ": Undefined implementation for block";
LOG(ERROR) << implementation << ": Undefined implementation for block";
}
return block;
}

View File

@ -8,7 +8,7 @@
*
* -------------------------------------------------------------------------
*
* 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
@ -32,13 +32,12 @@
*/
#include "gnss_flowgraph.h"
#include <exception>
#include "unistd.h"
#include <exception>
#include <iostream>
#include <boost/lexical_cast.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <set>
#include <boost/lexical_cast.hpp>
#include <glog/logging.h>
#include "configuration_interface.h"
#include "gnss_block_interface.h"
#include "channel_interface.h"
@ -79,7 +78,7 @@ void GNSSFlowgraph::start()
{
if (running_)
{
LOG_AT_LEVEL(WARNING) << "Already running";
LOG(WARNING) << "Already running";
return;
}
@ -89,8 +88,8 @@ void GNSSFlowgraph::start()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Unable to start flowgraph";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Unable to start flowgraph";
LOG(ERROR) << e.what();
return;
}
@ -108,10 +107,9 @@ void GNSSFlowgraph::stop()
}
for (unsigned int i = 0; i < channels_count_; i++)
{
std::cout << "Channel " << i << " in state " << channels_state_[i]
<< std::endl;
LOG(INFO) << "Channel " << i << " in state " << channels_state_[i] << std::endl;
}
DLOG(INFO) << "Threads finished. Return to main program.";
LOG(INFO) << "Threads finished. Return to main program.";
top_block_->stop();
running_ = false;
}
@ -124,10 +122,10 @@ void GNSSFlowgraph::connect()
*
* Signal Source > Signal conditioner >> Channels >> Observables >> PVT > Output filter
*/
DLOG(INFO) << "Connecting flowgraph";
LOG(INFO) << "Connecting flowgraph";
if (connected_)
{
LOG_AT_LEVEL(WARNING) << "flowgraph already connected";
LOG(WARNING) << "flowgraph already connected";
return;
}
@ -137,8 +135,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect signal source block internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(INFO) << "Can't connect signal source block internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -150,9 +148,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR)
<< "Can't connect signal conditioner block internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect signal conditioner block internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -165,9 +162,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect channel " << i
<< " internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect channel " << i << " internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -179,8 +175,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect observables block internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect observables block internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -192,8 +188,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect PVT block internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect PVT block internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -205,8 +201,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect output filter block internally";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect output filter block internally";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -218,29 +214,28 @@ void GNSSFlowgraph::connect()
try
{
if(signal_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);
}
}else{
//single channel
std::cout<<"NORMAL MODE"<<std::endl;
top_block_->connect(signal_source()->get_right_block(), 0,
signal_conditioner()->get_left_block(), 0);
}
if(signal_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);
}
}
else
{
//single channel
// std::cout<<"NORMAL MODE"<<std::endl;
top_block_->connect(signal_source()->get_right_block(), 0, signal_conditioner()->get_left_block(), 0);
}
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR)
<< "Can't connect signal source to signal conditioner";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect signal source to signal conditioner";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -256,9 +251,8 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR)
<< "Can't connect signal conditioner to channel " << i;
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect signal conditioner to channel " << i;
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
@ -273,28 +267,26 @@ void GNSSFlowgraph::connect()
}
catch (std::exception& e)
{
LOG_AT_LEVEL(ERROR) << "Can't connect channel " << i
<< " to observables";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect channel " << i << " to observables";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
channel(i)->set_signal(available_GNSS_signals_.front());
std::cout << "Channel " << i << " assigned to "
<< available_GNSS_signals_.front() << std::endl;
LOG(INFO) << "Channel " << i << " assigned to " << available_GNSS_signals_.front();
available_GNSS_signals_.pop_front();
channel(i)->start();
if (channels_state_[i] == 1)
{
channel(i)->start_acquisition();
DLOG(INFO) << "Channel " << i
<< " connected to observables and ready for acquisition";
LOG(INFO) << "Channel " << i
<< " connected to observables and ready for acquisition";
}
else
{
DLOG(INFO) << "Channel " << i
<< " connected to observables in standby mode";
LOG(INFO) << "Channel " << i
<< " connected to observables in standby mode";
}
}
@ -305,34 +297,32 @@ 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)
{
LOG_AT_LEVEL(ERROR) << "Can't connect observables to PVT";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect observables to PVT";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
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)
{
LOG_AT_LEVEL(ERROR) << "Can't connect PVT to output filter";
LOG_AT_LEVEL(ERROR) << e.what();
LOG(WARNING) << "Can't connect PVT to output filter";
LOG(ERROR) << e.what();
top_block_->disconnect_all();
return;
}
DLOG(INFO) << "PVT connected to output filter";
connected_ = true;
DLOG(INFO) << "Flowgraph connected";
LOG(INFO) << "Flowgraph connected";
top_block_->dump();
}
@ -343,7 +333,7 @@ void GNSSFlowgraph::wait()
{
if (!running_)
{
LOG_AT_LEVEL(WARNING) << "Can't apply wait. Flowgraph is not running";
LOG(WARNING) << "Can't apply wait. Flowgraph is not running";
return;
}
top_block_->wait();
@ -363,20 +353,19 @@ void GNSSFlowgraph::wait()
*/
void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
{
DLOG(INFO) << "received " << what << " from " << who;
LOG(INFO) << "received " << what << " from " << who;
switch (what)
{
case 0:
DLOG(INFO) << "Channel " << who << " ACQ FAILED satellite "
<< channel(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " ACQ FAILED satellite " << channel(who)->get_signal().get_satellite();
available_GNSS_signals_.push_back(channel(who)->get_signal());
while (channel(who)->get_signal().get_satellite().get_system() != available_GNSS_signals_.front().get_satellite().get_system()){
while (channel(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());
available_GNSS_signals_.pop_front();
channel(who)->start_acquisition();
@ -385,9 +374,7 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
// TODO: Tracking messages
case 1:
DLOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite "
<< channel(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " ACQ SUCCESS satellite " << channel(who)->get_signal().get_satellite();
channels_state_[who] = 2;
acq_channels_count_--;
if (acq_channels_count_ < max_acq_channels_)
@ -406,16 +393,12 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
for (unsigned int i = 0; i < channels_count_; i++)
{
std::cout << "Channel " << i << " in state " << channels_state_[i]
<< std::endl;
LOG(INFO) << "Channel " << i << " in state " << channels_state_[i] << std::endl;
}
break;
case 2:
DLOG(INFO) << "Channel " << who << " TRK FAILED satellite "
<< channel(who)->get_signal().get_satellite();
LOG(INFO) << "Channel " << who << " TRK FAILED satellite " << channel(who)->get_signal().get_satellite();
if (acq_channels_count_ < max_acq_channels_)
{
channels_state_[who] = 1;
@ -430,16 +413,14 @@ void GNSSFlowgraph::apply_action(unsigned int who, unsigned int what)
for (unsigned int i = 0; i < channels_count_; i++)
{
std::cout << "Channel " << i << " in state " << channels_state_[i]
<< std::endl;
LOG(INFO) << "Channel " << i << " in state " << channels_state_[i] << std::endl;
}
break;
default:
break;
}
DLOG(INFO) << "Number of available satellites: "
<< available_GNSS_signals_.size();
LOG(INFO) << "Number of available satellites: " << available_GNSS_signals_.size();
}
@ -448,15 +429,13 @@ void GNSSFlowgraph::set_configuration(ConfigurationInterface* configuration)
{
if (running_)
{
LOG_AT_LEVEL(WARNING)
<< "Unable to update configuration while flowgraph running";
LOG(WARNING) << "Unable to update configuration while flowgraph running";
return;
}
if (connected_)
{
LOG_AT_LEVEL(WARNING)
<< "Unable to update configuration while flowgraph connected";
LOG(WARNING) << "Unable to update configuration while flowgraph connected";
}
configuration_ = configuration;
}
@ -511,14 +490,12 @@ 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_->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::vector<GNSSBlockInterface*>* channels = block_factory_->GetChannels(
configuration_, queue_);
std::vector<GNSSBlockInterface*>* channels = block_factory_->GetChannels(configuration_, queue_);
channels_count_ = channels->size();
@ -558,15 +535,15 @@ 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"));
std::string default_system = configuration_->property("Channel.system", std::string("GPS"));
std::string default_signal = configuration_->property("Channel.signal", std::string("1C"));
/*
* 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)
if (default_system.compare(std::string("GPS")) == 0)
{
/*
* Loop to create GPS L1 C/A signals
@ -575,32 +552,34 @@ void GNSSFlowgraph::set_signals_list()
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)
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};
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)
if (default_system.compare(std::string("Galileo")) == 0)
{
/*
* Loop to create the list of Galileo E1 B signals
@ -609,11 +588,12 @@ void GNSSFlowgraph::set_signals_list()
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++)
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")));
available_GNSS_signals_.push_back(Gnss_Signal(Gnss_Satellite(std::string("Galileo"),
*available_gnss_prn_iter), std::string("1B")));
}
}
@ -628,12 +608,12 @@ void GNSSFlowgraph::set_signals_list()
std::string gnss_system = (configuration_->property("Channel"
+ boost::lexical_cast<std::string>(i) + ".system",
default_system));
DLOG(INFO) << "Channel " << i << " system " << gnss_system;
LOG(INFO) << "Channel " << i << " system " << gnss_system;
std::string gnss_signal = (configuration_->property("Channel"
+ boost::lexical_cast<std::string>(i) + ".signal",
default_signal));
DLOG(INFO) << "Channel " << i << " signal " << gnss_signal;
LOG(INFO) << "Channel " << i << " signal " << gnss_signal;
unsigned int sat = configuration_->property("Channel"
+ boost::lexical_cast<std::string>(i) + ".satellite", 0);
@ -644,8 +624,7 @@ void GNSSFlowgraph::set_signals_list()
}
else
{
Gnss_Signal signal_value = Gnss_Signal(Gnss_Satellite(gnss_system, sat),
gnss_signal);
Gnss_Signal signal_value = Gnss_Signal(Gnss_Satellite(gnss_system, sat), gnss_signal);
DLOG(INFO) << "Channel " << i << " " << signal_value;
available_GNSS_signals_.remove(signal_value);
available_GNSS_signals_.insert(gnss_it, signal_value);
@ -667,34 +646,27 @@ void GNSSFlowgraph::set_signals_list()
void GNSSFlowgraph::set_channels_state()
{
max_acq_channels_ = (configuration_->property("Channels.in_acquisition",
channels_count_));
max_acq_channels_ = (configuration_->property("Channels.in_acquisition", channels_count_));
if (max_acq_channels_ > channels_count_)
{
max_acq_channels_ = channels_count_;
std::cout
<< "Channels_in_acquisition is bigger than number of channels. Variable acq_channels_count_ is set to "
<< channels_count_ << std::endl;
LOG(WARNING) << "Channels_in_acquisition is bigger than number of channels. Variable acq_channels_count_ is set to "
<< channels_count_;
}
channels_state_.reserve(channels_count_);
for (unsigned int i = 0; i < channels_count_; i++)
{
if (i < max_acq_channels_)
{
channels_state_.push_back(1);
} else
channels_state_.push_back(0);
}
else
channels_state_.push_back(0);
}
acq_channels_count_ = max_acq_channels_;
DLOG(INFO) << acq_channels_count_ << " channels in acquisition state";
for (unsigned int i = 0; i < channels_count_; i++)
{
std::cout << "Channel " << i << " in state " << channels_state_[i]
<< std::endl;
LOG(INFO) << "Channel " << i << " in state " << channels_state_[i];
}
}

View File

@ -34,7 +34,6 @@
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/crc.hpp> // for boost::crc_basic, boost::crc_optimal
#include <boost/dynamic_bitset.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <iostream>
#include <cstring>
@ -656,7 +655,7 @@ int Galileo_Navigation_Message::page_jk_decoder(const char *data_jk)
//DLOG(INFO) << "Data_jk_bits (bitset) "<< endl << data_jk_bits << endl;
page_number = (int)read_navigation_unsigned(data_jk_bits, PAGE_TYPE_bit);
DLOG(INFO) << "Page number = " << page_number;
LOG(INFO) << "Page number = " << page_number;
switch (page_number)
{

View File

@ -54,49 +54,49 @@ double Galileo_Utc_Model::GST_to_UTC_time(double t_e, int WN)
int weeksToLeapSecondEvent = WN_LSF_6 - (WN % 256);
if ((weeksToLeapSecondEvent) >= 0) // is not in the past
{
//Detect if the effectivity time and user's time is within six hours = 6 * 60 *60 = 21600 s
int secondOfLeapSecondEvent = DN_6 * 24 * 60 * 60;
if (abs(t_e - secondOfLeapSecondEvent) > 21600)
{
/* 5.1.7a
* Whenever the leap second adjusted time indicated by the WN_LSF and the DN values
* is not in the past (relative to the user's present time), and the user's
* present time does not fall in the time span which starts at six hours prior
* to the effective time and ends at six hours after the effective time,
* the GST/Utc relationship is given by
*/
//std::cout<<"GST->UTC case a"<<std::endl;
Delta_t_Utc = Delta_tLS_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
t_Utc_daytime = fmod(t_e - Delta_t_Utc, 86400);
}
else
{
/* 5.1.7b
* Whenever the user's current time falls within the time span of six hours
* prior to the leap second adjustment to six hours after the adjustment time, ,
* the effective time is computed according to the following equations:
*/
//std::cout<<"GST->UTC case b"<<std::endl;
Delta_t_Utc = Delta_tLS_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
double W = fmod(t_e - Delta_t_Utc - 43200, 86400) + 43200;
t_Utc_daytime = fmod(W, 86400 + Delta_tLSF_6 - Delta_tLS_6);
//implement something to handle a leap second event!
}
}
{
//Detect if the effectivity time and user's time is within six hours = 6 * 60 *60 = 21600 s
int secondOfLeapSecondEvent = DN_6 * 24 * 60 * 60;
if (abs(t_e - secondOfLeapSecondEvent) > 21600)
{
/* 5.1.7a
* Whenever the leap second adjusted time indicated by the WN_LSF and the DN values
* is not in the past (relative to the user's present time), and the user's
* present time does not fall in the time span which starts at six hours prior
* to the effective time and ends at six hours after the effective time,
* the GST/Utc relationship is given by
*/
//std::cout<<"GST->UTC case a"<<std::endl;
Delta_t_Utc = Delta_tLS_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
t_Utc_daytime = fmod(t_e - Delta_t_Utc, 86400);
}
else
{
/* 5.1.7b
* Whenever the user's current time falls within the time span of six hours
* prior to the leap second adjustment to six hours after the adjustment time, ,
* the effective time is computed according to the following equations:
*/
//std::cout<<"GST->UTC case b"<<std::endl;
Delta_t_Utc = Delta_tLS_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
double W = fmod(t_e - Delta_t_Utc - 43200, 86400) + 43200;
t_Utc_daytime = fmod(W, 86400 + Delta_tLSF_6 - Delta_tLS_6);
//implement something to handle a leap second event!
}
}
else // the effectivity time is in the past
{
/* 5.1.7c
* Whenever the leap second adjustment time, as indicated by the WN_LSF and DN values,
* is in the past (relative to the users current time) and the users present time does not
* fall in the time span which starts six hours prior to the leap second adjustment time and
* ends six hours after the adjustment time, the effective time is computed according to
* the following equation:
*/
//std::cout<<"GST->UTC case c"<<std::endl;
Delta_t_Utc = Delta_tLSF_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
t_Utc_daytime = fmod(t_e - Delta_t_Utc, 86400);
}
{
/* 5.1.7c
* Whenever the leap second adjustment time, as indicated by the WN_LSF and DN values,
* is in the past (relative to the users current time) and the users present time does not
* fall in the time span which starts six hours prior to the leap second adjustment time and
* ends six hours after the adjustment time, the effective time is computed according to
* the following equation:
*/
//std::cout<<"GST->UTC case c"<<std::endl;
Delta_t_Utc = Delta_tLSF_6 + A0_6 + A1_6 * (t_e - t0t_6 + 604800 * (double)((WN % 256) - WNot_6));
t_Utc_daytime = fmod(t_e - Delta_t_Utc, 86400);
}
double secondsOfWeekBeforeToday = 43200 * floor(t_e / 43200);
t_Utc = secondsOfWeekBeforeToday + t_Utc_daytime;

View File

@ -29,7 +29,6 @@
*/
#include "gnss_satellite.h"
#include <glog/log_severity.h>
#include <glog/logging.h>

View File

@ -28,15 +28,15 @@
* -------------------------------------------------------------------------
*/
#include "sbas_ionospheric_correction.h"
#include <stdarg.h>
#include <stdio.h>
#include <math.h>
#include <cmath>
#include <iostream>
#include <sstream>
#include <boost/serialization/map.hpp>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "sbas_ionospheric_correction.h"
enum V_Log_Level {EVENT = 2, // logs important events which don't occur every update() call
FLOW = 3, // logs the function calls of block processing functions

View File

@ -33,7 +33,6 @@
#include <stdio.h>
#include <iostream>
#include <string>
#include <glog/log_severity.h>
#include <glog/logging.h>

View File

@ -32,7 +32,6 @@
#include <stdio.h>
#include <cstring>
#include <iostream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include "sbas_telemetry_data.h"
#include "sbas_ionospheric_correction.h"

View File

@ -33,7 +33,6 @@
#include <cmath>
#include <iostream>
#include <glog/log_severity.h>
#include <glog/logging.h>
#define EVENT 2 // logs important events which don't occur every update() call

View File

@ -34,17 +34,18 @@
#define GNSS_SDR_VERSION "0.0.2"
#endif
#include <boost/filesystem.hpp>
#include <ctime>
#include <memory>
#include <queue>
#include <boost/exception/diagnostic_information.hpp>
#include <boost/exception_ptr.hpp>
#include <boost/filesystem.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include "control_thread.h"
#include <queue>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include "concurrent_queue.h"
#include "concurrent_map.h"
#include "gps_ephemeris.h"
@ -61,9 +62,6 @@
#include "sbas_ephemeris.h"
#include "sbas_time.h"
#include <sys/time.h>
#include <ctime>
#include <memory>
using google::LogMessage;
@ -117,7 +115,7 @@ int main(int argc, char** argv)
const std::string intro_help(
std::string("\nGNSS-SDR is an Open Source GNSS Software Defined Receiver\n")
+
"Copyright (C) 2010-2013 (see AUTHORS file for a list of contributors)\n"
"Copyright (C) 2010-2014 (see AUTHORS file for a list of contributors)\n"
+
"This program comes with ABSOLUTELY NO WARRANTY;\n"
+
@ -170,11 +168,11 @@ int main(int argc, char** argv)
}
catch( boost::exception & e )
{
DLOG(FATAL) << "Boost exception: " << boost::diagnostic_information(e);
LOG(FATAL) << "Boost exception: " << boost::diagnostic_information(e);
}
catch(std::exception const& ex)
{
DLOG(FATAL) << "STD exception: " << ex.what();
LOG(FATAL) << "STD exception: " << ex.what();
}
// report the elapsed time
gettimeofday(&tv, NULL);

View File

@ -34,6 +34,52 @@
#include <gnuradio/msg_queue.h>
#include "control_thread.h"
#include "in_memory_configuration.h"
#include "control_thread.h"
#include <boost/lexical_cast.hpp>
#include "gps_ephemeris.h"
#include "gps_iono.h"
#include "gps_utc_model.h"
#include "gps_almanac.h"
#include "galileo_ephemeris.h"
#include "galileo_iono.h"
#include "galileo_utc_model.h"
#include "galileo_almanac.h"
#include "concurrent_queue.h"
#include "concurrent_map.h"
#include <unistd.h>
#include <gnuradio/message.h>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include "gnss_flowgraph.h"
#include "file_configuration.h"
#include "control_message_factory.h"
#include <boost/thread/thread.hpp>
extern concurrent_map<Gps_Ephemeris> global_gps_ephemeris_map;
extern concurrent_map<Gps_Iono> global_gps_iono_map;
extern concurrent_map<Gps_Utc_Model> global_gps_utc_model_map;
extern concurrent_map<Gps_Almanac> global_gps_almanac_map;
extern concurrent_map<Gps_Acq_Assist> global_gps_acq_assist_map;
extern concurrent_queue<Gps_Ephemeris> global_gps_ephemeris_queue;
extern concurrent_queue<Gps_Iono> global_gps_iono_queue;
extern concurrent_queue<Gps_Utc_Model> global_gps_utc_model_queue;
extern concurrent_queue<Gps_Almanac> global_gps_almanac_queue;
extern concurrent_queue<Gps_Acq_Assist> global_gps_acq_assist_queue;
extern concurrent_map<Galileo_Ephemeris> global_galileo_ephemeris_map;
extern concurrent_map<Galileo_Iono> global_galileo_iono_map;
extern concurrent_map<Galileo_Utc_Model> global_galileo_utc_model_map;
extern concurrent_map<Galileo_Almanac> global_galileo_almanac_map;
//extern concurrent_map<Galileo_Acq_Assist> global_gps_acq_assist_map;
extern concurrent_queue<Galileo_Ephemeris> global_galileo_ephemeris_queue;
extern concurrent_queue<Galileo_Iono> global_galileo_iono_queue;
extern concurrent_queue<Galileo_Utc_Model> global_galileo_utc_model_queue;
extern concurrent_queue<Galileo_Almanac> global_galileo_almanac_queue;
TEST(Control_Thread_Test, InstantiateRunControlMessages)
@ -48,11 +94,9 @@ TEST(Control_Thread_Test, InstantiateRunControlMessages)
config->set_property("SignalConditioner.implementation", "Pass_Through");
config->set_property("SignalConditioner.item_type", "gr_complex");
config->set_property("Channels.count", "2");
config->set_property("Acquisition1.implementation", "GPS_L1_CA_PCPS_Acquisition");
config->set_property("Acquisition1.item_type", "gr_complex");
config->set_property("Acquisition2.implementation", "GPS_L1_CA_PCPS_Acquisition");
config->set_property("Acquisition2.item_type", "gr_complex");
config->set_property("Tracking.implementation", "GPS_L1_CA_DLL_FLL_PLL_Tracking");
config->set_property("Acquisition.implementation", "GPS_L1_CA_PCPS_Acquisition");
config->set_property("Acquisition.item_type", "gr_complex");
config->set_property("Tracking.implementation", "GPS_L1_CA_DLL_PLL_Tracking");
config->set_property("Tracking.item_type", "gr_complex");
config->set_property("TelemetryDecoder.implementation", "GPS_L1_CA_Telemetry_Decoder");
config->set_property("TelemetryDecoder.item_type", "gr_complex");
@ -63,7 +107,7 @@ TEST(Control_Thread_Test, InstantiateRunControlMessages)
config->set_property("OutputFilter.implementation", "Null_Sink_Output_Filter");
config->set_property("OutputFilter.item_type", "gr_complex");
ControlThread *control_thread = new ControlThread(config);
std::unique_ptr<ControlThread> control_thread(new ControlThread(config));
gr::msg_queue::sptr control_queue = gr::msg_queue::make(0);
ControlMessageFactory *control_msg_factory = new ControlMessageFactory();
@ -97,7 +141,7 @@ TEST(Control_Thread_Test, InstantiateRunControlMessages)
EXPECT_EQ(expected1, control_thread->applied_actions());
delete config;
delete control_thread;
//delete control_thread;
delete control_msg_factory;
}

View File

@ -31,7 +31,6 @@
#include <gtest/gtest.h>
#include "file_output_filter.h"
#include "in_memory_configuration.h"

View File

@ -243,12 +243,10 @@ TEST_F(GalileoE1PcpsAmbiguousAcquisitionGSoCTest, ValidationOfResults)
}) << "Failure connecting the blocks of acquisition test." << std::endl;
ASSERT_NO_THROW( {
start_queue();
acquisition->init();
acquisition->reset();
}) << "Failure !!!" << std::endl;
start_queue();
acquisition->init();
acquisition->reset();
}) << "Failure starting acquisition" << std::endl;
EXPECT_NO_THROW( {
gettimeofday(&tv, NULL);

View File

@ -176,8 +176,8 @@ TEST_F(GpsL1CaPcpsAcquisitionTest, ValidationOfResults)
struct timeval tv;
long long int begin = 0;
long long int end = 0;
double expected_delay_samples = 524;
double expected_doppler_hz = 1680;
double expected_delay_samples = 945;
double expected_doppler_hz = 4000;
init();
GpsL1CaPcpsAcquisition *acquisition = new GpsL1CaPcpsAcquisition(config, "Acquisition", 1, 1, queue);
@ -194,7 +194,7 @@ TEST_F(GpsL1CaPcpsAcquisitionTest, ValidationOfResults)
}) << "Failure setting channel_internal_queue." << std::endl;
ASSERT_NO_THROW( {
acquisition->set_threshold(config->property("Acquisition.threshold", 0.0));
acquisition->set_threshold(config->property("Acquisition.threshold", 0.005));
}) << "Failure setting threshold." << std::endl;
ASSERT_NO_THROW( {
@ -236,6 +236,9 @@ TEST_F(GpsL1CaPcpsAcquisitionTest, ValidationOfResults)
ASSERT_EQ(1, message) << "Acquisition failure. Expected message: 1=ACQ SUCCESS.";
std::cout << "----Aq_delay: " << gnss_synchro.Acq_delay_samples << std::endl;
std::cout << "----Doppler: " << gnss_synchro.Acq_doppler_hz << std::endl;
double delay_error_samples = abs(expected_delay_samples - gnss_synchro.Acq_delay_samples);
float delay_error_chips = (float)(delay_error_samples*1023/4000);
double doppler_error_hz = abs(expected_doppler_hz - gnss_synchro.Acq_doppler_hz);

View File

@ -31,16 +31,15 @@
#include <iostream>
#include <queue>
#include <gtest/gtest.h>
#include "concurrent_map.h"
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gflags/gflags.h>
#include <gnuradio/msg_queue.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <boost/filesystem.hpp>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include <gtest/gtest.h>
#include <gnuradio/msg_queue.h>
#include "concurrent_queue.h"
#include "concurrent_map.h"
#include "gps_navigation_message.h"

View File

@ -35,7 +35,6 @@
#include <iostream>
#include <queue>
#include <gtest/gtest.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include <boost/thread/mutex.hpp>
@ -78,7 +77,7 @@
#include "string_converter/string_converter_test.cc"
//#include "flowgraph/gnss_flowgraph_test.cc"
#include "gnss_block/rtcm_printer_test.cc"
//#include "gnss_block/rtcm_printer_test.cc"
#include "gnss_block/file_output_filter_test.cc"
#include "gnss_block/file_signal_source_test.cc"
#include "gnss_block/fir_filter_test.cc"

View File

@ -29,10 +29,13 @@
* -------------------------------------------------------------------------
*/
#include "front_end_cal.h"
#include <cmath>
#include <ctime>
#include <memory>
#include <exception>
#include <boost/filesystem.hpp>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
@ -44,12 +47,6 @@
#include "gps_iono.h"
#include "gps_utc_model.h"
#include "gnss_sdr_supl_client.h"
#include <sys/time.h>
#include <ctime>
#include <memory>
#include <math.h>
#include "front_end_cal.h"
extern concurrent_map<Gps_Ephemeris> global_gps_ephemeris_map;
extern concurrent_map<Gps_Iono> global_gps_iono_map;
@ -103,7 +100,7 @@ int FrontEndCal::Get_SUPL_Assist()
if (enable_gps_supl_assistance == true)
//SUPL SERVER TEST. Not operational yet!
{
DLOG(INFO) << "SUPL RRLP GPS assistance enabled!" << std::endl;
LOG(INFO) << "SUPL RRLP GPS assistance enabled!" << std::endl;
std::string default_acq_server = "supl.nokia.com";
std::string default_eph_server = "supl.google.com";
supl_client_ephemeris_.server_name = configuration_->property("GNSS-SDR.SUPL_gps_ephemeris_server", default_acq_server);

View File

@ -32,10 +32,16 @@
#define FRONT_END_CAL_VERSION "0.0.1"
#endif
#include <ctime>
#include <exception>
#include <memory>
#include <queue>
#include <vector>
#include <boost/filesystem.hpp>
#include <boost/lexical_cast.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <gflags/gflags.h>
#include <glog/log_severity.h>
#include <glog/logging.h>
#include <gnuradio/msg_queue.h>
#include <gnuradio/top_block.h>
@ -44,41 +50,28 @@
#include <gnuradio/blocks/head.h>
#include <gnuradio/blocks/file_source.h>
#include <gnuradio/blocks/file_sink.h>
#include <queue>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <boost/lexical_cast.hpp>
#include <vector>
#include "concurrent_map.h"
#include "file_configuration.h"
#include "gps_l1_ca_pcps_acquisition_fine_doppler.h"
#include "gnss_signal.h"
#include "gnss_synchro.h"
#include "gnss_block_factory.h"
#include "gps_navigation_message.h"
#include "gps_ephemeris.h"
#include "gps_almanac.h"
#include "gps_iono.h"
#include "gps_utc_model.h"
#include "galileo_ephemeris.h"
#include "galileo_almanac.h"
#include "galileo_iono.h"
#include "galileo_utc_model.h"
#include "sbas_telemetry_data.h"
#include "sbas_ionospheric_correction.h"
#include "sbas_satellite_correction.h"
#include "sbas_ephemeris.h"
#include "sbas_time.h"
#include "gnss_sdr_supl_client.h"
#include <sys/time.h>
#include <ctime>
#include <memory>
#include "front_end_cal.h"
@ -412,7 +405,7 @@ int main(int argc, char** argv)
time_t t = utc_time(Eph_map.begin()->second.i_GPS_week, (long int)current_TOW);
fprintf(stdout, "Reference Time:\n");
fprintf(stdout, " GPS Week: %ld\n", Eph_map.begin()->second.i_GPS_week);
fprintf(stdout, " GPS Week: %d\n", Eph_map.begin()->second.i_GPS_week);
fprintf(stdout, " GPS TOW: %ld %lf\n", (long int)current_TOW, (long int)current_TOW*0.08);
fprintf(stdout, " ~ UTC: %s", ctime(&t));
std::cout << "Current TOW obtained from SUPL assistance = " << current_TOW << std::endl;