1
0
mirror of https://github.com/gnss-sdr/gnss-sdr synced 2025-01-15 11:45:47 +00:00
This commit is contained in:
Carles Fernandez 2019-08-18 22:16:41 +02:00
commit df0cd91b27
No known key found for this signature in database
GPG Key ID: 4C583C52B0C3877D
137 changed files with 824 additions and 837 deletions

View File

@ -283,8 +283,8 @@ Rtklib_Pvt::Rtklib_Pvt(ConfigurationInterface* configuration,
{ {
pvt_output_parameters.type_of_receiver = 18; pvt_output_parameters.type_of_receiver = 18;
} }
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 19; // if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 19;
//if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 20; // if( (gps_1C_count == 0) && (gps_2S_count == 0) && (gps_L5_count == 0) && (gal_1B_count == 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0)) pvt_output_parameters.type_of_receiver = 20;
if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0)) if ((gps_1C_count != 0) && (gps_2S_count != 0) && (gps_L5_count == 0) && (gal_1B_count != 0) && (gal_E5a_count == 0) && (gal_E5b_count == 0) && (glo_1G_count == 0) && (glo_2G_count == 0) && (bds_B1_count == 0) && (bds_B3_count == 0))
{ {
pvt_output_parameters.type_of_receiver = 21; // GPS L1 C/A + Galileo E1B + GPS L2C pvt_output_parameters.type_of_receiver = 21; // GPS L1 C/A + Galileo E1B + GPS L2C

View File

@ -99,7 +99,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
double GST = 0.0; double GST = 0.0;
double secondsperweek = 604800.0; double secondsperweek = 604800.0;
//double utc_tx_corrected = 0.0; //utc computed at tx_time_corrected, added for Galileo constellation (in GPS utc is directly computed at TX_time_corrected_s) // double utc_tx_corrected = 0.0; //utc computed at tx_time_corrected, added for Galileo constellation (in GPS utc is directly computed at TX_time_corrected_s)
double TX_time_corrected_s = 0.0; double TX_time_corrected_s = 0.0;
double SV_clock_bias_s = 0.0; double SV_clock_bias_s = 0.0;
@ -108,7 +108,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
// ******************************************************************************** // ********************************************************************************
// ****** PREPARE THE LEAST SQUARES DATA (SV POSITIONS MATRIX AND OBS VECTORS) **** // ****** PREPARE THE LEAST SQUARES DATA (SV POSITIONS MATRIX AND OBS VECTORS) ****
// ******************************************************************************** // ********************************************************************************
int valid_obs = 0; //valid observations counter int valid_obs = 0; // valid observations counter
for (gnss_observables_iter = gnss_observables_map.begin(); for (gnss_observables_iter = gnss_observables_map.begin();
gnss_observables_iter != gnss_observables_map.end(); gnss_observables_iter != gnss_observables_map.end();
@ -139,7 +139,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
TX_time_corrected_s = Tx_time - SV_clock_bias_s; TX_time_corrected_s = Tx_time - SV_clock_bias_s;
galileo_ephemeris_iter->second.satellitePosition(TX_time_corrected_s); galileo_ephemeris_iter->second.satellitePosition(TX_time_corrected_s);
//store satellite positions in a matrix // store satellite positions in a matrix
satpos.resize(3, valid_obs + 1); satpos.resize(3, valid_obs + 1);
satpos(0, valid_obs) = galileo_ephemeris_iter->second.d_satpos_X; satpos(0, valid_obs) = galileo_ephemeris_iter->second.d_satpos_X;
satpos(1, valid_obs) = galileo_ephemeris_iter->second.d_satpos_Y; satpos(1, valid_obs) = galileo_ephemeris_iter->second.d_satpos_Y;
@ -149,7 +149,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
obs.resize(valid_obs + 1, 1); obs.resize(valid_obs + 1, 1);
obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + SV_clock_bias_s * GALILEO_C_M_S - this->get_time_offset_s() * GALILEO_C_M_S; obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + SV_clock_bias_s * GALILEO_C_M_S - this->get_time_offset_s() * GALILEO_C_M_S;
Galileo_week_number = galileo_ephemeris_iter->second.WN_5; //for GST Galileo_week_number = galileo_ephemeris_iter->second.WN_5; // for GST
GST = galileo_ephemeris_iter->second.Galileo_System_Time(Galileo_week_number, hybrid_current_time); GST = galileo_ephemeris_iter->second.Galileo_System_Time(Galileo_week_number, hybrid_current_time);
// SV ECEF DEBUG OUTPUT // SV ECEF DEBUG OUTPUT
@ -194,7 +194,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
TX_time_corrected_s = Tx_time - SV_clock_bias_s; TX_time_corrected_s = Tx_time - SV_clock_bias_s;
double dtr = gps_ephemeris_iter->second.satellitePosition(TX_time_corrected_s); double dtr = gps_ephemeris_iter->second.satellitePosition(TX_time_corrected_s);
//store satellite positions in a matrix // store satellite positions in a matrix
satpos.resize(3, valid_obs + 1); satpos.resize(3, valid_obs + 1);
satpos(0, valid_obs) = gps_ephemeris_iter->second.d_satpos_X; satpos(0, valid_obs) = gps_ephemeris_iter->second.d_satpos_X;
satpos(1, valid_obs) = gps_ephemeris_iter->second.d_satpos_Y; satpos(1, valid_obs) = gps_ephemeris_iter->second.d_satpos_Y;
@ -247,10 +247,10 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
// 3- compute the current ECEF position for this SV using corrected TX time // 3- compute the current ECEF position for this SV using corrected TX time
TX_time_corrected_s = Tx_time - SV_clock_bias_s; TX_time_corrected_s = Tx_time - SV_clock_bias_s;
//std::cout<<"TX time["<<gps_cnav_ephemeris_iter->second.i_satellite_PRN<<"]="<<TX_time_corrected_s<<std::endl; // std::cout<<"TX time["<<gps_cnav_ephemeris_iter->second.i_satellite_PRN<<"]="<<TX_time_corrected_s<<std::endl;
double dtr = gps_cnav_ephemeris_iter->second.satellitePosition(TX_time_corrected_s); double dtr = gps_cnav_ephemeris_iter->second.satellitePosition(TX_time_corrected_s);
//store satellite positions in a matrix // store satellite positions in a matrix
satpos.resize(3, valid_obs + 1); satpos.resize(3, valid_obs + 1);
satpos(0, valid_obs) = gps_cnav_ephemeris_iter->second.d_satpos_X; satpos(0, valid_obs) = gps_cnav_ephemeris_iter->second.d_satpos_X;
satpos(1, valid_obs) = gps_cnav_ephemeris_iter->second.d_satpos_Y; satpos(1, valid_obs) = gps_cnav_ephemeris_iter->second.d_satpos_Y;
@ -261,7 +261,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + dtr * GPS_C_M_S + SV_clock_bias_s * GPS_C_M_S; obs(valid_obs) = gnss_observables_iter->second.Pseudorange_m + dtr * GPS_C_M_S + SV_clock_bias_s * GPS_C_M_S;
GPS_week = gps_cnav_ephemeris_iter->second.i_GPS_week; GPS_week = gps_cnav_ephemeris_iter->second.i_GPS_week;
GPS_week = GPS_week % 1024; //Necessary due to the increase of WN bits in CNAV message (10 in GPS NAV and 13 in CNAV) GPS_week = GPS_week % 1024; // Necessary due to the increase of WN bits in CNAV message (10 in GPS NAV and 13 in CNAV)
// SV ECEF DEBUG OUTPUT // SV ECEF DEBUG OUTPUT
LOG(INFO) << "(new)ECEF GPS L2M satellite SV ID=" << gps_cnav_ephemeris_iter->second.i_satellite_PRN LOG(INFO) << "(new)ECEF GPS L2M satellite SV ID=" << gps_cnav_ephemeris_iter->second.i_satellite_PRN
@ -386,7 +386,7 @@ bool Hybrid_Ls_Pvt::get_PVT(std::map<int, Gnss_Synchro> gnss_observables_map, do
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
this->set_time_offset_s(0.0); //reset rx time estimation this->set_time_offset_s(0.0); // reset rx time estimation
LOG(WARNING) << "Problem with the solver, invalid solution!" << e.what(); LOG(WARNING) << "Problem with the solver, invalid solution!" << e.what();
this->set_valid_position(false); this->set_valid_position(false);
} }

View File

@ -181,7 +181,7 @@ arma::vec Ls_Pvt::leastSquarePos(const arma::mat& satpos, const arma::vec& obs,
int nmbOfSatellites; int nmbOfSatellites;
nmbOfSatellites = satpos.n_cols; // Armadillo nmbOfSatellites = satpos.n_cols; // Armadillo
arma::mat w = arma::zeros(nmbOfSatellites, nmbOfSatellites); arma::mat w = arma::zeros(nmbOfSatellites, nmbOfSatellites);
w.diag() = w_vec; //diagonal weight matrix w.diag() = w_vec; // diagonal weight matrix
arma::vec rx_pos = this->get_rx_pos(); arma::vec rx_pos = this->get_rx_pos();
arma::vec pos = {rx_pos(0), rx_pos(1), rx_pos(2), 0}; // time error in METERS (time x speed) arma::vec pos = {rx_pos(0), rx_pos(1), rx_pos(2), 0}; // time error in METERS (time x speed)
@ -206,13 +206,13 @@ arma::vec Ls_Pvt::leastSquarePos(const arma::mat& satpos, const arma::vec& obs,
{ {
if (iter == 0) if (iter == 0)
{ {
//--- Initialize variables at the first iteration -------------- // --- Initialize variables at the first iteration -------------
Rot_X = X.col(i); //Armadillo Rot_X = X.col(i); // Armadillo
trop = 0.0; trop = 0.0;
} }
else else
{ {
//--- Update equations ----------------------------------------- // --- Update equations ----------------------------------------
rho2 = (X(0, i) - pos(0)) * rho2 = (X(0, i) - pos(0)) *
(X(0, i) - pos(0)) + (X(0, i) - pos(0)) +
(X(1, i) - pos(1)) * (X(1, i) - pos(1)) *
@ -221,8 +221,8 @@ arma::vec Ls_Pvt::leastSquarePos(const arma::mat& satpos, const arma::vec& obs,
(X(2, i) - pos(2)); (X(2, i) - pos(2));
traveltime = sqrt(rho2) / GPS_C_M_S; traveltime = sqrt(rho2) / GPS_C_M_S;
//--- Correct satellite position (do to earth rotation) -------- // --- Correct satellite position (do to earth rotation) -------
Rot_X = Ls_Pvt::rotateSatellite(traveltime, X.col(i)); //armadillo Rot_X = Ls_Pvt::rotateSatellite(traveltime, X.col(i)); // armadillo
//--- Find DOA and range of satellites //--- Find DOA and range of satellites
double* azim = nullptr; double* azim = nullptr;
@ -232,30 +232,30 @@ arma::vec Ls_Pvt::leastSquarePos(const arma::mat& satpos, const arma::vec& obs,
if (traveltime < 0.1 && nmbOfSatellites > 3) if (traveltime < 0.1 && nmbOfSatellites > 3)
{ {
//--- Find receiver's height // --- Find receiver's height
togeod(&dphi, &dlambda, &h, 6378137.0, 298.257223563, pos(0), pos(1), pos(2)); togeod(&dphi, &dlambda, &h, 6378137.0, 298.257223563, pos(0), pos(1), pos(2));
// Add troposphere correction if the receiver is below the troposphere // Add troposphere correction if the receiver is below the troposphere
if (h > 15000) if (h > 15000)
{ {
//receiver is above the troposphere // receiver is above the troposphere
trop = 0.0; trop = 0.0;
} }
else else
{ {
//--- Find delay due to troposphere (in meters) // --- Find delay due to troposphere (in meters)
Ls_Pvt::tropo(&trop, sin(*elev * GPS_PI / 180.0), h / 1000.0, 1013.0, 293.0, 50.0, 0.0, 0.0, 0.0); Ls_Pvt::tropo(&trop, sin(*elev * GPS_PI / 180.0), h / 1000.0, 1013.0, 293.0, 50.0, 0.0, 0.0, 0.0);
if (trop > 5.0) if (trop > 5.0)
{ {
trop = 0.0; //check for erratic values trop = 0.0; // check for erratic values
} }
} }
} }
} }
//--- Apply the corrections ---------------------------------------- // --- Apply the corrections ----------------------------------------
omc(i) = (obs(i) - norm(Rot_X - pos.subvec(0, 2), 2) - pos(3) - trop); // Armadillo omc(i) = (obs(i) - norm(Rot_X - pos.subvec(0, 2), 2) - pos(3) - trop); // Armadillo
//--- Construct the A matrix --------------------------------------- //--- Construct the A matrix ---------------------------------------
//Armadillo // Armadillo
A(i, 0) = (-(Rot_X(0) - pos(0))) / obs(i); A(i, 0) = (-(Rot_X(0) - pos(0))) / obs(i);
A(i, 1) = (-(Rot_X(1) - pos(1))) / obs(i); A(i, 1) = (-(Rot_X(1) - pos(1))) / obs(i);
A(i, 2) = (-(Rot_X(2) - pos(2))) / obs(i); A(i, 2) = (-(Rot_X(2) - pos(2))) / obs(i);

View File

@ -74,7 +74,7 @@ private:
std::string nmea_devname; std::string nmea_devname;
int nmea_dev_descriptor; // NMEA serial device descriptor (i.e. COM port) int nmea_dev_descriptor; // NMEA serial device descriptor (i.e. COM port)
std::shared_ptr<Rtklib_Solver> d_PVT_data; std::shared_ptr<Rtklib_Solver> d_PVT_data;
int init_serial(const std::string& serial_device); //serial port control int init_serial(const std::string& serial_device); // serial port control
void close_serial(); void close_serial();
std::string get_GPGGA(); // fix data std::string get_GPGGA(); // fix data
std::string get_GPGSV(); // satellite data std::string get_GPGSV(); // satellite data

View File

@ -127,7 +127,7 @@ int Pvt_Solution::cart2geo(double X, double Y, double Z, int elipsoid_selection)
d_latitude_d = phi * 180.0 / GPS_PI; d_latitude_d = phi * 180.0 / GPS_PI;
d_longitude_d = lambda * 180.0 / GPS_PI; d_longitude_d = lambda * 180.0 / GPS_PI;
d_height_m = h; d_height_m = h;
//todo: refactor this class. Mix of duplicated functions, use either RTKLIB geodetic functions or geofunctions.h // todo: refactor this class. Mix of duplicated functions, use either RTKLIB geodetic functions or geofunctions.h
return 0; return 0;
} }
@ -284,7 +284,7 @@ void Pvt_Solution::perform_pos_averaging()
} }
else else
{ {
//int current_depth=d_hist_longitude_d.size(); // int current_depth=d_hist_longitude_d.size();
// Push new values // Push new values
d_hist_longitude_d.push_front(d_longitude_d); d_hist_longitude_d.push_front(d_longitude_d);
d_hist_latitude_d.push_front(d_latitude_d); d_hist_latitude_d.push_front(d_latitude_d);

View File

@ -79,7 +79,7 @@ public:
int get_num_valid_observations() const; //!< Get the number of valid pseudorange observations (valid satellites) int get_num_valid_observations() const; //!< Get the number of valid pseudorange observations (valid satellites)
void set_num_valid_observations(int num); //!< Set the number of valid pseudorange observations (valid satellites) void set_num_valid_observations(int num); //!< Set the number of valid pseudorange observations (valid satellites)
//averaging // averaging
void perform_pos_averaging(); void perform_pos_averaging();
void set_averaging_depth(int depth); //!< Set length of averaging window void set_averaging_depth(int depth); //!< Set length of averaging window
bool is_averaging() const; bool is_averaging() const;

View File

@ -1385,7 +1385,7 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Gps_Iono& iono, co
{ {
line += std::string("N: GNSS NAV DATA"); line += std::string("N: GNSS NAV DATA");
line += std::string(4, ' '); line += std::string(4, ' ');
//todo Add here other systems... // todo Add here other systems...
line += std::string("G: GPS"); line += std::string("G: GPS");
line += std::string(14, ' '); line += std::string(14, ' ');
// ... // ...
@ -1750,7 +1750,7 @@ void Rinex_Printer::rinex_nav_header(std::fstream& out, const Beidou_Dnav_Iono&
{ {
line += std::string("N: GNSS NAV DATA"); line += std::string("N: GNSS NAV DATA");
line += std::string(4, ' '); line += std::string(4, ' ');
//todo: Add here other systems... // todo: Add here other systems...
line += std::string("F: BDS"); line += std::string("F: BDS");
line += std::string(14, ' '); line += std::string(14, ' ');
// ... // ...
@ -4258,7 +4258,7 @@ void Rinex_Printer::log_rinex_nav(std::fstream& out, const std::map<int32_t, Gal
line += std::string(5, ' '); line += std::string(5, ' ');
line += Rinex_Printer::doub2for(galileo_ephemeris_iter->second.iDot_2, 18, 2); line += Rinex_Printer::doub2for(galileo_ephemeris_iter->second.iDot_2, 18, 2);
line += std::string(1, ' '); line += std::string(1, ' ');
//double one = 1.0; // INAV E1-B // double one = 1.0; // INAV E1-B
std::string iNAVE1B("1000000001"); std::string iNAVE1B("1000000001");
int32_t data_source_INAV = Rinex_Printer::toInt(iNAVE1B, 10); int32_t data_source_INAV = Rinex_Printer::toInt(iNAVE1B, 10);
line += Rinex_Printer::doub2for(static_cast<double>(data_source_INAV), 18, 2); line += Rinex_Printer::doub2for(static_cast<double>(data_source_INAV), 18, 2);
@ -4477,7 +4477,7 @@ void Rinex_Printer::log_rinex_nav(std::fstream& out, const std::map<int32_t, Glo
line += std::string(1, ' '); line += std::string(1, ' ');
line += Rinex_Printer::doub2for(+glonass_gnav_ephemeris_iter->second.d_gamma_n, 18, 2); line += Rinex_Printer::doub2for(+glonass_gnav_ephemeris_iter->second.d_gamma_n, 18, 2);
line += std::string(1, ' '); line += std::string(1, ' ');
//TODO need to define this here. what is nd // TODO need to define this here. what is nd
line += Rinex_Printer::doub2for(glonass_gnav_ephemeris_iter->second.d_t_k + p_utc_time.date().day_of_week() * 86400, 18, 2); line += Rinex_Printer::doub2for(glonass_gnav_ephemeris_iter->second.d_t_k + p_utc_time.date().day_of_week() * 86400, 18, 2);
} }
Rinex_Printer::lengthCheck(line); Rinex_Printer::lengthCheck(line);
@ -8802,7 +8802,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Glonass_Gnav_Ephemeri
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -8817,7 +8817,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Glonass_Gnav_Ephemeri
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -8829,7 +8829,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Glonass_Gnav_Ephemeri
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -8859,8 +8859,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
// -------- EPOCH record // -------- EPOCH record
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = gps_obs_time; double gps_t = gps_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -9077,7 +9077,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9092,7 +9092,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9104,7 +9104,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9139,7 +9139,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
for (auto iter = ret.first; iter != ret.second; ++iter) for (auto iter = ret.first; iter != ret.second; ++iter)
{ {
/// \todo Need to account for pseudorange correction for glonass /// \todo Need to account for pseudorange correction for glonass
//double leap_seconds = Rinex_Printer::get_leap_second(glonass_gnav_eph, gps_obs_time); // double leap_seconds = Rinex_Printer::get_leap_second(glonass_gnav_eph, gps_obs_time);
lineObs += Rinex_Printer::rightJustify(asString(iter->second.Pseudorange_m, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(iter->second.Pseudorange_m, 3), 14);
// Loss of lock indicator (LLI) // Loss of lock indicator (LLI)
@ -9148,7 +9148,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9163,7 +9163,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9175,7 +9175,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9204,8 +9204,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
// -------- EPOCH record // -------- EPOCH record
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = gps_obs_time; double gps_t = gps_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -9337,7 +9337,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9352,7 +9352,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9364,7 +9364,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9397,7 +9397,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
for (auto iter = ret.first; iter != ret.second; ++iter) for (auto iter = ret.first; iter != ret.second; ++iter)
{ {
/// \todo Need to account for pseudorange correction for glonass /// \todo Need to account for pseudorange correction for glonass
//double leap_seconds = Rinex_Printer::get_leap_second(glonass_gnav_eph, gps_obs_time); // double leap_seconds = Rinex_Printer::get_leap_second(glonass_gnav_eph, gps_obs_time);
lineObs += Rinex_Printer::rightJustify(asString(iter->second.Pseudorange_m, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(iter->second.Pseudorange_m, 3), 14);
// Loss of lock indicator (LLI) // Loss of lock indicator (LLI)
@ -9406,7 +9406,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9421,7 +9421,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9433,7 +9433,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& g
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9461,8 +9461,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
boost::posix_time::ptime p_galileo_time = Rinex_Printer::compute_Galileo_time(galileo_eph, galileo_obs_time); boost::posix_time::ptime p_galileo_time = Rinex_Printer::compute_Galileo_time(galileo_eph, galileo_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_galileo_time); std::string timestring = boost::posix_time::to_iso_string(p_galileo_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double galileo_t = galileo_obs_time; double galileo_t = galileo_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -9593,7 +9593,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9608,7 +9608,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9620,7 +9620,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9659,7 +9659,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9674,7 +9674,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9686,7 +9686,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ga
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9712,8 +9712,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = obs_time; double gps_t = obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -9805,7 +9805,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9830,12 +9830,12 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1); lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1);
//GPS L1 SIGNAL STRENGTH // GPS L1 SIGNAL STRENGTH
lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14);
if (lineObs.size() < 80) if (lineObs.size() < 80)
{ {
@ -9911,7 +9911,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9926,7 +9926,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -9938,14 +9938,14 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1); lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1);
//GPS L1 SIGNAL STRENGTH // GPS L1 SIGNAL STRENGTH
lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14);
if (lineObs.size() < 80) if (lineObs.size() < 80)
@ -9965,8 +9965,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = obs_time; double gps_t = obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -10030,7 +10030,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
} }
lineObs += std::to_string(static_cast<int32_t>(observables_iter->second.PRN)); lineObs += std::to_string(static_cast<int32_t>(observables_iter->second.PRN));
// lineObs += std::string(2, ' '); // lineObs += std::string(2, ' ');
//GPS L2 PSEUDORANGE // GPS L2 PSEUDORANGE
lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.Pseudorange_m, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.Pseudorange_m, 3), 14);
// Loss of lock indicator (LLI) // Loss of lock indicator (LLI)
@ -10039,7 +10039,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10054,7 +10054,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10066,14 +10066,14 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1); lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<int32_t>(ssi), 1);
//GPS L2 SIGNAL STRENGTH // GPS L2 SIGNAL STRENGTH
lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(observables_iter->second.CN0_dB_hz, 3), 14);
if (lineObs.size() < 80) if (lineObs.size() < 80)
@ -10095,8 +10095,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = obs_time; double gps_t = obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -10279,7 +10279,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10291,7 +10291,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& eph, c
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10318,8 +10318,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ep
boost::posix_time::ptime p_galileo_time = Rinex_Printer::compute_Galileo_time(eph, obs_time); boost::posix_time::ptime p_galileo_time = Rinex_Printer::compute_Galileo_time(eph, obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_galileo_time); std::string timestring = boost::posix_time::to_iso_string(p_galileo_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double galileo_t = obs_time; double galileo_t = obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -10510,7 +10510,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10525,7 +10525,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10537,7 +10537,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Galileo_Ephemeris& ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10565,8 +10565,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = gps_obs_time; double gps_t = gps_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -10716,7 +10716,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10731,7 +10731,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10743,7 +10743,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10782,7 +10782,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10797,7 +10797,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10809,7 +10809,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -10837,8 +10837,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, gps_obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(eph, gps_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = gps_obs_time; double gps_t = gps_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -11017,7 +11017,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11032,7 +11032,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11044,7 +11044,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11079,7 +11079,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11094,7 +11094,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11106,7 +11106,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11116,7 +11116,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_CNAV_Ephemeris& e
lineObs += Rinex_Printer::rightJustify(asString(iter->second.CN0_dB_hz, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(iter->second.CN0_dB_hz, 3), 14);
} }
//if (lineObs.size() < 80) lineObs += std::string(80 - lineObs.size(), ' '); // if (lineObs.size() < 80) lineObs += std::string(80 - lineObs.size(), ' ');
out << lineObs << std::endl; out << lineObs << std::endl;
} }
} }
@ -11134,8 +11134,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time); boost::posix_time::ptime p_gps_time = Rinex_Printer::compute_GPS_time(gps_eph, gps_obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_gps_time); std::string timestring = boost::posix_time::to_iso_string(p_gps_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double gps_t = gps_obs_time; double gps_t = gps_obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -11332,7 +11332,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11347,7 +11347,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11359,7 +11359,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11394,7 +11394,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11409,7 +11409,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11421,7 +11421,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
{ {
lineObs += std::string(1, ' '); lineObs += std::string(1, ' ');
} }
//else // else
// { // {
// lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1); // lineObs += Rinex_Printer::rightJustify(Rinex_Printer::asString<short>(lli), 1);
// } // }
@ -11431,7 +11431,7 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Gps_Ephemeris& gps_ep
lineObs += Rinex_Printer::rightJustify(asString(iter->second.CN0_dB_hz, 3), 14); lineObs += Rinex_Printer::rightJustify(asString(iter->second.CN0_dB_hz, 3), 14);
} }
//if (lineObs.size() < 80) lineObs += std::string(80 - lineObs.size(), ' '); // if (lineObs.size() < 80) lineObs += std::string(80 - lineObs.size(), ' ');
out << lineObs << std::endl; out << lineObs << std::endl;
} }
} }
@ -11443,8 +11443,8 @@ void Rinex_Printer::log_rinex_obs(std::fstream& out, const Beidou_Dnav_Ephemeris
boost::posix_time::ptime p_bds_time = Rinex_Printer::compute_BDS_time(eph, obs_time); boost::posix_time::ptime p_bds_time = Rinex_Printer::compute_BDS_time(eph, obs_time);
std::string timestring = boost::posix_time::to_iso_string(p_bds_time); std::string timestring = boost::posix_time::to_iso_string(p_bds_time);
//double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time)); // double utc_t = nav_msg.utc_time(nav_msg.sv_clock_correction(obs_time));
//double gps_t = eph.sv_clock_correction(obs_time); // double gps_t = eph.sv_clock_correction(obs_time);
double bds_t = obs_time; double bds_t = obs_time;
std::string month(timestring, 4, 2); std::string month(timestring, 4, 2);
@ -11644,10 +11644,10 @@ void Rinex_Printer::to_date_time(int32_t gps_week, int32_t gps_tow, int& year, i
else else
{ {
year = y; year = y;
//std::cout << "year: year=" << year << " secs_in_year_y="<< secs_in_year_y << " remaining_secs="<< remaining_secs << std::endl; // std::cout << "year: year=" << year << " secs_in_year_y="<< secs_in_year_y << " remaining_secs="<< remaining_secs << std::endl;
break; break;
} }
//std::cout << "year: y=" << y << " secs_in_year_y="<< secs_in_year_y << " remaining_secs="<< remaining_secs << std::endl; // std::cout << "year: y=" << y << " secs_in_year_y="<< secs_in_year_y << " remaining_secs="<< remaining_secs << std::endl;
} }
// find month // find month
@ -11666,10 +11666,10 @@ void Rinex_Printer::to_date_time(int32_t gps_week, int32_t gps_tow, int& year, i
else else
{ {
month = m; month = m;
//std::cout << "month: month=" << month << " secs_in_month_m="<< secs_in_month_m << " remaining_secs="<< remaining_secs << std::endl; // std::cout << "month: month=" << month << " secs_in_month_m="<< secs_in_month_m << " remaining_secs="<< remaining_secs << std::endl;
break; break;
} }
//std::cout << "month: m=" << m << " secs_in_month_m="<< secs_in_month_m << " remaining_secs="<< remaining_secs << std::endl; // std::cout << "month: m=" << m << " secs_in_month_m="<< secs_in_month_m << " remaining_secs="<< remaining_secs << std::endl;
} }
day = remaining_secs / secs_per_day + 1; day = remaining_secs / secs_per_day + 1;
@ -11683,8 +11683,8 @@ void Rinex_Printer::to_date_time(int32_t gps_week, int32_t gps_tow, int& year, i
} }
//void Rinex_Printer::log_rinex_sbs(std::fstream& out, const Sbas_Raw_Msg& sbs_message) // void Rinex_Printer::log_rinex_sbs(std::fstream& out, const Sbas_Raw_Msg& sbs_message)
//{ // {
// // line 1: PRN / EPOCH / RCVR // // line 1: PRN / EPOCH / RCVR
// std::stringstream line1; // std::stringstream line1;
// //
@ -11763,7 +11763,7 @@ void Rinex_Printer::to_date_time(int32_t gps_week, int32_t gps_tow, int& year, i
// line3 << std::string(31, ' '); // line3 << std::string(31, ' ');
// lengthCheck(line3.str()); // lengthCheck(line3.str());
// out << line3.str() << std::endl; // out << line3.str() << std::endl;
//} // }
int32_t Rinex_Printer::signalStrength(const double snr) int32_t Rinex_Printer::signalStrength(const double snr)

View File

@ -403,7 +403,7 @@ public:
/*! /*!
* \brief Writes raw SBAS messages into the RINEX file * \brief Writes raw SBAS messages into the RINEX file
*/ */
//void log_rinex_sbs(std::fstream & out, const Sbas_Raw_Msg & sbs_message); // void log_rinex_sbs(std::fstream & out, const Sbas_Raw_Msg & sbs_message);
void update_nav_header(std::fstream& out, const Gps_Utc_Model& utc_model, const Gps_Iono& gps_iono, const Gps_Ephemeris& eph); void update_nav_header(std::fstream& out, const Gps_Utc_Model& utc_model, const Gps_Iono& gps_iono, const Gps_Ephemeris& eph);
@ -775,8 +775,8 @@ inline std::string& Rinex_Printer::sci2for(std::string& aStr,
int expAdd = 0; int expAdd = 0;
std::string exp; std::string exp;
int64_t iexp; int64_t iexp;
//If checkSwitch is false, always redo the exponential. Otherwise, // If checkSwitch is false, always redo the exponential. Otherwise,
//set it to false. // set it to false.
bool redoexp = !checkSwitch; bool redoexp = !checkSwitch;
// Check for decimal place within specified boundaries // Check for decimal place within specified boundaries
@ -852,7 +852,7 @@ inline std::string& Rinex_Printer::sci2for(std::string& aStr,
aStr.insert(static_cast<std::string::size_type>(0), 1, ' '); aStr.insert(static_cast<std::string::size_type>(0), 1, ' ');
} }
//If checkSwitch is false, add on one leading zero to the string // If checkSwitch is false, add on one leading zero to the string
if (!checkSwitch) if (!checkSwitch)
{ {
aStr.insert(static_cast<std::string::size_type>(1), 1, '0'); aStr.insert(static_cast<std::string::size_type>(1), 1, '0');

View File

@ -3686,7 +3686,7 @@ uint32_t Rtcm::msm_extended_lock_time_indicator(uint32_t lock_time_period_s)
if( 16777216 <= lock_time_period_s && lock_time_period_s < 33554432 ) return (640 + (lock_time_period_s - 16777216) / 524288 ); if( 16777216 <= lock_time_period_s && lock_time_period_s < 33554432 ) return (640 + (lock_time_period_s - 16777216) / 524288 );
if( 33554432 <= lock_time_period_s && lock_time_period_s < 67108864 ) return (672 + (lock_time_period_s - 33554432) / 1048576); if( 33554432 <= lock_time_period_s && lock_time_period_s < 67108864 ) return (672 + (lock_time_period_s - 33554432) / 1048576);
if( 67108864 <= lock_time_period_s ) return (704 ); if( 67108864 <= lock_time_period_s ) return (704 );
return 1023; // will never happen return 1023; // will never happen
} }
// clang-format on // clang-format on
@ -4173,7 +4173,7 @@ int32_t Rtcm::set_DF047(const Gnss_Synchro& gnss_synchroL1, const Gnss_Synchro&
return 0; return 0;
} }
//TODO Need to consider frequency channel in this fields // TODO Need to consider frequency channel in this fields
int32_t Rtcm::set_DF048(const Gnss_Synchro& gnss_synchroL1, const Gnss_Synchro& gnss_synchroL2) int32_t Rtcm::set_DF048(const Gnss_Synchro& gnss_synchroL1, const Gnss_Synchro& gnss_synchroL2)
{ {
const double lambda2 = GLONASS_C_M_S / GLONASS_L2_CA_FREQ_HZ; const double lambda2 = GLONASS_C_M_S / GLONASS_L2_CA_FREQ_HZ;
@ -5554,7 +5554,7 @@ int32_t Rtcm::set_DF404(const Gnss_Synchro& gnss_synchro)
} }
if ((sig_ == "2C") && (sys_ == "R")) if ((sig_ == "2C") && (sys_ == "R"))
{ {
//TODO Need to add slot number and freq number to gnss syncro // TODO Need to add slot number and freq number to gnss syncro
lambda = GLONASS_C_M_S / (GLONASS_L2_CA_FREQ_HZ); lambda = GLONASS_C_M_S / (GLONASS_L2_CA_FREQ_HZ);
} }
double rough_phase_range_rate = std::round(-gnss_synchro.Carrier_Doppler_hz * lambda); double rough_phase_range_rate = std::round(-gnss_synchro.Carrier_Doppler_hz * lambda);
@ -5641,7 +5641,7 @@ int32_t Rtcm::set_DF406(const Gnss_Synchro& gnss_synchro)
} }
if ((sig_ == "2C") && (sys_ == "R")) if ((sig_ == "2C") && (sys_ == "R"))
{ {
//TODO Need to add slot number and freq number to gnss syncro // TODO Need to add slot number and freq number to gnss syncro
lambda = GLONASS_C_M_S / (GLONASS_L2_CA_FREQ_HZ); lambda = GLONASS_C_M_S / (GLONASS_L2_CA_FREQ_HZ);
} }
phrng_m = (gnss_synchro.Carrier_phase_rads / GPS_TWO_PI) * lambda - rough_range_m; phrng_m = (gnss_synchro.Carrier_phase_rads / GPS_TWO_PI) * lambda - rough_range_m;

View File

@ -508,7 +508,7 @@ private:
// Classes for TCP communication // Classes for TCP communication
// //
uint16_t RTCM_port; uint16_t RTCM_port;
//uint16_t RTCM_Station_ID; // uint16_t RTCM_Station_ID;
class Rtcm_Message class Rtcm_Message
{ {
public: public:
@ -718,9 +718,9 @@ private:
if (!ec) if (!ec)
{ {
room_.deliver(read_msg_); room_.deliver(read_msg_);
//std::cout << "Delivered message (session): "; // std::cout << "Delivered message (session): ";
//std::cout.write(read_msg_.body(), read_msg_.body_length()); // std::cout.write(read_msg_.body(), read_msg_.body_length());
//std::cout << std::endl; // std::cout << std::endl;
do_read_message_header(); do_read_message_header();
} }
else else
@ -868,7 +868,7 @@ private:
{ {
std::string message; std::string message;
Rtcm_Message msg; Rtcm_Message msg;
queue_->wait_and_pop(message); //message += '\n'; queue_->wait_and_pop(message); // message += '\n';
if (message == "Goodbye") if (message == "Goodbye")
{ {
break; break;
@ -1417,7 +1417,7 @@ private:
// Content of message header for MSM1, MSM2, MSM3, MSM4, MSM5, MSM6 and MSM7 // Content of message header for MSM1, MSM2, MSM3, MSM4, MSM5, MSM6 and MSM7
std::bitset<1> DF393; std::bitset<1> DF393;
int32_t set_DF393(bool more_messages); //1 indicates that more MSMs follow for given physical time and reference station ID int32_t set_DF393(bool more_messages); // 1 indicates that more MSMs follow for given physical time and reference station ID
std::bitset<64> DF394; std::bitset<64> DF394;
int32_t set_DF394(const std::map<int32_t, Gnss_Synchro>& gnss_synchro); int32_t set_DF394(const std::map<int32_t, Gnss_Synchro>& gnss_synchro);

View File

@ -164,7 +164,7 @@ private:
uint16_t port; uint16_t port;
uint16_t station_id; uint16_t station_id;
int32_t rtcm_dev_descriptor; // RTCM serial device descriptor (i.e. COM port) int32_t rtcm_dev_descriptor; // RTCM serial device descriptor (i.e. COM port)
int32_t init_serial(const std::string& serial_device); //serial port control int32_t init_serial(const std::string& serial_device); // serial port control
void close_serial(); void close_serial();
std::shared_ptr<Rtcm> rtcm; std::shared_ptr<Rtcm> rtcm;
bool Print_Message(const std::string& message); bool Print_Message(const std::string& message);

View File

@ -678,7 +678,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
} }
break; break;
} }
case 'R': //TODO This should be using rtk lib nomenclature case 'R': // TODO This should be using rtk lib nomenclature
{ {
std::string sig_(gnss_observables_iter->second.Signal); std::string sig_(gnss_observables_iter->second.Signal);
// GLONASS GNAV L1 // GLONASS GNAV L1
@ -967,7 +967,7 @@ bool Rtklib_Solver::get_PVT(const std::map<int, Gnss_Synchro> &gnss_observables_
rx_position_and_time(0) = pvt_sol.rr[0]; // [m] rx_position_and_time(0) = pvt_sol.rr[0]; // [m]
rx_position_and_time(1) = pvt_sol.rr[1]; // [m] rx_position_and_time(1) = pvt_sol.rr[1]; // [m]
rx_position_and_time(2) = pvt_sol.rr[2]; // [m] rx_position_and_time(2) = pvt_sol.rr[2]; // [m]
//todo: fix this ambiguity in the RTKLIB units in receiver clock offset! // todo: fix this ambiguity in the RTKLIB units in receiver clock offset!
if (rtk_.opt.mode == PMODE_SINGLE) if (rtk_.opt.mode == PMODE_SINGLE)
{ {
// if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s] // if the RTKLIB solver is set to SINGLE, the dtr is already expressed in [s]

View File

@ -75,7 +75,7 @@ BeidouB1iPcpsAcquisition::BeidouB1iPcpsAcquisition(
acq_parameters_.doppler_max = doppler_max_; acq_parameters_.doppler_max = doppler_max_;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;
@ -102,7 +102,7 @@ BeidouB1iPcpsAcquisition::BeidouB1iPcpsAcquisition(
acq_parameters_.use_automatic_resampler = configuration_->property("GNSS-SDR.use_acquisition_resampler", false); acq_parameters_.use_automatic_resampler = configuration_->property("GNSS-SDR.use_acquisition_resampler", false);
acq_parameters_.resampled_fs = fs_in_; acq_parameters_.resampled_fs = fs_in_;
//--- Find number of samples per spreading code ------------------------- // --- Find number of samples per spreading code -------------------------
code_length_ = static_cast<unsigned int>(std::floor(static_cast<double>(fs_in_) / (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS))); code_length_ = static_cast<unsigned int>(std::floor(static_cast<double>(fs_in_) / (BEIDOU_B1I_CODE_RATE_HZ / BEIDOU_B1I_CODE_LENGTH_CHIPS)));
acq_parameters_.samples_per_ms = static_cast<float>(fs_in_) * 0.001; acq_parameters_.samples_per_ms = static_cast<float>(fs_in_) * 0.001;
acq_parameters_.samples_per_chip = static_cast<unsigned int>(ceil((1.0 / BEIDOU_B1I_CODE_RATE_HZ) * static_cast<float>(acq_parameters_.fs_in))); acq_parameters_.samples_per_chip = static_cast<unsigned int>(ceil((1.0 / BEIDOU_B1I_CODE_RATE_HZ) * static_cast<float>(acq_parameters_.fs_in)));
@ -227,7 +227,7 @@ void BeidouB1iPcpsAcquisition::set_state(int state)
float BeidouB1iPcpsAcquisition::calculate_threshold(float pfa) float BeidouB1iPcpsAcquisition::calculate_threshold(float pfa)
{ {
//Calculate the threshold // Calculate the threshold
uint32_t frequency_bins = 0; uint32_t frequency_bins = 0;
frequency_bins = (2 * doppler_max_ + doppler_step_) / doppler_step_; frequency_bins = (2 * doppler_max_ + doppler_step_) / doppler_step_;
DLOG(INFO) << "Channel " << channel_ << " Pfa = " << pfa; DLOG(INFO) << "Channel " << channel_ << " Pfa = " << pfa;

View File

@ -73,7 +73,7 @@ BeidouB3iPcpsAcquisition::BeidouB3iPcpsAcquisition(
acq_parameters_.doppler_max = doppler_max_; acq_parameters_.doppler_max = doppler_max_;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;
@ -100,7 +100,7 @@ BeidouB3iPcpsAcquisition::BeidouB3iPcpsAcquisition(
acq_parameters_.use_automatic_resampler = configuration_->property("GNSS-SDR.use_acquisition_resampler", false); acq_parameters_.use_automatic_resampler = configuration_->property("GNSS-SDR.use_acquisition_resampler", false);
acq_parameters_.resampled_fs = fs_in_; acq_parameters_.resampled_fs = fs_in_;
//--- Find number of samples per spreading code ------------------------- // --- Find number of samples per spreading code -------------------------
code_length_ = static_cast<unsigned int>(std::floor(static_cast<double>(fs_in_) / (BEIDOU_B3I_CODE_RATE_HZ / BEIDOU_B3I_CODE_LENGTH_CHIPS))); code_length_ = static_cast<unsigned int>(std::floor(static_cast<double>(fs_in_) / (BEIDOU_B3I_CODE_RATE_HZ / BEIDOU_B3I_CODE_LENGTH_CHIPS)));
acq_parameters_.samples_per_ms = static_cast<float>(fs_in_) * 0.001; acq_parameters_.samples_per_ms = static_cast<float>(fs_in_) * 0.001;
acq_parameters_.samples_per_chip = static_cast<unsigned int>(ceil((1.0 / BEIDOU_B3I_CODE_RATE_HZ) * static_cast<float>(acq_parameters_.fs_in))); acq_parameters_.samples_per_chip = static_cast<unsigned int>(ceil((1.0 / BEIDOU_B3I_CODE_RATE_HZ) * static_cast<float>(acq_parameters_.fs_in)));
@ -228,7 +228,7 @@ void BeidouB3iPcpsAcquisition::set_state(int state)
float BeidouB3iPcpsAcquisition::calculate_threshold(float pfa) float BeidouB3iPcpsAcquisition::calculate_threshold(float pfa)
{ {
//Calculate the threshold // Calculate the threshold
unsigned int frequency_bins = 0; unsigned int frequency_bins = 0;
frequency_bins = (2 * doppler_max_ + doppler_step_) / doppler_step_; frequency_bins = (2 * doppler_max_ + doppler_step_) / doppler_step_;
DLOG(INFO) << "Channel " << channel_ << " Pfa = " << pfa; DLOG(INFO) << "Channel " << channel_ << " Pfa = " << pfa;

View File

@ -75,9 +75,9 @@ GalileoE1PcpsAmbiguousAcquisition::GalileoE1PcpsAmbiguousAcquisition(
} }
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
acquire_pilot_ = configuration_->property(role + ".acquire_pilot", false); //will be true in future versions acquire_pilot_ = configuration_->property(role + ".acquire_pilot", false); // will be true in future versions
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;
dump_ = configuration_->property(role + ".dump", false); dump_ = configuration_->property(role + ".dump", false);

View File

@ -66,7 +66,7 @@ GalileoE1PcpsQuickSyncAmbiguousAcquisition::GalileoE1PcpsQuickSyncAmbiguousAcqui
} }
sampled_ms_ = configuration_->property(role + ".coherent_integration_time_ms", 8); sampled_ms_ = configuration_->property(role + ".coherent_integration_time_ms", 8);
/*--- Find number of samples per spreading code (4 ms) -----------------*/ /* --- Find number of samples per spreading code (4 ms) -----------------*/
code_length_ = round( code_length_ = round(
fs_in_ / (GALILEO_E1_CODE_CHIP_RATE_HZ / GALILEO_E1_B_CODE_LENGTH_CHIPS)); fs_in_ / (GALILEO_E1_CODE_CHIP_RATE_HZ / GALILEO_E1_B_CODE_LENGTH_CHIPS));
@ -78,7 +78,7 @@ GalileoE1PcpsQuickSyncAmbiguousAcquisition::GalileoE1PcpsQuickSyncAmbiguousAcqui
out that by making the folding factor smaller we were able to get QuickSync work with out that by making the folding factor smaller we were able to get QuickSync work with
Galileo. Future work should be directed to test this assumption statistically.*/ Galileo. Future work should be directed to test this assumption statistically.*/
//folding_factor_ = static_cast<unsigned int>(ceil(sqrt(log2(code_length_)))); // folding_factor_ = static_cast<unsigned int>(ceil(sqrt(log2(code_length_))));
folding_factor_ = configuration_->property(role + ".folding_factor", 2); folding_factor_ = configuration_->property(role + ".folding_factor", 2);
if (sampled_ms_ % (folding_factor_ * 4) != 0) if (sampled_ms_ % (folding_factor_ * 4) != 0)

View File

@ -78,13 +78,13 @@ GlonassL1CaPcpsAcquisition::GlonassL1CaPcpsAcquisition(
acq_parameters.sampled_ms = sampled_ms_; acq_parameters.sampled_ms = sampled_ms_;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters.bit_transition_flag = bit_transition_flag_; acq_parameters.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters.max_dwells = max_dwells_; acq_parameters.max_dwells = max_dwells_;
dump_filename_ = configuration_->property(role + ".dump_filename", default_dump_filename); dump_filename_ = configuration_->property(role + ".dump_filename", default_dump_filename);
acq_parameters.dump_filename = dump_filename_; acq_parameters.dump_filename = dump_filename_;
//--- Find number of samples per spreading code ------------------------- // --- Find number of samples per spreading code -------------------------
code_length_ = static_cast<unsigned int>(std::round(static_cast<double>(fs_in_) / (GLONASS_L1_CA_CODE_RATE_HZ / GLONASS_L1_CA_CODE_LENGTH_CHIPS))); code_length_ = static_cast<unsigned int>(std::round(static_cast<double>(fs_in_) / (GLONASS_L1_CA_CODE_RATE_HZ / GLONASS_L1_CA_CODE_LENGTH_CHIPS)));
vector_length_ = code_length_ * sampled_ms_; vector_length_ = code_length_ * sampled_ms_;
@ -230,7 +230,7 @@ void GlonassL1CaPcpsAcquisition::set_state(int state)
float GlonassL1CaPcpsAcquisition::calculate_threshold(float pfa) float GlonassL1CaPcpsAcquisition::calculate_threshold(float pfa)
{ {
//Calculate the threshold // Calculate the threshold
unsigned int frequency_bins = 0; unsigned int frequency_bins = 0;
/* /*
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_) for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)

View File

@ -76,14 +76,14 @@ GlonassL2CaPcpsAcquisition::GlonassL2CaPcpsAcquisition(
sampled_ms_ = configuration_->property(role + ".coherent_integration_time_ms", 1); sampled_ms_ = configuration_->property(role + ".coherent_integration_time_ms", 1);
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters.bit_transition_flag = bit_transition_flag_; acq_parameters.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters.max_dwells = max_dwells_; acq_parameters.max_dwells = max_dwells_;
dump_filename_ = configuration_->property(role + ".dump_filename", default_dump_filename); dump_filename_ = configuration_->property(role + ".dump_filename", default_dump_filename);
acq_parameters.dump_filename = dump_filename_; acq_parameters.dump_filename = dump_filename_;
//--- Find number of samples per spreading code ------------------------- // --- Find number of samples per spreading code -------------------------
code_length_ = static_cast<unsigned int>(std::round(static_cast<double>(fs_in_) / (GLONASS_L2_CA_CODE_RATE_HZ / GLONASS_L2_CA_CODE_LENGTH_CHIPS))); code_length_ = static_cast<unsigned int>(std::round(static_cast<double>(fs_in_) / (GLONASS_L2_CA_CODE_RATE_HZ / GLONASS_L2_CA_CODE_LENGTH_CHIPS)));
vector_length_ = code_length_ * sampled_ms_; vector_length_ = code_length_ * sampled_ms_;
@ -229,7 +229,7 @@ void GlonassL2CaPcpsAcquisition::set_state(int state)
float GlonassL2CaPcpsAcquisition::calculate_threshold(float pfa) float GlonassL2CaPcpsAcquisition::calculate_threshold(float pfa)
{ {
//Calculate the threshold // Calculate the threshold
unsigned int frequency_bins = 0; unsigned int frequency_bins = 0;
/* /*
for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_) for (int doppler = (int)(-doppler_max_); doppler <= (int)doppler_max_; doppler += doppler_step_)

View File

@ -79,7 +79,7 @@ GpsL1CaPcpsAcquisition::GpsL1CaPcpsAcquisition(
acq_parameters_.ms_per_code = 1; acq_parameters_.ms_per_code = 1;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;

View File

@ -178,7 +178,7 @@ void GpsL1CaPcpsAcquisitionFineDoppler::connect(boost::shared_ptr<gr::top_block>
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }
@ -187,7 +187,7 @@ void GpsL1CaPcpsAcquisitionFineDoppler::disconnect(boost::shared_ptr<gr::top_blo
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }

View File

@ -67,7 +67,7 @@ GpsL1CaPcpsAssistedAcquisition::GpsL1CaPcpsAssistedAcquisition(
max_dwells_ = configuration->property(role + ".max_dwells", 1); max_dwells_ = configuration->property(role + ".max_dwells", 1);
dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename); dump_filename_ = configuration->property(role + ".dump_filename", default_dump_filename);
//--- Find number of samples per spreading code ------------------------- // --- Find number of samples per spreading code -------------------------
vector_length_ = round(fs_in_ / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)); vector_length_ = round(fs_in_ / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
code_ = std::make_shared<std::complex<float>>(vector_length_); code_ = std::make_shared<std::complex<float>>(vector_length_);
@ -164,7 +164,7 @@ void GpsL1CaPcpsAssistedAcquisition::connect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }
@ -173,7 +173,7 @@ void GpsL1CaPcpsAssistedAcquisition::disconnect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }

View File

@ -73,7 +73,7 @@ GpsL2MPcpsAcquisition::GpsL2MPcpsAcquisition(
acq_parameters_.doppler_max = doppler_max_; acq_parameters_.doppler_max = doppler_max_;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;

View File

@ -74,7 +74,7 @@ GpsL5iPcpsAcquisition::GpsL5iPcpsAcquisition(
acq_parameters_.doppler_max = doppler_max_; acq_parameters_.doppler_max = doppler_max_;
bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false); bit_transition_flag_ = configuration_->property(role + ".bit_transition_flag", false);
acq_parameters_.bit_transition_flag = bit_transition_flag_; acq_parameters_.bit_transition_flag = bit_transition_flag_;
use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); //will be false in future versions use_CFAR_algorithm_flag_ = configuration_->property(role + ".use_CFAR_algorithm", true); // will be false in future versions
acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_; acq_parameters_.use_CFAR_algorithm_flag = use_CFAR_algorithm_flag_;
max_dwells_ = configuration_->property(role + ".max_dwells", 1); max_dwells_ = configuration_->property(role + ".max_dwells", 1);
acq_parameters_.max_dwells = max_dwells_; acq_parameters_.max_dwells = max_dwells_;

View File

@ -344,13 +344,13 @@ int galileo_pcps_8ms_acquisition_cc::general_work(int noutput_items,
<< "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_" << "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_"
<< d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat"; << d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat";
d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary); d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary);
d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); //write directly |abs(x)|^2 in this Doppler bin? d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); // write directly |abs(x)|^2 in this Doppler bin?
d_dump_file.close(); d_dump_file.close();
} }
} }
// 5- Compute the test statistics and compare to the threshold // 5- Compute the test statistics and compare to the threshold
//d_test_statistics = 2 * d_fft_size * d_mag / d_input_power; // d_test_statistics = 2 * d_fft_size * d_mag / d_input_power;
d_test_statistics = d_mag / d_input_power; d_test_statistics = d_mag / d_input_power;
if (d_test_statistics > d_threshold) if (d_test_statistics > d_threshold)

View File

@ -445,7 +445,7 @@ void pcps_acquisition::dump_results(int32_t effective_fft_size)
if (matfp == nullptr) if (matfp == nullptr)
{ {
std::cout << "Unable to create or open Acquisition dump file" << std::endl; std::cout << "Unable to create or open Acquisition dump file" << std::endl;
//acq_parameters.dump = false; // acq_parameters.dump = false;
} }
else else
{ {
@ -722,7 +722,7 @@ void pcps_acquisition::acquisition_core(uint64_t samp_count)
{ {
// take into account the acquisition resampler ratio // take into account the acquisition resampler ratio
d_gnss_synchro->Acq_delay_samples = static_cast<double>(std::fmod(static_cast<float>(indext), acq_parameters.samples_per_code)) * acq_parameters.resampler_ratio; d_gnss_synchro->Acq_delay_samples = static_cast<double>(std::fmod(static_cast<float>(indext), acq_parameters.samples_per_code)) * acq_parameters.resampler_ratio;
d_gnss_synchro->Acq_delay_samples -= static_cast<double>(acq_parameters.resampler_latency_samples); //account the resampler filter latency d_gnss_synchro->Acq_delay_samples -= static_cast<double>(acq_parameters.resampler_latency_samples); // account the resampler filter latency
d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler); d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler);
d_gnss_synchro->Acq_samplestamp_samples = rint(static_cast<double>(samp_count) * acq_parameters.resampler_ratio); d_gnss_synchro->Acq_samplestamp_samples = rint(static_cast<double>(samp_count) * acq_parameters.resampler_ratio);
} }
@ -780,7 +780,7 @@ void pcps_acquisition::acquisition_core(uint64_t samp_count)
{ {
// take into account the acquisition resampler ratio // take into account the acquisition resampler ratio
d_gnss_synchro->Acq_delay_samples = static_cast<double>(std::fmod(static_cast<float>(indext), acq_parameters.samples_per_code)) * acq_parameters.resampler_ratio; d_gnss_synchro->Acq_delay_samples = static_cast<double>(std::fmod(static_cast<float>(indext), acq_parameters.samples_per_code)) * acq_parameters.resampler_ratio;
d_gnss_synchro->Acq_delay_samples -= static_cast<double>(acq_parameters.resampler_latency_samples); //account the resampler filter latency d_gnss_synchro->Acq_delay_samples -= static_cast<double>(acq_parameters.resampler_latency_samples); // account the resampler filter latency
d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler); d_gnss_synchro->Acq_doppler_hz = static_cast<double>(doppler);
d_gnss_synchro->Acq_samplestamp_samples = rint(static_cast<double>(samp_count) * acq_parameters.resampler_ratio); d_gnss_synchro->Acq_samplestamp_samples = rint(static_cast<double>(samp_count) * acq_parameters.resampler_ratio);
d_gnss_synchro->Acq_doppler_step = acq_parameters.doppler_step2; d_gnss_synchro->Acq_doppler_step = acq_parameters.doppler_step2;

View File

@ -148,7 +148,7 @@ pcps_acquisition_fine_doppler_cc::pcps_acquisition_fine_doppler_cc(const Acq_Con
d_positive_acq = 0; d_positive_acq = 0;
d_dump_number = 0; d_dump_number = 0;
d_dump_channel = 0; // this implementation can only produce dumps in channel 0 d_dump_channel = 0; // this implementation can only produce dumps in channel 0
//todo: migrate config parameters to the unified acquisition config class // todo: migrate config parameters to the unified acquisition config class
} }
@ -199,7 +199,7 @@ void pcps_acquisition_fine_doppler_cc::set_local_code(std::complex<float> *code)
{ {
memcpy(d_fft_if->get_inbuf(), code, sizeof(gr_complex) * d_fft_size); memcpy(d_fft_if->get_inbuf(), code, sizeof(gr_complex) * d_fft_size);
d_fft_if->execute(); // We need the FFT of local code d_fft_if->execute(); // We need the FFT of local code
//Conjugate the local code // Conjugate the local code
volk_32fc_conjugate_32fc(d_fft_codes, d_fft_if->get_outbuf(), d_fft_size); volk_32fc_conjugate_32fc(d_fft_codes, d_fft_if->get_outbuf(), d_fft_size);
} }
@ -223,7 +223,7 @@ void pcps_acquisition_fine_doppler_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = d_gnuradio_forecast_samples; //set the required available samples in each call ninput_items_required[0] = d_gnuradio_forecast_samples; // set the required available samples in each call
} }
} }
@ -233,7 +233,7 @@ void pcps_acquisition_fine_doppler_cc::reset_grid()
d_well_count = 0; d_well_count = 0;
for (int i = 0; i < d_num_doppler_points; i++) for (int i = 0; i < d_num_doppler_points; i++)
{ {
//todo: use memset here // todo: use memset here
for (unsigned int j = 0; j < d_fft_size; j++) for (unsigned int j = 0; j < d_fft_size; j++)
{ {
d_grid_data[i][j] = 0.0; d_grid_data[i][j] = 0.0;
@ -271,7 +271,7 @@ double pcps_acquisition_fine_doppler_cc::compute_CAF()
// Look for correlation peaks in the results ============================== // Look for correlation peaks in the results ==============================
// Find the highest peak and compare it to the second highest peak // Find the highest peak and compare it to the second highest peak
// The second peak is chosen not closer than 1 chip to the highest peak // The second peak is chosen not closer than 1 chip to the highest peak
//--- Find the correlation peak and the carrier frequency -------------- // --- Find the correlation peak and the carrier frequency --------------
for (int i = 0; i < d_num_doppler_points; i++) for (int i = 0; i < d_num_doppler_points; i++)
{ {
volk_gnsssdr_32f_index_max_32u(&tmp_intex_t, d_grid_data[i].data(), d_fft_size); volk_gnsssdr_32f_index_max_32u(&tmp_intex_t, d_grid_data[i].data(), d_fft_size);
@ -316,7 +316,7 @@ double pcps_acquisition_fine_doppler_cc::compute_CAF()
} }
while (idx != excludeRangeIndex2); while (idx != excludeRangeIndex2);
//--- Find the second highest correlation peak in the same freq. bin --- // --- Find the second highest correlation peak in the same freq. bin ---
volk_gnsssdr_32f_index_max_32u(&tmp_intex_t, d_grid_data[index_doppler].data(), d_fft_size); volk_gnsssdr_32f_index_max_32u(&tmp_intex_t, d_grid_data[index_doppler].data(), d_fft_size);
float secondPeak = d_grid_data[index_doppler][tmp_intex_t]; float secondPeak = d_grid_data[index_doppler][tmp_intex_t];
@ -335,7 +335,7 @@ double pcps_acquisition_fine_doppler_cc::compute_CAF()
float pcps_acquisition_fine_doppler_cc::estimate_input_power(gr_vector_const_void_star &input_items) float pcps_acquisition_fine_doppler_cc::estimate_input_power(gr_vector_const_void_star &input_items)
{ {
const auto *in = reinterpret_cast<const gr_complex *>(input_items[0]); //Get the input samples pointer const auto *in = reinterpret_cast<const gr_complex *>(input_items[0]); // Get the input samples pointer
// Compute the input signal power estimation // Compute the input signal power estimation
float power = 0; float power = 0;
volk_32fc_magnitude_squared_32f(d_magnitude, in, d_fft_size); volk_32fc_magnitude_squared_32f(d_magnitude, in, d_fft_size);
@ -348,7 +348,7 @@ float pcps_acquisition_fine_doppler_cc::estimate_input_power(gr_vector_const_voi
int pcps_acquisition_fine_doppler_cc::compute_and_accumulate_grid(gr_vector_const_void_star &input_items) int pcps_acquisition_fine_doppler_cc::compute_and_accumulate_grid(gr_vector_const_void_star &input_items)
{ {
// initialize acquisition algorithm // initialize acquisition algorithm
const auto *in = reinterpret_cast<const gr_complex *>(input_items[0]); //Get the input samples pointer const auto *in = reinterpret_cast<const gr_complex *>(input_items[0]); // Get the input samples pointer
DLOG(INFO) << "Channel: " << d_channel DLOG(INFO) << "Channel: " << d_channel
<< " , doing acquisition of satellite: " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN << " , doing acquisition of satellite: " << d_gnss_synchro->System << " " << d_gnss_synchro->PRN
@ -378,13 +378,13 @@ int pcps_acquisition_fine_doppler_cc::compute_and_accumulate_grid(gr_vector_cons
// save the grid matrix delay file // save the grid matrix delay file
volk_32fc_magnitude_squared_32f(p_tmp_vector, d_ifft->get_outbuf(), d_fft_size); volk_32fc_magnitude_squared_32f(p_tmp_vector, d_ifft->get_outbuf(), d_fft_size);
//accumulate grid values // accumulate grid values
volk_32f_x2_add_32f(d_grid_data[doppler_index].data(), d_grid_data[doppler_index].data(), p_tmp_vector, d_fft_size); volk_32f_x2_add_32f(d_grid_data[doppler_index].data(), d_grid_data[doppler_index].data(), p_tmp_vector, d_fft_size);
} }
volk_gnsssdr_free(p_tmp_vector); volk_gnsssdr_free(p_tmp_vector);
return d_fft_size; return d_fft_size;
//debug // debug
// std::cout << "iff=["; // std::cout << "iff=[";
// for (int n = 0; n < d_fft_size; n++) // for (int n = 0; n < d_fft_size; n++)
// { // {
@ -401,13 +401,13 @@ int pcps_acquisition_fine_doppler_cc::estimate_Doppler()
int zero_padding_factor = 8; int zero_padding_factor = 8;
int prn_replicas = 10; int prn_replicas = 10;
int signal_samples = prn_replicas * d_fft_size; int signal_samples = prn_replicas * d_fft_size;
//int fft_size_extended = nextPowerOf2(signal_samples * zero_padding_factor); // int fft_size_extended = nextPowerOf2(signal_samples * zero_padding_factor);
int fft_size_extended = signal_samples * zero_padding_factor; int fft_size_extended = signal_samples * zero_padding_factor;
auto fft_operator = std::make_shared<gr::fft::fft_complex>(fft_size_extended, true); auto fft_operator = std::make_shared<gr::fft::fft_complex>(fft_size_extended, true);
//zero padding the entire vector // zero padding the entire vector
std::fill_n(fft_operator->get_inbuf(), fft_size_extended, gr_complex(0.0, 0.0)); std::fill_n(fft_operator->get_inbuf(), fft_size_extended, gr_complex(0.0, 0.0));
//1. generate local code aligned with the acquisition code phase estimation // 1. generate local code aligned with the acquisition code phase estimation
auto *code_replica = static_cast<gr_complex *>(volk_gnsssdr_malloc(signal_samples * sizeof(gr_complex), volk_gnsssdr_get_alignment())); auto *code_replica = static_cast<gr_complex *>(volk_gnsssdr_malloc(signal_samples * sizeof(gr_complex), volk_gnsssdr_get_alignment()));
gps_l1_ca_code_gen_complex_sampled(gsl::span<gr_complex>(code_replica, signal_samples * sizeof(gr_complex)), d_gnss_synchro->PRN, d_fs_in, 0); gps_l1_ca_code_gen_complex_sampled(gsl::span<gr_complex>(code_replica, signal_samples * sizeof(gr_complex)), d_gnss_synchro->PRN, d_fs_in, 0);
@ -424,7 +424,7 @@ int pcps_acquisition_fine_doppler_cc::estimate_Doppler()
{ {
memcpy(&code_replica[(n + 1) * d_fft_size], code_replica, d_fft_size * sizeof(gr_complex)); memcpy(&code_replica[(n + 1) * d_fft_size], code_replica, d_fft_size * sizeof(gr_complex));
} }
//2. Perform code wipe-off // 2. Perform code wipe-off
volk_32fc_x2_multiply_32fc(fft_operator->get_inbuf(), d_10_ms_buffer, code_replica, signal_samples); volk_32fc_x2_multiply_32fc(fft_operator->get_inbuf(), d_10_ms_buffer, code_replica, signal_samples);
// 3. Perform the FFT (zero padded!) // 3. Perform the FFT (zero padded!)
@ -438,7 +438,7 @@ int pcps_acquisition_fine_doppler_cc::estimate_Doppler()
uint32_t tmp_index_freq = 0; uint32_t tmp_index_freq = 0;
volk_gnsssdr_32f_index_max_32u(&tmp_index_freq, p_tmp_vector, fft_size_extended); volk_gnsssdr_32f_index_max_32u(&tmp_index_freq, p_tmp_vector, fft_size_extended);
//case even // case even
int counter = 0; int counter = 0;
auto fftFreqBins = std::vector<float>(fft_size_extended); auto fftFreqBins = std::vector<float>(fft_size_extended);
@ -458,7 +458,7 @@ int pcps_acquisition_fine_doppler_cc::estimate_Doppler()
if (std::abs(fftFreqBins[tmp_index_freq] - d_gnss_synchro->Acq_doppler_hz) < 1000) if (std::abs(fftFreqBins[tmp_index_freq] - d_gnss_synchro->Acq_doppler_hz) < 1000)
{ {
d_gnss_synchro->Acq_doppler_hz = static_cast<double>(fftFreqBins[tmp_index_freq]); d_gnss_synchro->Acq_doppler_hz = static_cast<double>(fftFreqBins[tmp_index_freq]);
//std::cout << "FFT maximum present at " << fftFreqBins[tmp_index_freq] << " [Hz]" << std::endl; // std::cout << "FFT maximum present at " << fftFreqBins[tmp_index_freq] << " [Hz]" << std::endl;
} }
else else
{ {
@ -483,7 +483,7 @@ bool pcps_acquisition_fine_doppler_cc::start()
void pcps_acquisition_fine_doppler_cc::set_state(int state) void pcps_acquisition_fine_doppler_cc::set_state(int state)
{ {
//gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler // gr::thread::scoped_lock lock(d_setlock); // require mutex with work function called by the scheduler
d_state = state; d_state = state;
if (d_state == 1) if (d_state == 1)
@ -557,11 +557,11 @@ int pcps_acquisition_fine_doppler_cc::general_work(int noutput_items,
d_test_statistics = compute_CAF(); d_test_statistics = compute_CAF();
if (d_test_statistics > d_threshold) if (d_test_statistics > d_threshold)
{ {
d_state = 3; //perform fine doppler estimation d_state = 3; // perform fine doppler estimation
} }
else else
{ {
d_state = 5; //negative acquisition d_state = 5; // negative acquisition
d_n_samples_in_buffer = 0; d_n_samples_in_buffer = 0;
} }
@ -584,7 +584,7 @@ int pcps_acquisition_fine_doppler_cc::general_work(int noutput_items,
d_sample_counter += static_cast<uint64_t>(samples_remaining); // sample counter d_sample_counter += static_cast<uint64_t>(samples_remaining); // sample counter
consume_each(samples_remaining); consume_each(samples_remaining);
} }
estimate_Doppler(); //disabled in repo estimate_Doppler(); // disabled in repo
d_n_samples_in_buffer = 0; d_n_samples_in_buffer = 0;
d_state = 4; d_state = 4;
} }

View File

@ -143,8 +143,7 @@ void pcps_acquisition_fpga::send_positive_acquisition()
<< ", input signal power " << d_input_power << ", input signal power " << d_input_power
<< ", Assist doppler_center " << d_doppler_center; << ", Assist doppler_center " << d_doppler_center;
// the channel FSM is set, so, notify it directly the positive acquisition to minimize delays
//the channel FSM is set, so, notify it directly the positive acquisition to minimize delays
d_channel_fsm.lock()->Event_valid_acquisition(); d_channel_fsm.lock()->Event_valid_acquisition();
} }
@ -220,7 +219,7 @@ void pcps_acquisition_fpga::acquisition_core(uint32_t num_doppler_bins, uint32_t
if (d_downsampling_factor > 1) if (d_downsampling_factor > 1)
{ {
d_gnss_synchro->Acq_delay_samples = static_cast<double>(d_downsampling_factor * (indext)); d_gnss_synchro->Acq_delay_samples = static_cast<double>(d_downsampling_factor * (indext));
d_gnss_synchro->Acq_samplestamp_samples = d_downsampling_factor * static_cast<uint64_t>(d_sample_counter) - static_cast<uint64_t>(44); //33; //41; //+ 81*0.5; // delay due to the downsampling filter in the acquisition d_gnss_synchro->Acq_samplestamp_samples = d_downsampling_factor * static_cast<uint64_t>(d_sample_counter) - static_cast<uint64_t>(44); // 33; // 41; // + 81*0.5; // delay due to the downsampling filter in the acquisition
} }
else else
{ {
@ -239,9 +238,7 @@ void pcps_acquisition_fpga::acquisition_core(uint32_t num_doppler_bins, uint32_t
void pcps_acquisition_fpga::set_active(bool active) void pcps_acquisition_fpga::set_active(bool active)
{ {
d_active = active; d_active = active;
d_input_power = 0.0; d_input_power = 0.0;
d_mag = 0.0; d_mag = 0.0;
DLOG(INFO) << "Channel: " << d_channel DLOG(INFO) << "Channel: " << d_channel

View File

@ -63,7 +63,7 @@ typedef struct
uint32_t select_queue_Fpga; uint32_t select_queue_Fpga;
std::string device_name; std::string device_name;
uint32_t* all_fft_codes; // pointer to memory that contains all the code ffts uint32_t* all_fft_codes; // pointer to memory that contains all the code ffts
//float downsampling_factor; // float downsampling_factor;
uint32_t downsampling_factor; uint32_t downsampling_factor;
uint32_t total_block_exp; uint32_t total_block_exp;
uint32_t excludelimit; uint32_t excludelimit;

View File

@ -164,7 +164,7 @@ void pcps_assisted_acquisition_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = d_gnuradio_forecast_samples; //set the required available samples in each call ninput_items_required[0] = d_gnuradio_forecast_samples; // set the required available samples in each call
} }
} }
@ -174,7 +174,7 @@ void pcps_assisted_acquisition_cc::get_assistance()
Gps_Acq_Assist gps_acq_assisistance; Gps_Acq_Assist gps_acq_assisistance;
if (global_gps_acq_assist_map.read(this->d_gnss_synchro->PRN, gps_acq_assisistance) == true) if (global_gps_acq_assist_map.read(this->d_gnss_synchro->PRN, gps_acq_assisistance) == true)
{ {
//TODO: use the LO tolerance here // TODO: use the LO tolerance here
if (gps_acq_assisistance.dopplerUncertainty >= 1000) if (gps_acq_assisistance.dopplerUncertainty >= 1000)
{ {
d_doppler_max = gps_acq_assisistance.d_Doppler0 + gps_acq_assisistance.dopplerUncertainty * 2; d_doppler_max = gps_acq_assisistance.d_Doppler0 + gps_acq_assisistance.dopplerUncertainty * 2;

View File

@ -370,7 +370,7 @@ int pcps_cccwsr_acquisition_cc::general_work(int noutput_items,
} }
// 5- Compute the test statistics and compare to the threshold // 5- Compute the test statistics and compare to the threshold
//d_test_statistics = 2 * d_fft_size * d_mag / d_input_power; // d_test_statistics = 2 * d_fft_size * d_mag / d_input_power;
d_test_statistics = d_mag / d_input_power; d_test_statistics = d_mag / d_input_power;
// 6- Declare positive or negative acquisition using a message port // 6- Declare positive or negative acquisition using a message port

View File

@ -49,7 +49,7 @@
*/ */
#include "pcps_opencl_acquisition_cc.h" #include "pcps_opencl_acquisition_cc.h"
#include "GPS_L1_CA.h" //GPS_TWO_PI #include "GPS_L1_CA.h" // GPS_TWO_PI
#include "opencl/fft_base_kernels.h" #include "opencl/fft_base_kernels.h"
#include "opencl/fft_internal.h" #include "opencl/fft_internal.h"
#include <glog/logging.h> #include <glog/logging.h>
@ -425,7 +425,7 @@ void pcps_opencl_acquisition_cc::acquisition_core_volk()
d_gnss_synchro->Acq_doppler_step = d_doppler_step; d_gnss_synchro->Acq_doppler_step = d_doppler_step;
// 5- Compute the test statistics and compare to the threshold // 5- Compute the test statistics and compare to the threshold
//d_test_statistics = 2 * d_fft_size * d_mag / d_input_power; // d_test_statistics = 2 * d_fft_size * d_mag / d_input_power;
d_test_statistics = d_mag / d_input_power; d_test_statistics = d_mag / d_input_power;
} }
} }
@ -440,7 +440,7 @@ void pcps_opencl_acquisition_cc::acquisition_core_volk()
<< "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_" << "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_"
<< d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat"; << d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat";
d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary); d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary);
d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); //write directly |abs(x)|^2 in this Doppler bin? d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); // write directly |abs(x)|^2 in this Doppler bin?
d_dump_file.close(); d_dump_file.close();
} }
} }
@ -481,7 +481,7 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
int doppler; int doppler;
uint32_t indext = 0; uint32_t indext = 0;
float magt = 0.0; float magt = 0.0;
float fft_normalization_factor = (static_cast<float>(d_fft_size_pow2) * static_cast<float>(d_fft_size)); //This works, but I am not sure why. float fft_normalization_factor = (static_cast<float>(d_fft_size_pow2) * static_cast<float>(d_fft_size)); // This works, but I am not sure why.
uint64_t samplestamp = d_sample_counter_buffer[d_well_count]; uint64_t samplestamp = d_sample_counter_buffer[d_well_count];
d_input_power = 0.0; d_input_power = 0.0;
@ -520,9 +520,9 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
// Multiply input signal with doppler wipe-off // Multiply input signal with doppler wipe-off
kernel = cl::Kernel(d_cl_program, "mult_vectors"); kernel = cl::Kernel(d_cl_program, "mult_vectors");
kernel.setArg(0, *d_cl_buffer_in); //input 1 kernel.setArg(0, *d_cl_buffer_in); // input 1
kernel.setArg(1, *d_cl_buffer_grid_doppler_wipeoffs[doppler_index]); //input 2 kernel.setArg(1, *d_cl_buffer_grid_doppler_wipeoffs[doppler_index]); // input 2
kernel.setArg(2, *d_cl_buffer_1); //output kernel.setArg(2, *d_cl_buffer_1); // output
d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size), d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size),
cl::NullRange); cl::NullRange);
@ -536,9 +536,9 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
// Multiply carrier wiped--off, Fourier transformed incoming signal // Multiply carrier wiped--off, Fourier transformed incoming signal
// with the local FFT'd code reference // with the local FFT'd code reference
kernel = cl::Kernel(d_cl_program, "mult_vectors"); kernel = cl::Kernel(d_cl_program, "mult_vectors");
kernel.setArg(0, *d_cl_buffer_2); //input 1 kernel.setArg(0, *d_cl_buffer_2); // input 1
kernel.setArg(1, *d_cl_buffer_fft_codes); //input 2 kernel.setArg(1, *d_cl_buffer_fft_codes); // input 2
kernel.setArg(2, *d_cl_buffer_2); //output kernel.setArg(2, *d_cl_buffer_2); // output
d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size_pow2), d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size_pow2),
cl::NullRange); cl::NullRange);
@ -549,8 +549,8 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
// Compute magnitude // Compute magnitude
kernel = cl::Kernel(d_cl_program, "magnitude_squared"); kernel = cl::Kernel(d_cl_program, "magnitude_squared");
kernel.setArg(0, *d_cl_buffer_2); //input 1 kernel.setArg(0, *d_cl_buffer_2); // input 1
kernel.setArg(1, *d_cl_buffer_magnitude); //output kernel.setArg(1, *d_cl_buffer_magnitude); // output
d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size), d_cl_queue->enqueueNDRangeKernel(kernel, cl::NullRange, cl::NDRange(d_fft_size),
cl::NullRange); cl::NullRange);
@ -586,7 +586,7 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
d_gnss_synchro->Acq_doppler_step = d_doppler_step; d_gnss_synchro->Acq_doppler_step = d_doppler_step;
// 5- Compute the test statistics and compare to the threshold // 5- Compute the test statistics and compare to the threshold
//d_test_statistics = 2 * d_fft_size * d_mag / d_input_power; // d_test_statistics = 2 * d_fft_size * d_mag / d_input_power;
d_test_statistics = d_mag / d_input_power; d_test_statistics = d_mag / d_input_power;
} }
} }
@ -601,7 +601,7 @@ void pcps_opencl_acquisition_cc::acquisition_core_opencl()
<< "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_" << "_" << d_gnss_synchro->Signal[0] << d_gnss_synchro->Signal[1] << "_sat_"
<< d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat"; << d_gnss_synchro->PRN << "_doppler_" << doppler << ".dat";
d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary); d_dump_file.open(filename.str().c_str(), std::ios::out | std::ios::binary);
d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); //write directly |abs(x)|^2 in this Doppler bin? d_dump_file.write(reinterpret_cast<char *>(d_ifft->get_outbuf()), n); // write directly |abs(x)|^2 in this Doppler bin?
d_dump_file.close(); d_dump_file.close();
} }
} }

View File

@ -156,7 +156,7 @@ void Fpga_Acquisition::run_acquisition()
{ {
// enable interrupts // enable interrupts
int32_t reenable = 1; int32_t reenable = 1;
//int32_t disable_int = 0; // int32_t disable_int = 0;
ssize_t nbytes = TEMP_FAILURE_RETRY(write(d_fd, reinterpret_cast<void *>(&reenable), sizeof(int32_t))); ssize_t nbytes = TEMP_FAILURE_RETRY(write(d_fd, reinterpret_cast<void *>(&reenable), sizeof(int32_t)));
if (nbytes != sizeof(int32_t)) if (nbytes != sizeof(int32_t))
{ {
@ -207,7 +207,7 @@ void Fpga_Acquisition::set_doppler_sweep(uint32_t num_sweeps, uint32_t doppler_s
void Fpga_Acquisition::configure_acquisition() void Fpga_Acquisition::configure_acquisition()
{ {
//Fpga_Acquisition::(); // Fpga_Acquisition::();
d_map_base[0] = d_select_queue; d_map_base[0] = d_select_queue;
d_map_base[1] = d_vector_length; d_map_base[1] = d_vector_length;
d_map_base[2] = d_nsamples; d_map_base[2] = d_nsamples;
@ -265,7 +265,7 @@ void Fpga_Acquisition::close_device()
void Fpga_Acquisition::reset_acquisition() void Fpga_Acquisition::reset_acquisition()
{ {
//printf("============ resetting the hw now from the acquisition ==============="); // printf("============ resetting the hw now from the acquisition ===============");
d_map_base[8] = RESET_ACQUISITION; // writing a 2 to d_map_base[8] resets the acquisition. This causes a reset of all d_map_base[8] = RESET_ACQUISITION; // writing a 2 to d_map_base[8] resets the acquisition. This causes a reset of all
// the FPGA HW modules including the multicorrelators // the FPGA HW modules including the multicorrelators
} }

View File

@ -62,12 +62,12 @@ void ArraySignalConditioner::connect(gr::top_block_sptr top_block)
LOG(WARNING) << "Array Signal conditioner already connected internally"; LOG(WARNING) << "Array Signal conditioner already connected internally";
return; return;
} }
//data_type_adapt_->connect(top_block); // data_type_adapt_->connect(top_block);
in_filt_->connect(top_block); in_filt_->connect(top_block);
res_->connect(top_block); res_->connect(top_block);
//top_block->connect(data_type_adapt_->get_right_block(), 0, in_filt_->get_left_block(), 0); // top_block->connect(data_type_adapt_->get_right_block(), 0, in_filt_->get_left_block(), 0);
//DLOG(INFO) << "data_type_adapter -> input_filter"; // DLOG(INFO) << "data_type_adapter -> input_filter";
top_block->connect(in_filt_->get_right_block(), 0, top_block->connect(in_filt_->get_right_block(), 0,
res_->get_left_block(), 0); res_->get_left_block(), 0);
@ -86,12 +86,12 @@ void ArraySignalConditioner::disconnect(gr::top_block_sptr top_block)
return; return;
} }
//top_block->disconnect(data_type_adapt_->get_right_block(), 0, // top_block->disconnect(data_type_adapt_->get_right_block(), 0,
// in_filt_->get_left_block(), 0); // in_filt_->get_left_block(), 0);
top_block->disconnect(in_filt_->get_right_block(), 0, top_block->disconnect(in_filt_->get_right_block(), 0,
res_->get_left_block(), 0); res_->get_left_block(), 0);
//data_type_adapt_->disconnect(top_block); // data_type_adapt_->disconnect(top_block);
in_filt_->disconnect(top_block); in_filt_->disconnect(top_block);
res_->disconnect(top_block); res_->disconnect(top_block);
@ -101,7 +101,7 @@ void ArraySignalConditioner::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr ArraySignalConditioner::get_left_block() gr::basic_block_sptr ArraySignalConditioner::get_left_block()
{ {
//return data_type_adapt_->get_left_block(); // return data_type_adapt_->get_left_block();
return in_filt_->get_left_block(); return in_filt_->get_left_block();
} }

View File

@ -124,29 +124,29 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration
LOG(INFO) << "Created freq_xlating_fir_filter with " << taps_.size() << " taps"; LOG(INFO) << "Created freq_xlating_fir_filter with " << taps_.size() << " taps";
if ((taps_item_type_ == "float") && (input_item_type_ == "gr_complex") && (output_item_type_ == "gr_complex")) if ((taps_item_type_ == "float") && (input_item_type_ == "gr_complex") && (output_item_type_ == "gr_complex"))
{ {
item_size = sizeof(gr_complex); //output item_size = sizeof(gr_complex); // output
input_size_ = sizeof(gr_complex); //input input_size_ = sizeof(gr_complex); // input
freq_xlating_fir_filter_ccf_ = gr::filter::freq_xlating_fir_filter_ccf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_ccf_ = gr::filter::freq_xlating_fir_filter_ccf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_ccf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_ccf_->unique_id() << ")";
} }
else if ((taps_item_type_ == "float") && (input_item_type_ == "float") && (output_item_type_ == "gr_complex")) else if ((taps_item_type_ == "float") && (input_item_type_ == "float") && (output_item_type_ == "gr_complex"))
{ {
item_size = sizeof(gr_complex); item_size = sizeof(gr_complex);
input_size_ = sizeof(float); //input input_size_ = sizeof(float); // input
freq_xlating_fir_filter_fcf_ = gr::filter::freq_xlating_fir_filter_fcf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_fcf_ = gr::filter::freq_xlating_fir_filter_fcf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_fcf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_fcf_->unique_id() << ")";
} }
else if ((taps_item_type_ == "float") && (input_item_type_ == "short") && (output_item_type_ == "gr_complex")) else if ((taps_item_type_ == "float") && (input_item_type_ == "short") && (output_item_type_ == "gr_complex"))
{ {
item_size = sizeof(gr_complex); item_size = sizeof(gr_complex);
input_size_ = sizeof(int16_t); //input input_size_ = sizeof(int16_t); // input
freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")";
} }
else if ((taps_item_type_ == "float") && (input_item_type_ == "short") && (output_item_type_ == "cshort")) else if ((taps_item_type_ == "float") && (input_item_type_ == "short") && (output_item_type_ == "cshort"))
{ {
item_size = sizeof(lv_16sc_t); item_size = sizeof(lv_16sc_t);
input_size_ = sizeof(int16_t); //input input_size_ = sizeof(int16_t); // input
freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")";
complex_to_float_ = gr::blocks::complex_to_float::make(); complex_to_float_ = gr::blocks::complex_to_float::make();
@ -157,7 +157,7 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration
else if ((taps_item_type_ == "float") && (input_item_type_ == "byte") && (output_item_type_ == "gr_complex")) else if ((taps_item_type_ == "float") && (input_item_type_ == "byte") && (output_item_type_ == "gr_complex"))
{ {
item_size = sizeof(gr_complex); item_size = sizeof(gr_complex);
input_size_ = sizeof(int8_t); //input input_size_ = sizeof(int8_t); // input
gr_char_to_short_ = gr::blocks::char_to_short::make(); gr_char_to_short_ = gr::blocks::char_to_short::make();
freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")";
@ -165,7 +165,7 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration
else if ((taps_item_type_ == "float") && (input_item_type_ == "byte") && (output_item_type_ == "cbyte")) else if ((taps_item_type_ == "float") && (input_item_type_ == "byte") && (output_item_type_ == "cbyte"))
{ {
item_size = sizeof(lv_8sc_t); item_size = sizeof(lv_8sc_t);
input_size_ = sizeof(int8_t); //input input_size_ = sizeof(int8_t); // input
gr_char_to_short_ = gr::blocks::char_to_short::make(); gr_char_to_short_ = gr::blocks::char_to_short::make();
freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_); freq_xlating_fir_filter_scf_ = gr::filter::freq_xlating_fir_filter_scf::make(decimation_factor_, taps_, intermediate_freq_, sampling_freq_);
DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")"; DLOG(INFO) << "input_filter(" << freq_xlating_fir_filter_scf_->unique_id() << ")";
@ -174,8 +174,8 @@ FreqXlatingFirFilter::FreqXlatingFirFilter(ConfigurationInterface* configuration
else else
{ {
LOG(ERROR) << " Unknown input filter input/output item type conversion"; LOG(ERROR) << " Unknown input filter input/output item type conversion";
item_size = sizeof(gr_complex); //avoids uninitialization item_size = sizeof(gr_complex); // avoids uninitialization
input_size_ = sizeof(gr_complex); //avoids uninitialization input_size_ = sizeof(gr_complex); // avoids uninitialization
} }
if (dump_) if (dump_)

View File

@ -63,15 +63,15 @@ PulseBlankingFilter::PulseBlankingFilter(ConfigurationInterface* configuration,
int n_segments_reset = config_->property(role_ + ".segments_reset", default_n_segments_reset); int n_segments_reset = config_->property(role_ + ".segments_reset", default_n_segments_reset);
if (input_item_type_ == "gr_complex") if (input_item_type_ == "gr_complex")
{ {
item_size = sizeof(gr_complex); //output item_size = sizeof(gr_complex); // output
input_size_ = sizeof(gr_complex); //input input_size_ = sizeof(gr_complex); // input
pulse_blanking_cc_ = make_pulse_blanking_cc(pfa, length_, n_segments_est, n_segments_reset); pulse_blanking_cc_ = make_pulse_blanking_cc(pfa, length_, n_segments_est, n_segments_reset);
} }
else else
{ {
LOG(ERROR) << " Unknown input filter input/output item type conversion"; LOG(ERROR) << " Unknown input filter input/output item type conversion";
item_size = sizeof(gr_complex); //avoids uninitialization item_size = sizeof(gr_complex); // avoids uninitialization
input_size_ = sizeof(gr_complex); //avoids uninitialization input_size_ = sizeof(gr_complex); // avoids uninitialization
} }
double default_if = 0.0; double default_if = 0.0;
double if_aux = config_->property(role_ + ".if", default_if); double if_aux = config_->property(role_ + ".if", default_if);

View File

@ -62,7 +62,7 @@ int beamformer::work(int noutput_items, gr_vector_const_void_star &input_items,
// gr_complex *ch8 = (gr_complex *) input_items[7]; // gr_complex *ch8 = (gr_complex *) input_items[7];
// NON-VOLK beamforming operation // NON-VOLK beamforming operation
//TODO: Implement VOLK SIMD-accelerated beamformer! // TODO: Implement VOLK SIMD-accelerated beamformer!
gr_complex sum; gr_complex sum;
for (int n = 0; n < noutput_items; n++) for (int n = 0; n < noutput_items; n++)
{ {

View File

@ -71,7 +71,7 @@ DEFINE_int32(max_carrier_lock_fail, 5000, "Maximum number of carrier lock failur
DEFINE_int32(max_lock_fail, 50, "Maximum number of code lock failures before dropping a satellite."); DEFINE_int32(max_lock_fail, 50, "Maximum number of code lock failures before dropping a satellite.");
//cos(2xError_angle)=0.7 -> Error_angle=22 deg // cos(2xError_angle)=0.7 -> Error_angle=22 deg
DEFINE_double(carrier_lock_th, 0.7, "Carrier lock threshold (in rad)."); DEFINE_double(carrier_lock_th, 0.7, "Carrier lock threshold (in rad).");
DEFINE_string(RINEX_version, "-", "If defined, specifies the RINEX version (2.11 or 3.02). Overrides the configuration file."); DEFINE_string(RINEX_version, "-", "If defined, specifies the RINEX version (2.11 or 3.02). Overrides the configuration file.");

View File

@ -1323,9 +1323,9 @@ const int STRFMT_SP3 = 16; /* stream format: SP3 */
const int STRFMT_RNXCLK = 17; /* stream format: RINEX CLK */ const int STRFMT_RNXCLK = 17; /* stream format: RINEX CLK */
const int STRFMT_SBAS = 18; /* stream format: SBAS messages */ const int STRFMT_SBAS = 18; /* stream format: SBAS messages */
const int STRFMT_NMEA = 19; /* stream format: NMEA 0183 */ const int STRFMT_NMEA = 19; /* stream format: NMEA 0183 */
//const solopt_t solopt_default; /* default solution output options */ // const solopt_t solopt_default; /* default solution output options */
const int MAXSTRRTK = 8; /* max number of stream in RTK server */ const int MAXSTRRTK = 8; /* max number of stream in RTK server */
#endif #endif // GNSS_SDR_RTKLIB_H_

View File

@ -1007,8 +1007,8 @@ int satpos(gtime_t time, gtime_t teph, int sat, int ephopt,
{ {
return 1; return 1;
} }
//TODO: enable lex // TODO: enable lex
//case EPHOPT_LEX : // case EPHOPT_LEX :
// if (!lexeph2pos(time, sat, nav, rs, dts, var)) break; else return 1; // if (!lexeph2pos(time, sat, nav, rs, dts, var)) break; else return 1;
} }
*svh = -1; *svh = -1;

View File

@ -77,7 +77,7 @@ geph_t *selgeph(gtime_t time, int sat, int iode, const nav_t *nav);
seph_t *selseph(gtime_t time, int sat, const nav_t *nav); seph_t *selseph(gtime_t time, int sat, const nav_t *nav);
int ephclk(gtime_t time, gtime_t teph, int sat, const nav_t *nav, int ephclk(gtime_t time, gtime_t teph, int sat, const nav_t *nav,
double *dts); double *dts);
//satellite position and clock by broadcast ephemeris // satellite position and clock by broadcast ephemeris
int ephpos(gtime_t time, gtime_t teph, int sat, const nav_t *nav, int ephpos(gtime_t time, gtime_t teph, int sat, const nav_t *nav,
int iode, double *rs, double *dts, double *var, int *svh); int iode, double *rs, double *dts, double *var, int *svh);
int satpos_sbas(gtime_t time, gtime_t teph, int sat, const nav_t *nav, int satpos_sbas(gtime_t time, gtime_t teph, int sat, const nav_t *nav,

View File

@ -151,10 +151,10 @@ double prange(const obsd_t *obs, const nav_t *nav, const double *azel,
double P1_C1 = 0.0; double P1_C1 = 0.0;
double P2_C2 = 0.0; double P2_C2 = 0.0;
// Intersignal corrections (m). See GPS IS-200 CNAV message // Intersignal corrections (m). See GPS IS-200 CNAV message
//double ISCl1 = 0.0; // double ISCl1 = 0.0;
double ISCl2 = 0.0; double ISCl2 = 0.0;
double ISCl5i = 0.0; double ISCl5i = 0.0;
//double ISCl5q = 0.0; // double ISCl5q = 0.0;
double gamma_ = 0.0; double gamma_ = 0.0;
int i = 0; int i = 0;
int j = 1; int j = 1;
@ -234,7 +234,7 @@ double prange(const obsd_t *obs, const nav_t *nav, const double *azel,
// ISCl5q = getiscl5q(obs->sat, nav); // ISCl5q = getiscl5q(obs->sat, nav);
} }
//CHECK IF IT IS STILL NEEDED // CHECK IF IT IS STILL NEEDED
if (opt->ionoopt == IONOOPT_IFLC) if (opt->ionoopt == IONOOPT_IFLC)
{ {
/* dual-frequency */ /* dual-frequency */
@ -272,12 +272,12 @@ double prange(const obsd_t *obs, const nav_t *nav, const double *azel,
if (sys == SYS_GPS) if (sys == SYS_GPS)
{ {
P2 += P2_C2; /* C2->P2 */ P2 += P2_C2; /* C2->P2 */
//PC = P2 - gamma_ * P1_P2 / (1.0 - gamma_); // PC = P2 - gamma_ * P1_P2 / (1.0 - gamma_);
if (obs->code[j] == CODE_L2S) //L2 single freq. if (obs->code[j] == CODE_L2S) // L2 single freq.
{ {
PC = P2 + P1_P2 - ISCl2; PC = P2 + P1_P2 - ISCl2;
} }
else if (obs->code[j] == CODE_L5X) //L5 single freq. else if (obs->code[j] == CODE_L5X) // L5 single freq.
{ {
PC = P2 + P1_P2 - ISCl5i; PC = P2 + P1_P2 - ISCl5i;
} }
@ -298,15 +298,15 @@ double prange(const obsd_t *obs, const nav_t *nav, const double *azel,
{ {
if (obs->code[j] == CODE_L2S) /* L1 + L2 */ if (obs->code[j] == CODE_L2S) /* L1 + L2 */
{ {
//By the moment, GPS L2 pseudoranges are not used // By the moment, GPS L2 pseudoranges are not used
//PC = (P2 + ISCl2 - gamma_ * (P1 + ISCl1)) / (1.0 - gamma_) - P1_P2; // PC = (P2 + ISCl2 - gamma_ * (P1 + ISCl1)) / (1.0 - gamma_) - P1_P2;
P1 += P1_C1; /* C1->P1 */ P1 += P1_C1; /* C1->P1 */
PC = P1 + P1_P2; PC = P1 + P1_P2;
} }
else if (obs->code[j] == CODE_L5X) /* L1 + L5 */ else if (obs->code[j] == CODE_L5X) /* L1 + L5 */
{ {
//By the moment, GPS L5 pseudoranges are not used // By the moment, GPS L5 pseudoranges are not used
//PC = (P2 + ISCl5i - gamma_ * (P1 + ISCl5i)) / (1.0 - gamma_) - P1_P2; // PC = (P2 + ISCl5i - gamma_ * (P1 + ISCl5i)) / (1.0 - gamma_) - P1_P2;
P1 += P1_C1; /* C1->P1 */ P1 += P1_C1; /* C1->P1 */
PC = P1 + P1_P2; PC = P1 + P1_P2;
} }
@ -371,9 +371,9 @@ int ionocorr(gtime_t time, const nav_t *nav, int sat, const double *pos,
return 1; return 1;
} }
/* lex ionosphere model */ /* lex ionosphere model */
//if (ionoopt == IONOOPT_LEX) { // if (ionoopt == IONOOPT_LEX) {
// return lexioncorr(time, nav, pos, azel, ion, var); // return lexioncorr(time, nav, pos, azel, ion, var);
//} // }
*ion = 0.0; *ion = 0.0;
*var = ionoopt == IONOOPT_OFF ? std::pow(ERR_ION, 2.0) : 0.0; *var = ionoopt == IONOOPT_OFF ? std::pow(ERR_ION, 2.0) : 0.0;
return 1; return 1;

View File

@ -54,7 +54,7 @@
#include "rtklib_rtcm.h" #include "rtklib_rtcm.h"
#include "rtklib_rtkcmn.h" #include "rtklib_rtkcmn.h"
//extern int encode_rtcm3(rtcm_t *rtcm, int type, int sync); // extern int encode_rtcm3(rtcm_t *rtcm, int type, int sync);
/* initialize rtcm control ----------------------------------------------------- /* initialize rtcm control -----------------------------------------------------
@ -440,15 +440,15 @@ int gen_rtcm2(rtcm_t *rtcm, int type, int sync)
} }
///* generate rtcm 3 message ----------------------------------------------------- // /* generate rtcm 3 message -----------------------------------------------------
// * generate rtcm 3 message // * generate rtcm 3 message
// * args : rtcm_t *rtcm IO rtcm control struct // * args : rtcm_t *rtcm IO rtcm control struct
// * int type I message type // * int type I message type
// * int sync I sync flag (1:another message follows) // * int sync I sync flag (1:another message follows)
// * return : status (1:ok,0:error) // * return : status (1:ok,0:error)
// *-----------------------------------------------------------------------------*/ // *-----------------------------------------------------------------------------*/
//int gen_rtcm3(rtcm_t *rtcm, int type, int sync) // int gen_rtcm3(rtcm_t *rtcm, int type, int sync)
//{ // {
// unsigned int crc; // unsigned int crc;
// int i = 0; // int i = 0;
// //
@ -487,4 +487,4 @@ int gen_rtcm2(rtcm_t *rtcm, int type, int sync)
// rtcm->nbyte = rtcm->len+3; // rtcm->nbyte = rtcm->len+3;
// //
// return 1; // return 1;
//} // }

View File

@ -70,7 +70,7 @@ int input_rtcm3(rtcm_t *rtcm, unsigned char data);
int input_rtcm2f(rtcm_t *rtcm, FILE *fp); int input_rtcm2f(rtcm_t *rtcm, FILE *fp);
int input_rtcm3f(rtcm_t *rtcm, FILE *fp); int input_rtcm3f(rtcm_t *rtcm, FILE *fp);
int gen_rtcm2(rtcm_t *rtcm, int type, int sync); int gen_rtcm2(rtcm_t *rtcm, int type, int sync);
//int gen_rtcm3(rtcm_t *rtcm, int type, int sync); // int gen_rtcm3(rtcm_t *rtcm, int type, int sync);
#endif #endif // GNSS_SDR_RTKLIB_RTCM_H_

View File

@ -1720,7 +1720,7 @@ int decode_type1045(rtcm_t *rtcm)
i += 2; /* OSHS */ i += 2; /* OSHS */
e5a_dvs = getbitu(rtcm->buff, i, 1); e5a_dvs = getbitu(rtcm->buff, i, 1);
i += 1; /* OSDVS */ i += 1; /* OSDVS */
//rsv = getbitu(rtcm->buff, i, 7); // rsv = getbitu(rtcm->buff, i, 7);
} }
else else
{ {
@ -1834,7 +1834,7 @@ int decode_type1046(rtcm_t *rtcm)
i += 2; /* OSHS */ i += 2; /* OSHS */
e5a_dvs = getbitu(rtcm->buff, i, 1); e5a_dvs = getbitu(rtcm->buff, i, 1);
i += 1; /* OSDVS */ i += 1; /* OSDVS */
//rsv = getbitu(rtcm->buff, i, 7); // rsv = getbitu(rtcm->buff, i, 7);
} }
else else
{ {

View File

@ -1741,17 +1741,16 @@ double timediff(gtime_t t1, gtime_t t2)
return difftime(t1.time, t2.time) + t1.sec - t2.sec; return difftime(t1.time, t2.time) + t1.sec - t2.sec;
} }
/* time difference accounting with week crossovers ------------------------------------------------------------- /* time difference accounting with week crossovers -----------------------------
* difference between gtime_t structs * difference between gtime_t structs
* args : gtime_t t1,t2 I gtime_t structs * args : gtime_t t1,t2 I gtime_t structs
* return : time difference (t1-t2) (s) * return : time difference (t1-t2) (s)
*-----------------------------------------------------------------------------*/ *-----------------------------------------------------------------------------*/
double timediffweekcrossover(gtime_t t1, gtime_t t2) double timediffweekcrossover(gtime_t t1, gtime_t t2)
{ {
//as stated in IS-GPS-200J table 20-IV footnote among other parts of the ICD, // as stated in IS-GPS-200J table 20-IV footnote among other parts of the ICD,
// if tk=(t - toe) > 302400s then tk = tk - s
//if tk=(t - toe) > 302400s then tk = tk - s // if tk=(t - toe) < -302400s then tk = tk + 604800s
//if tk=(t - toe) < -302400s then tk = tk + 604800s
double tk = difftime(t1.time, t2.time) + t1.sec - t2.sec; double tk = difftime(t1.time, t2.time) + t1.sec - t2.sec;
if (tk > 302400.0) if (tk > 302400.0)
{ {
@ -1763,6 +1762,7 @@ double timediffweekcrossover(gtime_t t1, gtime_t t2)
} }
return tk; return tk;
} }
/* get current time in utc ----------------------------------------------------- /* get current time in utc -----------------------------------------------------
* get current time in utc * get current time in utc
* args : none * args : none
@ -3826,7 +3826,7 @@ void freenav(nav_t *nav, int opt)
/* debug trace functions -----------------------------------------------------*/ /* debug trace functions -----------------------------------------------------*/
//#ifdef TRACE // #ifdef TRACE
// //
FILE *fp_trace = nullptr; /* file pointer of trace */ FILE *fp_trace = nullptr; /* file pointer of trace */
char file_trace[1024]; /* trace file */ char file_trace[1024]; /* trace file */
@ -3908,8 +3908,9 @@ void tracelevel(int level)
{ {
level_trace = level; level_trace = level;
} }
//extern void trace(int level, const char *format, ...)
//{ // extern void trace(int level, const char *format, ...)
// {
// va_list ap; // va_list ap;
// //
// /* print error message to stderr */ // /* print error message to stderr */
@ -3921,7 +3922,7 @@ void tracelevel(int level)
// fprintf(fp_trace,"%d ",level); // fprintf(fp_trace,"%d ",level);
// va_start(ap,format); vfprintf(fp_trace,format,ap); va_end(ap); // va_start(ap,format); vfprintf(fp_trace,format,ap); va_end(ap);
// fflush(fp_trace); // fflush(fp_trace);
//} // }
void tracet(int level, const char *format, ...) void tracet(int level, const char *format, ...)
{ {
@ -3962,8 +3963,9 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// } // }
// fflush(fp_trace); // fflush(fp_trace);
} }
//extern void tracenav(int level, const nav_t *nav)
//{ // extern void tracenav(int level, const nav_t *nav)
// {
// char s1[64],s2[64],id[16]; // char s1[64],s2[64],id[16];
// int i; // int i;
// //
@ -3981,9 +3983,9 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// nav->ion_gps[5],nav->ion_gps[6],nav->ion_gps[7]); // nav->ion_gps[5],nav->ion_gps[6],nav->ion_gps[7]);
// fprintf(fp_trace,"(ion) %9.4e %9.4e %9.4e %9.4e\n",nav->ion_gal[0], // fprintf(fp_trace,"(ion) %9.4e %9.4e %9.4e %9.4e\n",nav->ion_gal[0],
// nav->ion_gal[1],nav->ion_gal[2],nav->ion_gal[3]); // nav->ion_gal[1],nav->ion_gal[2],nav->ion_gal[3]);
//} // }
//extern void tracegnav(int level, const nav_t *nav) // extern void tracegnav(int level, const nav_t *nav)
//{ // {
// char s1[64],s2[64],id[16]; // char s1[64],s2[64],id[16];
// int i; // int i;
// //
@ -3995,9 +3997,9 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// fprintf(fp_trace,"(%3d) %-3s : %s %s %2d %2d %8.3f\n",i+1, // fprintf(fp_trace,"(%3d) %-3s : %s %s %2d %2d %8.3f\n",i+1,
// id,s1,s2,nav->geph[i].frq,nav->geph[i].svh,nav->geph[i].taun*1e6); // id,s1,s2,nav->geph[i].frq,nav->geph[i].svh,nav->geph[i].taun*1e6);
// } // }
//} // }
//extern void tracehnav(int level, const nav_t *nav) // extern void tracehnav(int level, const nav_t *nav)
//{ // {
// char s1[64],s2[64],id[16]; // char s1[64],s2[64],id[16];
// int i; // int i;
// //
@ -4009,9 +4011,9 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// fprintf(fp_trace,"(%3d) %-3s : %s %s %2d %2d\n",i+1, // fprintf(fp_trace,"(%3d) %-3s : %s %s %2d %2d\n",i+1,
// id,s1,s2,nav->seph[i].svh,nav->seph[i].sva); // id,s1,s2,nav->seph[i].svh,nav->seph[i].sva);
// } // }
//} // }
//extern void tracepeph(int level, const nav_t *nav) // extern void tracepeph(int level, const nav_t *nav)
//{ // {
// char s[64],id[16]; // char s[64],id[16];
// int i,j; // int i,j;
// //
@ -4029,9 +4031,9 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// nav->peph[i].std[j][2],nav->peph[i].std[j][3]*1e9); // nav->peph[i].std[j][2],nav->peph[i].std[j][3]*1e9);
// } // }
// } // }
//} // }
//extern void tracepclk(int level, const nav_t *nav) // extern void tracepclk(int level, const nav_t *nav)
//{ // {
// char s[64],id[16]; // char s[64],id[16];
// int i,j; // int i,j;
// //
@ -4046,19 +4048,19 @@ void traceobs(int level __attribute__((unused)), const obsd_t *obs __attribute__
// nav->pclk[i].clk[j][0]*1e9,nav->pclk[i].std[j][0]*1e9); // nav->pclk[i].clk[j][0]*1e9,nav->pclk[i].std[j][0]*1e9);
// } // }
// } // }
//} // }
//extern void traceb(int level, const unsigned char *p, int n) // extern void traceb(int level, const unsigned char *p, int n)
//{ // {
// int i; // int i;
// if (!fp_trace||level>level_trace) return; // if (!fp_trace||level>level_trace) return;
// for (i=0;i<n;i++) fprintf(fp_trace,"%02X%s",*p++,i%8==7?" ":""); // for (i=0;i<n;i++) fprintf(fp_trace,"%02X%s",*p++,i%8==7?" ":"");
// fprintf(fp_trace,"\n"); // fprintf(fp_trace,"\n");
//} // }
//#else // #else
//void traceopen(const char *file) {} // void traceopen(const char *file) {}
//void traceclose(void) {} // void traceclose(void) {}
//void tracelevel(int level) {} // void tracelevel(int level) {}
void trace(int level, const char *format, ...) void trace(int level, const char *format, ...)
{ {
va_list ap; va_list ap;
@ -4069,17 +4071,17 @@ void trace(int level, const char *format, ...)
std::string str(buffer); std::string str(buffer);
VLOG(level) << "RTKLIB TRACE[" << level << "]:" << str; VLOG(level) << "RTKLIB TRACE[" << level << "]:" << str;
} }
//void tracet (int level, const char *format, ...) {} // void tracet (int level, const char *format, ...) {}
//void tracemat(int level, const double *A, int n, int m, int p, int q) {} // void tracemat(int level, const double *A, int n, int m, int p, int q) {}
//void traceobs(int level, const obsd_t *obs, int n) {} // void traceobs(int level, const obsd_t *obs, int n) {}
//void tracenav(int level, const nav_t *nav) {} // void tracenav(int level, const nav_t *nav) {}
//void tracegnav(int level, const nav_t *nav) {} // void tracegnav(int level, const nav_t *nav) {}
//void tracehnav(int level, const nav_t *nav) {} // void tracehnav(int level, const nav_t *nav) {}
//void tracepeph(int level, const nav_t *nav) {} // void tracepeph(int level, const nav_t *nav) {}
//void tracepclk(int level, const nav_t *nav) {} // void tracepclk(int level, const nav_t *nav) {}
//void traceb (int level, const unsigned char *p, int n) {} // void traceb (int level, const unsigned char *p, int n) {}
//#endif /* TRACE */ // #endif /* TRACE */
/* execute command ------------------------------------------------------------- /* execute command -------------------------------------------------------------
@ -4104,7 +4106,7 @@ void createdir(const char *path)
{ {
char buff[1024]; char buff[1024];
char *p; char *p;
//tracet(3, "createdir: path=%s\n", path); // tracet(3, "createdir: path=%s\n", path);
if (strlen(path) < 1025) if (strlen(path) < 1025)
{ {
@ -5240,10 +5242,10 @@ int expath(const char *path, char *paths[], int nmax)
trace(3, "expath : path=%s nmax=%d\n", path, nmax); trace(3, "expath : path=%s nmax=%d\n", path, nmax);
//TODO: Fix invalid conversion from const char* to char* // TODO: Fix invalid conversion from const char* to char*
//if ((p=strrchr(path,'/')) || (p=strrchr(path,'\\'))) { // if ((p=strrchr(path,'/')) || (p=strrchr(path,'\\'))) {
// file=p+1; strncpy(dir,path,p-path+1); dir[p-path+1]='\0'; // file=p+1; strncpy(dir,path,p-path+1); dir[p-path+1]='\0';
//} // }
if (!(dp = opendir(*dir ? dir : "."))) if (!(dp = opendir(*dir ? dir : ".")))
{ {
return 0; return 0;

View File

@ -240,12 +240,12 @@ void trace(int level, const char *format, ...);
void tracet(int level, const char *format, ...); void tracet(int level, const char *format, ...);
void tracemat(int level, const double *A, int n, int m, int p, int q); void tracemat(int level, const double *A, int n, int m, int p, int q);
void traceobs(int level, const obsd_t *obs, int n); void traceobs(int level, const obsd_t *obs, int n);
//void tracenav(int level, const nav_t *nav); // void tracenav(int level, const nav_t *nav);
//void tracegnav(int level, const nav_t *nav); // void tracegnav(int level, const nav_t *nav);
//void tracehnav(int level, const nav_t *nav); // void tracehnav(int level, const nav_t *nav);
//void tracepeph(int level, const nav_t *nav); // void tracepeph(int level, const nav_t *nav);
//void tracepclk(int level, const nav_t *nav); // void tracepclk(int level, const nav_t *nav);
//void traceb (int level, const unsigned char *p, int n); // void traceb (int level, const unsigned char *p, int n);
int execcmd(const char *cmd); int execcmd(const char *cmd);
void createdir(const char *path); void createdir(const char *path);
@ -258,7 +258,6 @@ double satwavelen(int sat, int frq, const nav_t *nav);
double geodist(const double *rs, const double *rr, double *e); double geodist(const double *rs, const double *rr, double *e);
double satazel(const double *pos, const double *e, double *azel); double satazel(const double *pos, const double *e, double *azel);
//#define SQRT(x) ((x)<0.0?0.0:sqrt(x))
void dops(int ns, const double *azel, double elmin, double *dop); void dops(int ns, const double *azel, double elmin, double *dop);
double ionmodel(gtime_t t, const double *ion, const double *pos, double ionmodel(gtime_t t, const double *ion, const double *pos,
const double *azel); const double *azel);

View File

@ -428,7 +428,7 @@ int decoderaw(rtksvr_t *svr, int index)
else else
{ {
// Disabled !! // Disabled !!
//ret = input_raw(svr->raw+index, svr->format[index], svr->buff[index][i]); // ret = input_raw(svr->raw+index, svr->format[index], svr->buff[index][i]);
obs = &svr->raw[index].obs; obs = &svr->raw[index].obs;
nav = &svr->raw[index].nav; nav = &svr->raw[index].nav;
sat = svr->raw[index].ephsat; sat = svr->raw[index].ephsat;
@ -678,7 +678,7 @@ void *rtksvrthread(void *arg)
svr->buff[i] = nullptr; svr->buff[i] = nullptr;
free(svr->pbuf[i]); free(svr->pbuf[i]);
svr->pbuf[i] = nullptr; svr->pbuf[i] = nullptr;
//free_raw (svr->raw +i); // free_raw (svr->raw +i);
free_rtcm(svr->rtcm + i); free_rtcm(svr->rtcm + i);
} }
for (i = 0; i < 2; i++) for (i = 0; i < 2; i++)
@ -958,7 +958,7 @@ int rtksvrstart(rtksvr_t *svr, int cycle, int buffsize, int *strs,
} }
/* initialize receiver raw and rtcm control */ /* initialize receiver raw and rtcm control */
//init_raw (svr->raw +i); // init_raw (svr->raw +i);
init_rtcm(svr->rtcm + i); init_rtcm(svr->rtcm + i);
/* set receiver and rtcm option */ /* set receiver and rtcm option */

View File

@ -1643,7 +1643,7 @@ int outnmea_gga(unsigned char *buff, const sol_t *sol)
} }
time2epoch(time, ep); time2epoch(time, ep);
ecef2pos(sol->rr, pos); ecef2pos(sol->rr, pos);
h = 0; //geoidh(pos); h = 0; // geoidh(pos);
deg2dms(fabs(pos[0]) * R2D, dms1); deg2dms(fabs(pos[0]) * R2D, dms1);
deg2dms(fabs(pos[1]) * R2D, dms2); deg2dms(fabs(pos[1]) * R2D, dms2);
p += sprintf(p, "$GPGGA,%02.0f%02.0f%05.2f,%02.0f%010.7f,%s,%03.0f%010.7f,%s,%d,%02d,%.1f,%.3f,M,%.3f,M,%.1f,", p += sprintf(p, "$GPGGA,%02.0f%02.0f%05.2f,%02.0f%010.7f,%s,%03.0f%010.7f,%s,%d,%02d,%.1f,%.3f,M,%.3f,M,%.1f,",

View File

@ -2886,22 +2886,22 @@ void strsendcmd(stream_t *str, const char *cmd)
sleepms(ms); sleepms(ms);
} }
//else if (!strncmp(msg+1, "UBX", 3)) // else if (!strncmp(msg+1, "UBX", 3))
//{ /* ublox */ // { /* ublox */
// if ((m=gen_ubx(msg+4, buff))>0) strwrite(str, buff, m); // if ((m=gen_ubx(msg+4, buff))>0) strwrite(str, buff, m);
//} // }
//else if (!strncmp(msg+1, "STQ", 3)) // else if (!strncmp(msg+1, "STQ", 3))
//{ /* skytraq */ // { /* skytraq */
// if ((m=gen_stq(msg+4, buff))>0) strwrite(str, buff, m); // if ((m=gen_stq(msg+4, buff))>0) strwrite(str, buff, m);
//} // }
//else if (!strncmp(msg+1, "NVS", 3)) // else if (!strncmp(msg+1, "NVS", 3))
//{ /* nvs */ // { /* nvs */
// if ((m=gen_nvs(msg+4, buff))>0) strwrite(str, buff, m); // if ((m=gen_nvs(msg+4, buff))>0) strwrite(str, buff, m);
//} // }
//else if (!strncmp(msg+1, "LEXR", 4)) // else if (!strncmp(msg+1, "LEXR", 4))
//{ /* lex receiver */ // { /* lex receiver */
// if ((m=gen_lexr(msg+5, buff))>0) strwrite(str, buff, m); // if ((m=gen_lexr(msg+5, buff))>0) strwrite(str, buff, m);
//} // }
else if (!strncmp(msg + 1, "HEX", 3)) else if (!strncmp(msg + 1, "HEX", 3))
{ /* general hex message */ { /* general hex message */
if ((m = gen_hex(msg + 4, buff)) > 0) if ((m = gen_hex(msg + 4, buff)) > 0)

View File

@ -55,7 +55,7 @@
/* solar/lunar tides (ref [2] 7) ---------------------------------------------*/ /* solar/lunar tides (ref [2] 7) ---------------------------------------------*/
//#ifndef IERS_MODEL // #ifndef IERS_MODEL
void tide_pl(const double *eu, const double *rp, double GMp, void tide_pl(const double *eu, const double *rp, double GMp,
const double *pos, double *dr) const double *pos, double *dr)
{ {
@ -164,7 +164,7 @@ void tide_solid(const double *rsun, const double *rmoon,
} }
trace(5, "tide_solid: dr=%.3f %.3f %.3f\n", dr[0], dr[1], dr[2]); trace(5, "tide_solid: dr=%.3f %.3f %.3f\n", dr[0], dr[1], dr[2]);
} }
//#endif /* !IERS_MODEL */ // #endif /* !IERS_MODEL */
/* displacement by ocean tide loading (ref [2] 7) ----------------------------*/ /* displacement by ocean tide loading (ref [2] 7) ----------------------------*/

View File

@ -64,8 +64,7 @@ MmseResamplerConditioner::MmseResamplerConditioner(
{ {
item_size_ = sizeof(gr_complex); item_size_ = sizeof(gr_complex);
// create a FIR low pass filter
//create a FIR low pass filter
std::vector<float> taps = gr::filter::firdes::low_pass(1.0, std::vector<float> taps = gr::filter::firdes::low_pass(1.0,
sample_freq_in_, sample_freq_in_,
sample_freq_out_ / 2.1, sample_freq_out_ / 2.1,

View File

@ -151,14 +151,12 @@ void signal_generator_c::init()
void signal_generator_c::generate_codes() void signal_generator_c::generate_codes()
{ {
//sampled_code_data_.reset(new gr_complex *[num_sats_]);
//sampled_code_pilot_.reset(new gr_complex *[num_sats_]);
sampled_code_data_ = std::vector<std::vector<gr_complex>>(num_sats_, std::vector<gr_complex>(vector_length_)); sampled_code_data_ = std::vector<std::vector<gr_complex>>(num_sats_, std::vector<gr_complex>(vector_length_));
sampled_code_pilot_ = std::vector<std::vector<gr_complex>>(num_sats_, std::vector<gr_complex>(vector_length_)); sampled_code_pilot_ = std::vector<std::vector<gr_complex>>(num_sats_, std::vector<gr_complex>(vector_length_));
for (unsigned int sat = 0; sat < num_sats_; sat++) for (unsigned int sat = 0; sat < num_sats_; sat++)
{ {
std::array<gr_complex, 64000> code{}; //[samples_per_code_[sat]]; std::array<gr_complex, 64000> code{};
if (system_[sat] == "G") if (system_[sat] == "G")
{ {
@ -212,7 +210,7 @@ void signal_generator_c::generate_codes()
galileo_e5_a_code_gen_complex_sampled(sampled_code_data_[sat], signal, PRN_[sat], fs_in_, galileo_e5_a_code_gen_complex_sampled(sampled_code_data_[sat], signal, PRN_[sat], fs_in_,
static_cast<int>(GALILEO_E5A_CODE_LENGTH_CHIPS) - delay_chips_[sat]); static_cast<int>(GALILEO_E5A_CODE_LENGTH_CHIPS) - delay_chips_[sat]);
//noise // noise
if (noise_flag_) if (noise_flag_)
{ {
for (unsigned int i = 0; i < vector_length_; i++) for (unsigned int i = 0; i < vector_length_; i++)

View File

@ -95,7 +95,7 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(ConfigurationInterface* configura
rf_gain_rx1_, rf_gain_rx1_,
rf_gain_rx2_); rf_gain_rx2_);
//LOCAL OSCILLATOR DDS GENERATOR FOR DUAL FREQUENCY OPERATION // LOCAL OSCILLATOR DDS GENERATOR FOR DUAL FREQUENCY OPERATION
if (enable_dds_lo_ == true) if (enable_dds_lo_ == true)
{ {
config_ad9361_lo_local(bandwidth_, config_ad9361_lo_local(bandwidth_,
@ -126,9 +126,9 @@ Ad9361FpgaSignalSource::Ad9361FpgaSignalSource(ConfigurationInterface* configura
Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource() Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource()
{ {
/* cleanup and exit */ /* cleanup and exit */
//std::cout<<"* AD9361 Disabling streaming channels\n"; // std::cout<<"* AD9361 Disabling streaming channels\n";
//if (rx0_i) { iio_channel_disable(rx0_i); } // if (rx0_i) { iio_channel_disable(rx0_i); }
//if (rx0_q) { iio_channel_disable(rx0_q); } // if (rx0_q) { iio_channel_disable(rx0_q); }
if (enable_dds_lo_) if (enable_dds_lo_)
{ {
@ -143,7 +143,7 @@ Ad9361FpgaSignalSource::~Ad9361FpgaSignalSource()
} }
// std::cout<<"* AD9361 Destroying context\n"; // std::cout<<"* AD9361 Destroying context\n";
//if (ctx) { iio_context_destroy(ctx); } // if (ctx) { iio_context_destroy(ctx); }
} }

View File

@ -206,7 +206,7 @@ FileSignalSource::FileSignalSource(ConfigurationInterface* configuration,
{ {
int64_t bytes_to_skip = samples_to_skip * item_size_; int64_t bytes_to_skip = samples_to_skip * item_size_;
int64_t bytes_to_process = static_cast<int64_t>(size) - bytes_to_skip; int64_t bytes_to_process = static_cast<int64_t>(size) - bytes_to_skip;
samples_ = floor(static_cast<double>(bytes_to_process) / static_cast<double>(item_size()) - ceil(0.002 * static_cast<double>(sampling_frequency_))); //process all the samples available in the file excluding at least the last 1 ms samples_ = floor(static_cast<double>(bytes_to_process) / static_cast<double>(item_size()) - ceil(0.002 * static_cast<double>(sampling_frequency_))); // process all the samples available in the file excluding at least the last 1 ms
} }
} }

View File

@ -58,7 +58,7 @@ FlexibandSignalSource::FlexibandSignalSource(ConfigurationInterface* configurati
gain3_ = configuration->property(role + ".gain3", 0); // check gain DAC values for Flexiband frontend! gain3_ = configuration->property(role + ".gain3", 0); // check gain DAC values for Flexiband frontend!
AGC_ = configuration->property(role + ".AGC", true); // enabled AGC by default AGC_ = configuration->property(role + ".AGC", true); // enabled AGC by default
flag_read_file = configuration->property(role + ".flag_read_file", false); //disable read samples from file by default flag_read_file = configuration->property(role + ".flag_read_file", false); // disable read samples from file by default
std::string default_signal_file = "flexiband_frame_samples.bin"; std::string default_signal_file = "flexiband_frame_samples.bin";
signal_file = configuration->property(role + ".signal_file", default_signal_file); signal_file = configuration->property(role + ".signal_file", default_signal_file);
@ -79,7 +79,7 @@ FlexibandSignalSource::FlexibandSignalSource(ConfigurationInterface* configurati
item_size_ = sizeof(gr_complex); item_size_ = sizeof(gr_complex);
flexiband_source_ = gr::teleorbit::frontend::make(firmware_filename_.c_str(), gain1_, gain2_, gain3_, AGC_, usb_packet_buffer_size_, signal_file.c_str(), flag_read_file); flexiband_source_ = gr::teleorbit::frontend::make(firmware_filename_.c_str(), gain1_, gain2_, gain3_, AGC_, usb_packet_buffer_size_, signal_file.c_str(), flag_read_file);
//create I, Q -> gr_complex type conversion blocks // create I, Q -> gr_complex type conversion blocks
for (int n = 0; n < (n_channels_ * 2); n++) for (int n = 0; n < (n_channels_ * 2); n++)
{ {
char_to_float.push_back(gr::blocks::char_to_float::make()); char_to_float.push_back(gr::blocks::char_to_float::make());
@ -157,12 +157,13 @@ gr::basic_block_sptr FlexibandSignalSource::get_right_block()
return get_right_block(0); return get_right_block(0);
} }
gr::basic_block_sptr FlexibandSignalSource::get_right_block(int RF_channel) gr::basic_block_sptr FlexibandSignalSource::get_right_block(int RF_channel)
{ {
if (RF_channel == 0) if (RF_channel == 0)
{ {
//in the first RF channel, return the signalsource selected channel. // in the first RF channel, return the signalsource selected channel.
//this trick enables the use of the second or the third frequency of a FlexiBand signal without a dual frequency configuration // this trick enables the use of the second or the third frequency of a FlexiBand signal without a dual frequency configuration
return float_to_complex_.at(sel_ch_ - 1); return float_to_complex_.at(sel_ch_ - 1);
} }
else else

View File

@ -84,11 +84,11 @@ private:
std::string role_; std::string role_;
// Front-end settings // Front-end settings
std::string uri_; //device direction std::string uri_; // device direction
unsigned long freq_; //frequency of local oscilator unsigned long freq_; // frequency of local oscilator
unsigned long sample_rate_; unsigned long sample_rate_;
unsigned long bandwidth_; unsigned long bandwidth_;
unsigned long buffer_size_; //reception buffer unsigned long buffer_size_; // reception buffer
bool rx1_en_; bool rx1_en_;
bool rx2_en_; bool rx2_en_;
bool quadrature_; bool quadrature_;
@ -103,7 +103,7 @@ private:
std::string filter_file_; std::string filter_file_;
bool filter_auto_; bool filter_auto_;
//DDS configuration for LO generation for external mixer // DDS configuration for LO generation for external mixer
bool enable_dds_lo_; bool enable_dds_lo_;
unsigned long freq_rf_tx_hz_; unsigned long freq_rf_tx_hz_;
unsigned long freq_dds_tx_hz_; unsigned long freq_dds_tx_hz_;
@ -127,4 +127,4 @@ private:
std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue_; std::shared_ptr<Concurrent_Queue<pmt::pmt_t>> queue_;
}; };
#endif /*GNSS_SDR_FMCOMMS2_SIGNAL_SOURCE_H_*/ #endif /* GNSS_SDR_FMCOMMS2_SIGNAL_SOURCE_H_ */

View File

@ -170,7 +170,7 @@ MultichannelFileSignalSource::MultichannelFileSignalSource(ConfigurationInterfac
throw(e); throw(e);
} }
//todo from here.... add mux demux also // todo from here.... add mux demux also
if (samples_ == 0) // read all file if (samples_ == 0) // read all file
{ {
/*! /*!

View File

@ -138,7 +138,7 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
{ {
int sample_packet_factor = 4; // 1 byte -> 4 samples int sample_packet_factor = 4; // 1 byte -> 4 samples
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor; samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); //process all the samples available in the file excluding the last 2 ms samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
} }
} }
@ -153,7 +153,7 @@ NsrFileSignalSource::NsrFileSignalSource(ConfigurationInterface* configuration,
if (dump_) if (dump_)
{ {
//sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str()); // sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str()); sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")"; DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
} }
@ -298,7 +298,7 @@ void NsrFileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr NsrFileSignalSource::get_left_block() gr::basic_block_sptr NsrFileSignalSource::get_left_block()
{ {
LOG(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_block_sptr();
return gr::blocks::file_source::sptr(); return gr::blocks::file_source::sptr();
} }

View File

@ -44,8 +44,8 @@ RawArraySignalSource::RawArraySignalSource(ConfigurationInterface* configuration
std::string default_dump_file = "./data/raw_array_source.dat"; std::string default_dump_file = "./data/raw_array_source.dat";
item_type_ = configuration->property(role + ".item_type", default_item_type); item_type_ = configuration->property(role + ".item_type", default_item_type);
//dump_ = configuration->property(role + ".dump", false); // dump_ = configuration->property(role + ".dump", false);
//dump_filename_ = configuration->property(role + ".dump_filename", default_dump_file); // dump_filename_ = configuration->property(role + ".dump_filename", default_dump_file);
dump_ = false; dump_ = false;
std::string default_ethernet_dev = "eth0"; std::string default_ethernet_dev = "eth0";
@ -83,7 +83,7 @@ RawArraySignalSource::RawArraySignalSource(ConfigurationInterface* configuration
} }
if (dump_) if (dump_)
{ {
//TODO: multichannel recorder // TODO: multichannel recorder
DLOG(INFO) << "Dumping output into file " << dump_filename_; DLOG(INFO) << "Dumping output into file " << dump_filename_;
file_sink_ = gr::blocks::file_sink::make(item_size_, dump_filename_.c_str()); file_sink_ = gr::blocks::file_sink::make(item_size_, dump_filename_.c_str());
} }
@ -98,7 +98,7 @@ void RawArraySignalSource::connect(gr::top_block_sptr top_block)
{ {
if (dump_) if (dump_)
{ {
//TODO: multichannel recorder // TODO: multichannel recorder
top_block->connect(raw_array_source_, 0, file_sink_, 0); top_block->connect(raw_array_source_, 0, file_sink_, 0);
DLOG(INFO) << "connected raw_array_source_ to file sink"; DLOG(INFO) << "connected raw_array_source_ to file sink";
} }
@ -113,7 +113,7 @@ void RawArraySignalSource::disconnect(gr::top_block_sptr top_block)
{ {
if (dump_) if (dump_)
{ {
//TODO: multichannel recorder // TODO: multichannel recorder
top_block->disconnect(raw_array_source_, 0, file_sink_, 0); top_block->disconnect(raw_array_source_, 0, file_sink_, 0);
} }
} }

View File

@ -137,7 +137,7 @@ SpirFileSignalSource::SpirFileSignalSource(ConfigurationInterface* configuration
{ {
int sample_packet_factor = 1; // 1 int -> 1 complex sample (I&Q from 1 channel) int sample_packet_factor = 1; // 1 int -> 1 complex sample (I&Q from 1 channel)
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor; samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); //process all the samples available in the file excluding the last 2 ms samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
} }
} }
@ -152,7 +152,7 @@ SpirFileSignalSource::SpirFileSignalSource(ConfigurationInterface* configuration
if (dump_) if (dump_)
{ {
//sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str()); // sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str()); sink_ = gr::blocks::file_sink::make(sizeof(float), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")"; DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
} }
@ -297,7 +297,7 @@ void SpirFileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr SpirFileSignalSource::get_left_block() gr::basic_block_sptr SpirFileSignalSource::get_left_block()
{ {
LOG(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_block_sptr();
return gr::blocks::file_source::sptr(); return gr::blocks::file_source::sptr();
} }

View File

@ -137,7 +137,7 @@ SpirGSS6450FileSignalSource::SpirGSS6450FileSignalSource(ConfigurationInterface*
if (size > 0) if (size > 0)
{ {
samples_ = static_cast<uint64_t>(floor(static_cast<double>(static_cast<int64_t>(size) - static_cast<int64_t>(bytes_seek)) / (sample_size_byte * static_cast<double>(n_channels_)))); samples_ = static_cast<uint64_t>(floor(static_cast<double>(static_cast<int64_t>(size) - static_cast<int64_t>(bytes_seek)) / (sample_size_byte * static_cast<double>(n_channels_))));
samples_ = samples_ - static_cast<uint64_t>(ceil(0.002 * sampling_frequency_)); //process all the samples available in the file excluding the last 2 ms samples_ = samples_ - static_cast<uint64_t>(ceil(0.002 * sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
} }
} }

View File

@ -114,7 +114,7 @@ private:
int64_t sampling_frequency_; int64_t sampling_frequency_;
std::string filename_; std::string filename_;
bool repeat_; bool repeat_;
bool dump_; //Enables dumping the gr_complex sample output bool dump_; // Enables dumping the gr_complex sample output
bool enable_throttle_control_; bool enable_throttle_control_;
bool endian_swap_; bool endian_swap_;
std::string dump_filename_; std::string dump_filename_;

View File

@ -87,7 +87,7 @@ TwoBitCpxFileSignalSource::TwoBitCpxFileSignalSource(ConfigurationInterface* con
{ {
file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_); file_source_ = gr::blocks::file_source::make(item_size_, filename_.c_str(), repeat_);
unpack_byte_ = make_unpack_byte_2bit_cpx_samples(); unpack_byte_ = make_unpack_byte_2bit_cpx_samples();
inter_shorts_to_cpx_ = gr::blocks::interleaved_short_to_complex::make(false, true); //I/Q swap enabled inter_shorts_to_cpx_ = gr::blocks::interleaved_short_to_complex::make(false, true); // I/Q swap enabled
} }
catch (const std::exception& e) catch (const std::exception& e)
{ {
@ -143,7 +143,7 @@ TwoBitCpxFileSignalSource::TwoBitCpxFileSignalSource(ConfigurationInterface* con
{ {
int sample_packet_factor = 2; // 1 byte -> 2 samples int sample_packet_factor = 2; // 1 byte -> 2 samples
samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor; samples_ = floor(static_cast<double>(size) / static_cast<double>(item_size())) * sample_packet_factor;
samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); //process all the samples available in the file excluding the last 2 ms samples_ = samples_ - ceil(0.002 * static_cast<double>(sampling_frequency_)); // process all the samples available in the file excluding the last 2 ms
} }
} }
@ -158,7 +158,7 @@ TwoBitCpxFileSignalSource::TwoBitCpxFileSignalSource(ConfigurationInterface* con
if (dump_) if (dump_)
{ {
//sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str()); // sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(sizeof(gr_complex), dump_filename_.c_str()); sink_ = gr::blocks::file_sink::make(sizeof(gr_complex), dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")"; DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
} }
@ -307,7 +307,7 @@ void TwoBitCpxFileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr TwoBitCpxFileSignalSource::get_left_block() gr::basic_block_sptr TwoBitCpxFileSignalSource::get_left_block()
{ {
LOG(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_block_sptr();
return gr::blocks::file_source::sptr(); return gr::blocks::file_source::sptr();
} }

View File

@ -197,7 +197,7 @@ TwoBitPackedFileSignalSource::TwoBitPackedFileSignalSource(ConfigurationInterfac
LOG(INFO) << "Total samples in the file= " << samples_; // 4 samples per byte LOG(INFO) << "Total samples in the file= " << samples_; // 4 samples per byte
samples_ -= bytes_to_skip; samples_ -= bytes_to_skip;
//Also skip the last two milliseconds: // Also skip the last two milliseconds:
samples_ -= ceil(0.002 * sampling_frequency_ / (is_complex_ ? 2.0 : 4.0)); samples_ -= ceil(0.002 * sampling_frequency_ / (is_complex_ ? 2.0 : 4.0));
} }
else else
@ -222,7 +222,7 @@ TwoBitPackedFileSignalSource::TwoBitPackedFileSignalSource(ConfigurationInterfac
if (dump_) if (dump_)
{ {
//sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str()); // sink_ = gr_make_file_sink(item_size_, dump_filename_.c_str());
sink_ = gr::blocks::file_sink::make(output_item_size, dump_filename_.c_str()); sink_ = gr::blocks::file_sink::make(output_item_size, dump_filename_.c_str());
DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")"; DLOG(INFO) << "file_sink(" << sink_->unique_id() << ")";
} }
@ -318,7 +318,7 @@ void TwoBitPackedFileSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr TwoBitPackedFileSignalSource::get_left_block() gr::basic_block_sptr TwoBitPackedFileSignalSource::get_left_block()
{ {
LOG(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_block_sptr();
return gr::blocks::file_source::sptr(); return gr::blocks::file_source::sptr();
} }

View File

@ -60,7 +60,7 @@ UhdSignalSource::UhdSignalSource(ConfigurationInterface* configuration,
{ {
dev_addr["addr"] = device_address_; dev_addr["addr"] = device_address_;
} }
//filter the device by serial number if required (useful for USB devices) // filter the device by serial number if required (useful for USB devices)
std::string device_serial = configuration->property(role + ".device_serial", empty); std::string device_serial = configuration->property(role + ".device_serial", empty);
if (empty != device_serial) // if not empty if (empty != device_serial) // if not empty
{ {
@ -101,7 +101,7 @@ UhdSignalSource::UhdSignalSource(ConfigurationInterface* configuration,
} }
} }
// 1. Make the uhd driver instance // 1. Make the uhd driver instance
//uhd_source_= uhd::usrp::multi_usrp::make(dev_addr); // uhd_source_= uhd::usrp::multi_usrp::make(dev_addr);
// single source // single source
// param: device_addr the address to identify the hardware // param: device_addr the address to identify the hardware
@ -182,12 +182,12 @@ UhdSignalSource::UhdSignalSource(ConfigurationInterface* configuration,
std::cout << boost::format("Actual daughterboard gain set to: %f dB...") % uhd_source_->get_gain(i) << std::endl; std::cout << boost::format("Actual daughterboard gain set to: %f dB...") % uhd_source_->get_gain(i) << std::endl;
LOG(INFO) << boost::format("Actual daughterboard gain set to: %f dB...") % uhd_source_->get_gain(i); LOG(INFO) << boost::format("Actual daughterboard gain set to: %f dB...") % uhd_source_->get_gain(i);
//5. Set the bandpass filter on the RF frontend // 5. Set the bandpass filter on the RF frontend
std::cout << boost::format("Setting RF bandpass filter bandwidth to: %f [Hz]...") % IF_bandwidth_hz_.at(i) << std::endl; std::cout << boost::format("Setting RF bandpass filter bandwidth to: %f [Hz]...") % IF_bandwidth_hz_.at(i) << std::endl;
uhd_source_->set_bandwidth(IF_bandwidth_hz_.at(i), i); uhd_source_->set_bandwidth(IF_bandwidth_hz_.at(i), i);
//set the antenna (optional) // set the antenna (optional)
//uhd_source_->set_antenna(ant); // uhd_source_->set_antenna(ant);
// We should wait? #include <boost/thread.hpp> // We should wait? #include <boost/thread.hpp>
// boost::this_thread::sleep(boost::posix_time::seconds(1)); // boost::this_thread::sleep(boost::posix_time::seconds(1));
@ -206,11 +206,10 @@ UhdSignalSource::UhdSignalSource(ConfigurationInterface* configuration,
{ {
std::cout << "UNLOCKED!" << std::endl; std::cout << "UNLOCKED!" << std::endl;
} }
//UHD_ASSERT_THROW(lo_locked.to_bool()); // UHD_ASSERT_THROW(lo_locked.to_bool());
} }
} }
for (int i = 0; i < RF_channels_; i++) for (int i = 0; i < RF_channels_; i++)
{ {
if (samples_.at(i) != 0ULL) if (samples_.at(i) != 0ULL)
@ -291,7 +290,7 @@ void UhdSignalSource::disconnect(gr::top_block_sptr top_block)
gr::basic_block_sptr UhdSignalSource::get_left_block() gr::basic_block_sptr UhdSignalSource::get_left_block()
{ {
LOG(WARNING) << "Trying to get signal source left block."; LOG(WARNING) << "Trying to get signal source left block.";
//return gr_basic_block_sptr(); // return gr_basic_block_sptr();
return gr::uhd::usrp_source::sptr(); return gr::uhd::usrp_source::sptr();
} }
@ -304,7 +303,7 @@ gr::basic_block_sptr UhdSignalSource::get_right_block()
gr::basic_block_sptr UhdSignalSource::get_right_block(int RF_channel) gr::basic_block_sptr UhdSignalSource::get_right_block(int RF_channel)
{ {
//TODO: There is a incoherence here: Multichannel UHD is a single block with multiple outputs, but if the sample limit is enabled, the output is a multiple block! // TODO: There is a incoherence here: Multichannel UHD is a single block with multiple outputs, but if the sample limit is enabled, the output is a multiple block!
if (samples_.at(RF_channel) != 0ULL) if (samples_.at(RF_channel) != 0ULL)
{ {
return valve_.at(RF_channel); return valve_.at(RF_channel);

View File

@ -257,10 +257,10 @@ void Gr_Complex_Ip_Packet_Source::pcap_callback(__attribute__((unused)) u_char *
uh = reinterpret_cast<const gr_udp_header *>(reinterpret_cast<const u_char *>(ih) + ip_len); uh = reinterpret_cast<const gr_udp_header *>(reinterpret_cast<const u_char *>(ih) + ip_len);
// convert from network byte order to host byte order // convert from network byte order to host byte order
//u_short sport; // u_short sport;
u_short dport; u_short dport;
dport = ntohs(uh->dport); dport = ntohs(uh->dport);
//sport = ntohs(uh->sport); // sport = ntohs(uh->sport);
if (dport == d_udp_port) if (dport == d_udp_port)
{ {
// print ip addresses and udp ports // print ip addresses and udp ports
@ -319,7 +319,7 @@ void Gr_Complex_Ip_Packet_Source::my_pcap_loop_thread(pcap_t *pcap_handle)
} }
void Gr_Complex_Ip_Packet_Source::demux_samples(const gr_vector_void_star& output_items, int num_samples_readed) void Gr_Complex_Ip_Packet_Source::demux_samples(const gr_vector_void_star &output_items, int num_samples_readed)
{ {
int8_t real; int8_t real;
int8_t imag; int8_t imag;

View File

@ -147,7 +147,7 @@ void labsat23_source::decode_samples_one_channel(int16_t input_short, gr_complex
// bits per sample, 4 samples per int16 // bits per sample, 4 samples per int16
for (int i = 0; i < 4; i++) for (int i = 0; i < 4; i++)
{ {
//out[i] = gr_complex(0.0, 0.0); // out[i] = gr_complex(0.0, 0.0);
// In-Phase // In-Phase
if (bs[15 - 4 * i]) if (bs[15 - 4 * i])
{ {
@ -195,7 +195,7 @@ void labsat23_source::decode_samples_one_channel(int16_t input_short, gr_complex
out[i] += gr_complex(0, 1); out[i] += gr_complex(0, 1);
} }
} }
//out[i] += gr_complex(0.5, 0.5); // out[i] += gr_complex(0.5, 0.5);
} }
break; break;
default: default:
@ -273,8 +273,8 @@ int labsat23_source::general_work(int noutput_items,
uint8_t section_id = static_cast<int>(memblock[byte_counter]) + static_cast<int>(memblock[byte_counter + 1]) * 256; uint8_t section_id = static_cast<int>(memblock[byte_counter]) + static_cast<int>(memblock[byte_counter + 1]) * 256;
byte_counter += 2; byte_counter += 2;
//uint8_t section_lenght_bytes = 0; // uint8_t section_lenght_bytes = 0;
//section_lenght_bytes += memblock[byte_counter] | (memblock[byte_counter + 1] << 8) | (memblock[byte_counter + 2] << 16) | (memblock[byte_counter + 3] << 24); // section_lenght_bytes += memblock[byte_counter] | (memblock[byte_counter + 1] << 8) | (memblock[byte_counter + 2] << 16) | (memblock[byte_counter + 3] << 24);
byte_counter += 4; byte_counter += 4;
if (section_id == 2) if (section_id == 2)
@ -343,7 +343,7 @@ int labsat23_source::general_work(int noutput_items,
return -1; return -1;
} }
//todo: Add support for dual channel files // todo: Add support for dual channel files
if (d_channel_selector == 0) if (d_channel_selector == 0)
{ {
std::cout << "ERROR: Labsat file contains more than one channel and it is not currently supported by Labsat signal source." << std::endl; std::cout << "ERROR: Labsat file contains more than one channel and it is not currently supported by Labsat signal source." << std::endl;
@ -422,7 +422,7 @@ int labsat23_source::general_work(int noutput_items,
{ {
case 0: case 0:
// dual channel 2 bits per complex sample // dual channel 2 bits per complex sample
//todo: implement dual channel reader // todo: implement dual channel reader
break; break;
default: default:
// single channel 2 bits per complex sample (1 bit I + 1 bit Q, 8 samples per int16) // single channel 2 bits per complex sample (1 bit I + 1 bit Q, 8 samples per int16)
@ -480,7 +480,7 @@ int labsat23_source::general_work(int noutput_items,
{ {
case 0: case 0:
// dual channel // dual channel
//todo: implement dual channel reader // todo: implement dual channel reader
break; break;
default: default:
// single channel 4 bits per complex sample (2 bit I + 2 bit Q, 4 samples per int16) // single channel 4 bits per complex sample (2 bit I + 2 bit Q, 4 samples per int16)

View File

@ -69,11 +69,11 @@ int unpack_byte_2bit_cpx_samples::work(int noutput_items,
for (int i = 0; i < noutput_items / 4; i++) for (int i = 0; i < noutput_items / 4; i++)
{ {
// Read packed input sample (1 byte = 2 complex samples) // Read packed input sample (1 byte = 2 complex samples)
//* Packing Order // * Packing Order
//* Most Significant Nibble - Sample n // * Most Significant Nibble - Sample n
//* Least Significant Nibble - Sample n+1 // * Least Significant Nibble - Sample n+1
//* Packing order in Nibble Q1 Q0 I1 I0 // * Packing order in Nibble Q1 Q0 I1 I0
//normal // normal
// int8_t c = in[i]; // int8_t c = in[i];
// //Q[n] // //Q[n]
// sample.two_bit_sample = (c>>6) & 3; // sample.two_bit_sample = (c>>6) & 3;
@ -88,18 +88,18 @@ int unpack_byte_2bit_cpx_samples::work(int noutput_items,
// sample.two_bit_sample = c & 3; // sample.two_bit_sample = c & 3;
// out[n++] = (2*(int16_t)sample.two_bit_sample+1); // out[n++] = (2*(int16_t)sample.two_bit_sample+1);
//I/Q swap // I/Q swap
int8_t c = in[i]; int8_t c = in[i];
//I[n] // I[n]
sample.two_bit_sample = (c >> 4) & 3; sample.two_bit_sample = (c >> 4) & 3;
out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1); out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1);
//Q[n] // Q[n]
sample.two_bit_sample = (c >> 6) & 3; sample.two_bit_sample = (c >> 6) & 3;
out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1); out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1);
//I[n+1] // I[n+1]
sample.two_bit_sample = c & 3; sample.two_bit_sample = c & 3;
out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1); out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1);
//Q[n+1] // Q[n+1]
sample.two_bit_sample = (c >> 2) & 3; sample.two_bit_sample = (c >> 2) & 3;
out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1); out[n++] = (2 * static_cast<int16_t>(sample.two_bit_sample) + 1);
} }

View File

@ -57,7 +57,7 @@ void unpack_spir_gss6450_samples::decode_4bits_word(uint32_t input_uint32, gr_co
switch (adc_bits) switch (adc_bits)
{ {
case 2: case 2:
//four bits per complex sample (2 I + 2 Q), 8 samples per int32[s0,s1,s2,s3,s4,s5,s6,s7] // four bits per complex sample (2 I + 2 Q), 8 samples per int32[s0,s1,s2,s3,s4,s5,s6,s7]
for (int i = 0; i < 8; i++) for (int i = 0; i < 8; i++)
{ {
tmp_char = input_uint32 & 3; tmp_char = input_uint32 & 3;
@ -86,7 +86,7 @@ void unpack_spir_gss6450_samples::decode_4bits_word(uint32_t input_uint32, gr_co
} }
break; break;
case 4: case 4:
//eight bits per complex sample (4 I + 4 Q), 4 samples per int32= [s0,s1,s2,s3] // eight bits per complex sample (4 I + 4 Q), 4 samples per int32= [s0,s1,s2,s3]
for (int i = 0; i < 4; i++) for (int i = 0; i < 4; i++)
{ {
tmp_char = input_uint32 & 0x0F; tmp_char = input_uint32 & 0x0F;

View File

@ -154,7 +154,7 @@ bool cfg_ad9361_streaming_ch(struct iio_context *ctx, struct stream_cfg *cfg, en
struct iio_channel *chn = nullptr; struct iio_channel *chn = nullptr;
// Configure phy and lo channels // Configure phy and lo channels
//LOG(INFO)<<"* Acquiring AD9361 phy channel"<<chid; // LOG(INFO)<<"* Acquiring AD9361 phy channel"<<chid;
std::cout << "* Acquiring AD9361 phy channel" << chid << std::endl; std::cout << "* Acquiring AD9361 phy channel" << chid << std::endl;
if (!get_phy_chan(ctx, type, chid, &chn)) if (!get_phy_chan(ctx, type, chid, &chn))
{ {
@ -165,7 +165,7 @@ bool cfg_ad9361_streaming_ch(struct iio_context *ctx, struct stream_cfg *cfg, en
wr_ch_lli(chn, "sampling_frequency", cfg->fs_hz); wr_ch_lli(chn, "sampling_frequency", cfg->fs_hz);
// Configure LO channel // Configure LO channel
//LOG(INFO)<<"* Acquiring AD9361 "<<type == TX ? "TX" : "RX"; // LOG(INFO)<<"* Acquiring AD9361 "<<type == TX ? "TX" : "RX";
std::cout << "* Acquiring AD9361 " << (type == TX ? "TX" : "RX") << std::endl; std::cout << "* Acquiring AD9361 " << (type == TX ? "TX" : "RX") << std::endl;
if (!get_lo_chan(ctx, type, &chn)) if (!get_lo_chan(ctx, type, &chn))
{ {
@ -431,7 +431,7 @@ bool config_ad9361_lo_local(uint64_t bandwidth_,
throw std::runtime_error("AD9361 IIO No context"); throw std::runtime_error("AD9361 IIO No context");
} }
//find tx device // find tx device
struct iio_device *tx; struct iio_device *tx;
std::cout << "* Acquiring AD9361 TX streaming devices\n"; std::cout << "* Acquiring AD9361 TX streaming devices\n";
@ -449,11 +449,11 @@ bool config_ad9361_lo_local(uint64_t bandwidth_,
throw std::runtime_error("AD9361 IIO TX port 0 not found"); throw std::runtime_error("AD9361 IIO TX port 0 not found");
} }
//ENABLE DDS on TX1 // ENABLE DDS on TX1
struct iio_device *ad9361_phy; struct iio_device *ad9361_phy;
ad9361_phy = iio_context_find_device(ctx, "ad9361-phy"); ad9361_phy = iio_context_find_device(ctx, "ad9361-phy");
int ret; int ret;
//set output amplifier attenuation // set output amplifier attenuation
ret = iio_device_attr_write_double(ad9361_phy, "out_voltage0_hardwaregain", -tx_attenuation_db_); ret = iio_device_attr_write_double(ad9361_phy, "out_voltage0_hardwaregain", -tx_attenuation_db_);
if (ret < 0) if (ret < 0)
{ {
@ -474,8 +474,7 @@ bool config_ad9361_lo_local(uint64_t bandwidth_,
std::cout << "Failed to toggle DDS: " << ret << std::endl; std::cout << "Failed to toggle DDS: " << ret << std::endl;
} }
//set frequency, scale and phase // set frequency, scale and phase
ret = iio_channel_attr_write_longlong(dds_channel0_I, "frequency", static_cast<int64_t>(freq_dds_tx_hz_)); ret = iio_channel_attr_write_longlong(dds_channel0_I, "frequency", static_cast<int64_t>(freq_dds_tx_hz_));
if (ret < 0) if (ret < 0)
{ {
@ -512,8 +511,7 @@ bool config_ad9361_lo_local(uint64_t bandwidth_,
std::cout << "Failed to set TX DDS scale Q: " << ret << std::endl; std::cout << "Failed to set TX DDS scale Q: " << ret << std::endl;
} }
//disable TX2 // disable TX2
ret = iio_device_attr_write_double(ad9361_phy, "out_voltage1_hardwaregain", -89.0); ret = iio_device_attr_write_double(ad9361_phy, "out_voltage1_hardwaregain", -89.0);
if (ret < 0) if (ret < 0)
{ {
@ -568,7 +566,7 @@ bool config_ad9361_lo_remote(const std::string &remote_host,
throw std::runtime_error("AD9361 IIO No context"); throw std::runtime_error("AD9361 IIO No context");
} }
//find tx device // find tx device
struct iio_device *tx; struct iio_device *tx;
std::cout << "* Acquiring AD9361 TX streaming devices\n"; std::cout << "* Acquiring AD9361 TX streaming devices\n";
@ -586,11 +584,11 @@ bool config_ad9361_lo_remote(const std::string &remote_host,
throw std::runtime_error("AD9361 IIO TX port 0 not found"); throw std::runtime_error("AD9361 IIO TX port 0 not found");
} }
//ENABLE DDS on TX1 // ENABLE DDS on TX1
struct iio_device *ad9361_phy; struct iio_device *ad9361_phy;
ad9361_phy = iio_context_find_device(ctx, "ad9361-phy"); ad9361_phy = iio_context_find_device(ctx, "ad9361-phy");
int ret; int ret;
//set output amplifier attenuation // set output amplifier attenuation
ret = iio_device_attr_write_double(ad9361_phy, "out_voltage0_hardwaregain", -tx_attenuation_db_); ret = iio_device_attr_write_double(ad9361_phy, "out_voltage0_hardwaregain", -tx_attenuation_db_);
if (ret < 0) if (ret < 0)
{ {
@ -611,8 +609,7 @@ bool config_ad9361_lo_remote(const std::string &remote_host,
std::cout << "Failed to toggle DDS: " << ret << std::endl; std::cout << "Failed to toggle DDS: " << ret << std::endl;
} }
//set frequency, scale and phase // set frequency, scale and phase
ret = iio_channel_attr_write_longlong(dds_channel0_I, "frequency", static_cast<int64_t>(freq_dds_tx_hz_)); ret = iio_channel_attr_write_longlong(dds_channel0_I, "frequency", static_cast<int64_t>(freq_dds_tx_hz_));
if (ret < 0) if (ret < 0)
{ {
@ -649,8 +646,7 @@ bool config_ad9361_lo_remote(const std::string &remote_host,
std::cout << "Failed to set TX DDS scale Q: " << ret << std::endl; std::cout << "Failed to set TX DDS scale Q: " << ret << std::endl;
} }
//disable TX2 // disable TX2
ret = iio_device_attr_write_double(ad9361_phy, "out_voltage1_hardwaregain", -89.0); ret = iio_device_attr_write_double(ad9361_phy, "out_voltage1_hardwaregain", -89.0);
if (ret < 0) if (ret < 0)
{ {

View File

@ -686,27 +686,27 @@ int galileo_telemetry_decoder_gs::general_work(int noutput_items __attribute__((
{ {
d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_1 * 1000.0); d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_1 * 1000.0);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS); d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS);
//d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS); // d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS);
d_fnav_nav.flag_TOW_1 = false; d_fnav_nav.flag_TOW_1 = false;
} }
else if (d_fnav_nav.flag_TOW_2 == true) else if (d_fnav_nav.flag_TOW_2 == true)
{ {
d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_2 * 1000.0); d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_2 * 1000.0);
//d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS); // d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS); d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS);
d_fnav_nav.flag_TOW_2 = false; d_fnav_nav.flag_TOW_2 = false;
} }
else if (d_fnav_nav.flag_TOW_3 == true) else if (d_fnav_nav.flag_TOW_3 == true)
{ {
d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_3 * 1000.0); d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_3 * 1000.0);
//d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS); // d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS); d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS);
d_fnav_nav.flag_TOW_3 = false; d_fnav_nav.flag_TOW_3 = false;
} }
else if (d_fnav_nav.flag_TOW_4 == true) else if (d_fnav_nav.flag_TOW_4 == true)
{ {
d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_4 * 1000.0); d_TOW_at_Preamble_ms = static_cast<uint32_t>(d_fnav_nav.FNAV_TOW_4 * 1000.0);
//d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS); // d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((GALILEO_FNAV_CODES_PER_PAGE + GALILEO_FNAV_CODES_PER_PREAMBLE) * GALILEO_E5a_CODE_PERIOD_MS);
d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS); d_TOW_at_current_symbol_ms = d_TOW_at_Preamble_ms + static_cast<uint32_t>((d_required_symbols + 1) * GALILEO_FNAV_CODES_PER_SYMBOL * GALILEO_E5A_CODE_PERIOD_MS);
d_fnav_nav.flag_TOW_4 = false; d_fnav_nav.flag_TOW_4 = false;
} }

View File

@ -301,7 +301,7 @@ bool gps_l1_ca_telemetry_decoder_gs::decode_subframe()
break; break;
case 5: case 5:
// get almanac (if available) // get almanac (if available)
//TODO: implement almanac reader in navigation_message // TODO: implement almanac reader in navigation_message
break; break;
default: default:
break; break;

View File

@ -225,7 +225,7 @@ int gps_l2c_telemetry_decoder_gs::general_work(int noutput_items __attribute__((
// \code // \code
// symbolTime_ms = msg->tow * 6000 + *pdelay * 20 + (12 * 20); 12 symbols of the encoder's transitory // symbolTime_ms = msg->tow * 6000 + *pdelay * 20 + (12 * 20); 12 symbols of the encoder's transitory
d_TOW_at_current_symbol = static_cast<double>(msg.tow) * 6.0 + static_cast<double>(delay) * GPS_L2_M_PERIOD + 12 * GPS_L2_M_PERIOD; d_TOW_at_current_symbol = static_cast<double>(msg.tow) * 6.0 + static_cast<double>(delay) * GPS_L2_M_PERIOD + 12 * GPS_L2_M_PERIOD;
//d_TOW_at_current_symbol = floor(d_TOW_at_current_symbol * 1000.0) / 1000.0; // d_TOW_at_current_symbol = floor(d_TOW_at_current_symbol * 1000.0) / 1000.0;
d_flag_valid_word = true; d_flag_valid_word = true;
} }
else else

View File

@ -61,7 +61,7 @@ sbas_l1_telemetry_decoder_gs::sbas_l1_telemetry_decoder_gs(
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)), gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)),
gr::io_signature::make(1, 1, sizeof(Gnss_Synchro))) gr::io_signature::make(1, 1, sizeof(Gnss_Synchro)))
{ {
//prevent telemetry symbols accumulation in output buffers // prevent telemetry symbols accumulation in output buffers
this->set_max_noutput_items(1); this->set_max_noutput_items(1);
// Ephemeris data port out // Ephemeris data port out
this->message_port_register_out(pmt::mp("telemetry")); this->message_port_register_out(pmt::mp("telemetry"));
@ -168,7 +168,7 @@ bool sbas_l1_telemetry_decoder_gs::Sample_Aligner::get_symbols(const std::vector
<< "smpl0: " << std::setw(6) << "smpl0: " << std::setw(6)
<< smpls[1] << " " << smpls[1] << " "
<< "smpl1: " << std::setw(6) << smpls[2] << "\t" << "smpl1: " << std::setw(6) << smpls[2] << "\t"
//<< "Flag_valid_tracking: " << std::setw(1) << in[0][0].Flag_valid_tracking << " " << std::setw(1) << in[0][0].Flag_valid_tracking << "\t" // << "Flag_valid_tracking: " << std::setw(1) << in[0][0].Flag_valid_tracking << " " << std::setw(1) << in[0][0].Flag_valid_tracking << "\t"
<< "d_corr_paired: " << std::setw(10) << d_corr_paired << "\t" << "d_corr_paired: " << std::setw(10) << d_corr_paired << "\t"
<< "d_corr_shifted: " << std::setw(10) << d_corr_shifted << "\t" << "d_corr_shifted: " << std::setw(10) << d_corr_shifted << "\t"
<< "corr_diff: " << std::setw(10) << corr_diff << "\t" << "corr_diff: " << std::setw(10) << corr_diff << "\t"
@ -425,7 +425,7 @@ int sbas_l1_telemetry_decoder_gs::general_work(int noutput_items __attribute__((
// 1. Copy the current tracking output // 1. Copy the current tracking output
current_symbol = in[0]; current_symbol = in[0];
// copy correlation samples into samples vector // copy correlation samples into samples vector
d_sample_buf.push_back(current_symbol.Prompt_I); //add new symbol to the symbol queue d_sample_buf.push_back(current_symbol.Prompt_I); // add new symbol to the symbol queue
// store the time stamp of the first sample in the processed sample block // store the time stamp of the first sample in the processed sample block
double sample_stamp = static_cast<double>(in[0].Tracking_sample_counter) / static_cast<double>(in[0].fs); double sample_stamp = static_cast<double>(in[0].Tracking_sample_counter) / static_cast<double>(in[0].fs);
@ -455,7 +455,7 @@ int sbas_l1_telemetry_decoder_gs::general_work(int noutput_items __attribute__((
// compute message sample stamp // compute message sample stamp
// and fill messages in SBAS raw message objects // and fill messages in SBAS raw message objects
//std::vector<Sbas_Raw_Msg> sbas_raw_msgs; // std::vector<Sbas_Raw_Msg> sbas_raw_msgs;
for (const auto &valid_msg : valid_msgs) for (const auto &valid_msg : valid_msgs)
{ {
int32_t message_sample_offset = int32_t message_sample_offset =
@ -468,16 +468,16 @@ int sbas_l1_telemetry_decoder_gs::general_work(int noutput_items __attribute__((
<< " relative_preamble_start=" << valid_msg.first << " relative_preamble_start=" << valid_msg.first
<< " message_sample_offset=" << message_sample_offset << " message_sample_offset=" << message_sample_offset
<< ")"; << ")";
//Sbas_Raw_Msg sbas_raw_msg(message_sample_stamp, this->d_satellite.get_PRN(), it->second); // Sbas_Raw_Msg sbas_raw_msg(message_sample_stamp, this->d_satellite.get_PRN(), it->second);
//sbas_raw_msgs.push_back(sbas_raw_msg); // sbas_raw_msgs.push_back(sbas_raw_msg);
} }
// parse messages // parse messages
// and send them to the SBAS raw message queue // and send them to the SBAS raw message queue
//for(std::vector<Sbas_Raw_Msg>::iterator it = sbas_raw_msgs.begin(); it != sbas_raw_msgs.end(); it++) // for(std::vector<Sbas_Raw_Msg>::iterator it = sbas_raw_msgs.begin(); it != sbas_raw_msgs.end(); it++)
// { // {
//std::cout << "SBAS message type " << it->get_msg_type() << " from PRN" << it->get_prn() << " received" << std::endl; // std::cout << "SBAS message type " << it->get_msg_type() << " from PRN" << it->get_prn() << " received" << std::endl;
//sbas_telemetry_data.update(*it); // sbas_telemetry_data.update(*it);
// } // }
// clear all processed samples in the input buffer // clear all processed samples in the input buffer

View File

@ -154,7 +154,7 @@ void Viterbi_Decoder::init_trellis_state()
for (state = 0; state < d_states; state++) for (state = 0; state < d_states; state++)
{ {
d_pm_t[state] = -MAXLOG; d_pm_t[state] = -MAXLOG;
//d_pm_t_next[state] = -MAXLOG; // d_pm_t_next[state] = -MAXLOG;
} }
d_pm_t[0] = 0; /* start in all-zeros state */ d_pm_t[0] = 0; /* start in all-zeros state */
@ -237,7 +237,7 @@ int Viterbi_Decoder::do_acs(const double sym[], int nbits)
d_trellis_paths.push_front(next_trellis_states); d_trellis_paths.push_front(next_trellis_states);
/* normalize -> afterwards, the largest metric value is always 0 */ /* normalize -> afterwards, the largest metric value is always 0 */
//max_val = 0; // max_val = 0;
max_val = -MAXLOG; max_val = -MAXLOG;
for (state_at_t = 0; state_at_t < d_states; state_at_t++) for (state_at_t = 0; state_at_t < d_states; state_at_t++)
{ {
@ -301,7 +301,7 @@ int Viterbi_Decoder::do_tb_and_decode(int traceback_length, int requested_decodi
{ {
state = it->get_anchestor_state_of_current_state(state); state = it->get_anchestor_state_of_current_state(state);
} }
t_out = d_trellis_paths.end() - (d_trellis_paths.begin() + traceback_length + overstep_length) - 1; //requested_decoding_length-1; t_out = d_trellis_paths.end() - (d_trellis_paths.begin() + traceback_length + overstep_length) - 1; // requested_decoding_length-1;
indicator_metric = 0; indicator_metric = 0;
for (it = d_trellis_paths.begin() + traceback_length + overstep_length; it < d_trellis_paths.end(); ++it) for (it = d_trellis_paths.begin() + traceback_length + overstep_length; it < d_trellis_paths.end(); ++it)
{ {
@ -352,16 +352,17 @@ float Viterbi_Decoder::gamma(const float rec_array[], int symbol, int nn)
for (i = 0; i < nn; i++) for (i = 0; i < nn; i++)
{ {
//if (symbol & mask) rm += rec_array[nn - i - 1]; // if (symbol & mask) rm += rec_array[nn - i - 1];
txsym = symbol & mask ? 1 : -1; txsym = symbol & mask ? 1 : -1;
rm += txsym * rec_array[nn - i - 1]; rm += txsym * rec_array[nn - i - 1];
mask = mask << 1U; mask = mask << 1U;
} }
//rm = rm > 50 ? rm : -1000; // rm = rm > 50 ? rm : -1000;
return (rm); return (rm);
} }
/* function that creates the transit and output vectors */ /* function that creates the transit and output vectors */
void Viterbi_Decoder::nsc_transit(int output_p[], int trans_p[], int input, const int g[], void Viterbi_Decoder::nsc_transit(int output_p[], int trans_p[], int input, const int g[],
int KK, int nn) int KK, int nn)
@ -528,7 +529,7 @@ Viterbi_Decoder::Prev::~Prev()
delete[] bit; delete[] bit;
delete[] metric; delete[] metric;
delete refcount; delete refcount;
//std::cout << "~Prev(" << "?" << ", " << t << ")" << " destructor with delete" << std::endl; // std::cout << "~Prev(" << "?" << ", " << t << ")" << " destructor with delete" << std::endl;
} }
else else
{ {
@ -543,20 +544,20 @@ Viterbi_Decoder::Prev::~Prev()
int Viterbi_Decoder::Prev::get_anchestor_state_of_current_state(int current_state) int Viterbi_Decoder::Prev::get_anchestor_state_of_current_state(int current_state)
{ {
//std::cout << "get prev state: for state " << current_state << " at time " << t << ", the prev state at time " << t-1 << " is " << state[current_state] << std::endl; // std::cout << "get prev state: for state " << current_state << " at time " << t << ", the prev state at time " << t-1 << " is " << state[current_state] << std::endl;
if (num_states > current_state) if (num_states > current_state)
{ {
return state[current_state]; return state[current_state];
} }
//std::cout<<"alarm "<<"num_states="<<num_states<<" current_state="<<current_state<<std::endl; // std::cout<<"alarm "<<"num_states="<<num_states<<" current_state="<<current_state<<std::endl;
//return state[current_state]; // return state[current_state];
return 0; return 0;
} }
int Viterbi_Decoder::Prev::get_bit_of_current_state(int current_state) int Viterbi_Decoder::Prev::get_bit_of_current_state(int current_state)
{ {
//std::cout << "get prev bit : for state " << current_state << " at time " << t << ", the send bit is " << bit[current_state] << std::endl; // std::cout << "get prev bit : for state " << current_state << " at time " << t << ", the send bit is " << bit[current_state] << std::endl;
if (num_states > current_state) if (num_states > current_state)
{ {
return bit[current_state]; return bit[current_state];

View File

@ -58,7 +58,7 @@ GpsL1CaDllPllTrackingGPU::GpsL1CaDllPllTrackingGPU(
float dll_bw_hz; float dll_bw_hz;
float early_late_space_chips; float early_late_space_chips;
item_type = configuration->property(role + ".item_type", default_item_type); item_type = configuration->property(role + ".item_type", default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048); // vector_length = configuration->property(role + ".vector_length", 2048);
int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000); int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated); fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
dump = configuration->property(role + ".dump", false); dump = configuration->property(role + ".dump", false);
@ -71,7 +71,7 @@ GpsL1CaDllPllTrackingGPU::GpsL1CaDllPllTrackingGPU(
dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)); vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ################### // ################# MAKE TRACKING GNURadio object ###################
if (item_type.compare("gr_complex") == 0) if (item_type.compare("gr_complex") == 0)
{ {
item_size_ = sizeof(gr_complex); item_size_ = sizeof(gr_complex);
@ -139,7 +139,7 @@ void GpsL1CaDllPllTrackingGPU::connect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to connect, now the tracking uses gr_sync_decimator // nothing to connect, now the tracking uses gr_sync_decimator
} }
@ -148,7 +148,7 @@ void GpsL1CaDllPllTrackingGPU::disconnect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }

View File

@ -57,7 +57,7 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
float early_late_space_chips; float early_late_space_chips;
size_t port_ch0; size_t port_ch0;
item_type = configuration->property(role + ".item_type", default_item_type); item_type = configuration->property(role + ".item_type", default_item_type);
//vector_length = configuration->property(role + ".vector_length", 2048); // vector_length = configuration->property(role + ".vector_length", 2048);
int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000); int fs_in_deprecated = configuration->property("GNSS-SDR.internal_fs_hz", 2048000);
fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated); fs_in = configuration->property("GNSS-SDR.internal_fs_sps", fs_in_deprecated);
dump = configuration->property(role + ".dump", false); dump = configuration->property(role + ".dump", false);
@ -67,7 +67,7 @@ GpsL1CaTcpConnectorTracking::GpsL1CaTcpConnectorTracking(
dump_filename = configuration->property(role + ".dump_filename", default_dump_filename); dump_filename = configuration->property(role + ".dump_filename", default_dump_filename);
vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS)); vector_length = std::round(fs_in / (GPS_L1_CA_CODE_RATE_HZ / GPS_L1_CA_CODE_LENGTH_CHIPS));
//################# MAKE TRACKING GNURadio object ################### // ################# MAKE TRACKING GNURadio object ###################
if (item_type == "gr_complex") if (item_type == "gr_complex")
{ {
item_size_ = sizeof(gr_complex); item_size_ = sizeof(gr_complex);
@ -129,7 +129,7 @@ void GpsL1CaTcpConnectorTracking::connect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to connect, now the tracking uses gr_sync_decimator // nothing to connect, now the tracking uses gr_sync_decimator
} }
@ -138,7 +138,7 @@ void GpsL1CaTcpConnectorTracking::disconnect(gr::top_block_sptr top_block)
if (top_block) if (top_block)
{ /* top_block is not null */ { /* top_block is not null */
}; };
//nothing to disconnect, now the tracking uses gr_sync_decimator // nothing to disconnect, now the tracking uses gr_sync_decimator
} }

View File

@ -285,7 +285,7 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(const Dll_Pll_Conf &conf_) : gr::bl
d_code_period = BEIDOU_B1I_CODE_PERIOD; d_code_period = BEIDOU_B1I_CODE_PERIOD;
d_code_chip_rate = BEIDOU_B1I_CODE_RATE_HZ; d_code_chip_rate = BEIDOU_B1I_CODE_RATE_HZ;
d_code_length_chips = static_cast<uint32_t>(BEIDOU_B1I_CODE_LENGTH_CHIPS); d_code_length_chips = static_cast<uint32_t>(BEIDOU_B1I_CODE_LENGTH_CHIPS);
d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = true; d_secondary = true;
@ -303,7 +303,7 @@ dll_pll_veml_tracking::dll_pll_veml_tracking(const Dll_Pll_Conf &conf_) : gr::bl
d_code_period = BEIDOU_B3I_CODE_PERIOD; d_code_period = BEIDOU_B3I_CODE_PERIOD;
d_code_chip_rate = BEIDOU_B3I_CODE_RATE_HZ; d_code_chip_rate = BEIDOU_B3I_CODE_RATE_HZ;
d_code_length_chips = static_cast<uint32_t>(BEIDOU_B3I_CODE_LENGTH_CHIPS); d_code_length_chips = static_cast<uint32_t>(BEIDOU_B3I_CODE_LENGTH_CHIPS);
d_symbols_per_bit = BEIDOU_B3I_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B3I_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = false; d_secondary = false;
@ -641,7 +641,7 @@ void dll_pll_veml_tracking::start_tracking()
// GEO Satellites use different secondary code // GEO Satellites use different secondary code
if (d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6) if (d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6)
{ {
d_symbols_per_bit = BEIDOU_B1I_GEO_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B1I_GEO_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = false; d_secondary = false;
@ -654,7 +654,7 @@ void dll_pll_veml_tracking::start_tracking()
} }
else else
{ {
d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B1I_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = true; d_secondary = true;
@ -674,7 +674,7 @@ void dll_pll_veml_tracking::start_tracking()
// Update secondary code settings for geo satellites // Update secondary code settings for geo satellites
if (d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6) if (d_acquisition_gnss_synchro->PRN > 0 and d_acquisition_gnss_synchro->PRN < 6)
{ {
d_symbols_per_bit = BEIDOU_B3I_GEO_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B3I_GEO_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = false; d_secondary = false;
@ -687,7 +687,7 @@ void dll_pll_veml_tracking::start_tracking()
} }
else else
{ {
d_symbols_per_bit = BEIDOU_B3I_TELEMETRY_SYMBOLS_PER_BIT; //todo: enable after fixing beidou symbol synchronization d_symbols_per_bit = BEIDOU_B3I_TELEMETRY_SYMBOLS_PER_BIT; // todo: enable after fixing beidou symbol synchronization
d_correlation_length_ms = 1; d_correlation_length_ms = 1;
d_code_samples_per_chip = 1; d_code_samples_per_chip = 1;
d_secondary = true; d_secondary = true;
@ -1193,7 +1193,7 @@ void dll_pll_veml_tracking::save_correlation_results()
else else
{ {
d_P_data_accu += *d_Prompt; d_P_data_accu += *d_Prompt;
//std::cout << "s[" << d_current_data_symbol << "]=" << (int)((*d_Prompt).real() > 0) << std::endl; // std::cout << "s[" << d_current_data_symbol << "]=" << (int)((*d_Prompt).real() > 0) << std::endl;
} }
d_current_data_symbol++; d_current_data_symbol++;
d_current_data_symbol %= d_symbols_per_bit; d_current_data_symbol %= d_symbols_per_bit;

View File

@ -128,7 +128,7 @@ private:
float *d_local_code_shift_chips; float *d_local_code_shift_chips;
float *d_prompt_data_shift; float *d_prompt_data_shift;
Cpu_Multicorrelator_Real_Codes multicorrelator_cpu; Cpu_Multicorrelator_Real_Codes multicorrelator_cpu;
Cpu_Multicorrelator_Real_Codes correlator_data_cpu; //for data channel Cpu_Multicorrelator_Real_Codes correlator_data_cpu; // for data channel
/* TODO: currently the multicorrelator does not support adding extra correlator /* TODO: currently the multicorrelator does not support adding extra correlator
with different local code, thus we need extra multicorrelator instance. with different local code, thus we need extra multicorrelator instance.

View File

@ -1601,7 +1601,7 @@ int dll_pll_veml_tracking_fpga::general_work(int noutput_items __attribute__((un
d_state = 1; // loss-of-lock detected d_state = 1; // loss-of-lock detected
// send something to let the scheduler know that it has to keep on calling general work and to finish the loop // send something to let the scheduler know that it has to keep on calling general work and to finish the loop
//current_synchro_data.Flag_valid_symbol_output=1; // current_synchro_data.Flag_valid_symbol_output=1;
} }
else else
{ {
@ -1793,7 +1793,7 @@ int dll_pll_veml_tracking_fpga::general_work(int noutput_items __attribute__((un
d_state = 1; // loss-of-lock detected d_state = 1; // loss-of-lock detected
// send something to let the scheduler know that it has to keep on calling general work and to finish the loop // send something to let the scheduler know that it has to keep on calling general work and to finish the loop
//current_synchro_data.Flag_valid_symbol_output=1; // current_synchro_data.Flag_valid_symbol_output=1;
} }
else else
{ {
@ -1900,7 +1900,7 @@ int dll_pll_veml_tracking_fpga::general_work(int noutput_items __attribute__((un
d_state = 1; // loss-of-lock detected d_state = 1; // loss-of-lock detected
// send something to let the scheduler know that it has to keep on calling general work and to finish the loop // send something to let the scheduler know that it has to keep on calling general work and to finish the loop
//current_synchro_data.Flag_valid_symbol_output=1; // current_synchro_data.Flag_valid_symbol_output=1;
} }
else else
{ {

View File

@ -143,7 +143,6 @@ private:
std::string *d_data_secondary_code_string; std::string *d_data_secondary_code_string;
std::string signal_pretty_name; std::string signal_pretty_name;
// dll filter buffer // dll filter buffer
boost::circular_buffer<float> d_dll_filt_history; boost::circular_buffer<float> d_dll_filt_history;
// tracking state machine // tracking state machine
@ -252,4 +251,4 @@ private:
bool d_stop_tracking; bool d_stop_tracking;
}; };
#endif //GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H #endif // GNSS_SDR_DLL_PLL_VEML_TRACKING_FPGA_H

View File

@ -144,7 +144,7 @@ Galileo_E1_Tcp_Connector_Tracking_cc::Galileo_E1_Tcp_Connector_Tracking_cc(
multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_chips = GALILEO_E1_CODE_CHIP_RATE_HZ; d_code_freq_chips = GALILEO_E1_CODE_CHIP_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -327,9 +327,9 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset);
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
d_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset); //count for the processed samples d_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset); // count for the processed samples
d_pull_in = false; d_pull_in = false;
consume_each(samples_offset); //shift input to perform alignment with local replica consume_each(samples_offset); // shift input to perform alignment with local replica
return 1; return 1;
} }
@ -348,10 +348,10 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
d_correlation_length_samples); d_correlation_length_samples);
// ################## TCP CONNECTOR ########################################################## // ################## TCP CONNECTOR ##########################################################
//! Variable used for control // Variable used for control
d_control_id++; d_control_id++;
//! Send and receive a TCP packet // Send and receive a TCP packet
boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> tx_variables_array = {{d_control_id, boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> tx_variables_array = {{d_control_id,
(*d_Very_Early).real(), (*d_Very_Early).real(),
(*d_Very_Early).imag(), (*d_Very_Early).imag(),
@ -374,18 +374,18 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
d_carrier_doppler_hz = d_acq_carrier_doppler_hz + carr_error_filt_hz; d_carrier_doppler_hz = d_acq_carrier_doppler_hz + carr_error_filt_hz;
// New code Doppler frequency estimation // New code Doppler frequency estimation
d_code_freq_chips = GALILEO_E1_CODE_CHIP_RATE_HZ + ((d_carrier_doppler_hz * GALILEO_E1_CODE_CHIP_RATE_HZ) / GALILEO_E1_FREQ_HZ); d_code_freq_chips = GALILEO_E1_CODE_CHIP_RATE_HZ + ((d_carrier_doppler_hz * GALILEO_E1_CODE_CHIP_RATE_HZ) / GALILEO_E1_FREQ_HZ);
//carrier phase accumulator for (K) doppler estimation // carrier phase accumulator for (K) doppler estimation
d_acc_carrier_phase_rad -= GPS_TWO_PI * d_carrier_doppler_hz * GALILEO_E1_CODE_PERIOD; d_acc_carrier_phase_rad -= GPS_TWO_PI * d_carrier_doppler_hz * GALILEO_E1_CODE_PERIOD;
//remnant carrier phase to prevent overflow in the code NCO // remnant carrier phase to prevent overflow in the code NCO
d_rem_carr_phase_rad = d_rem_carr_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * GALILEO_E1_CODE_PERIOD; d_rem_carr_phase_rad = d_rem_carr_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * GALILEO_E1_CODE_PERIOD;
d_rem_carr_phase_rad = fmod(d_rem_carr_phase_rad, GPS_TWO_PI); d_rem_carr_phase_rad = fmod(d_rem_carr_phase_rad, GPS_TWO_PI);
// ################## DLL ########################################################## // ################## DLL ##########################################################
// DLL discriminator, carrier loop filter implementation and NCO command generation (TCP_connector) // DLL discriminator, carrier loop filter implementation and NCO command generation (TCP_connector)
code_error_filt_chips = tcp_data.proc_pack_code_error; code_error_filt_chips = tcp_data.proc_pack_code_error;
//Code phase accumulator // Code phase accumulator
float code_error_filt_secs; float code_error_filt_secs;
code_error_filt_secs = (GALILEO_E1_CODE_PERIOD * code_error_filt_chips) / GALILEO_E1_CODE_CHIP_RATE_HZ; //[seconds] code_error_filt_secs = (GALILEO_E1_CODE_PERIOD * code_error_filt_chips) / GALILEO_E1_CODE_CHIP_RATE_HZ; // [seconds]
d_acc_code_phase_secs = d_acc_code_phase_secs + code_error_filt_secs; d_acc_code_phase_secs = d_acc_code_phase_secs + code_error_filt_secs;
// ################## CARRIER AND CODE NCO BUFFER ALIGNMENT ####################### // ################## CARRIER AND CODE NCO BUFFER ALIGNMENT #######################
@ -399,8 +399,8 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
T_prn_seconds = T_chip_seconds * GALILEO_E1_B_CODE_LENGTH_CHIPS; T_prn_seconds = T_chip_seconds * GALILEO_E1_B_CODE_LENGTH_CHIPS;
T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in); T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in); K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
d_current_prn_length_samples = round(K_blk_samples); //round to a discrete samples d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
//d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample // d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample
// ####### CN0 ESTIMATION AND LOCK DETECTORS ###### // ####### CN0 ESTIMATION AND LOCK DETECTORS ######
if (d_cn0_estimation_counter < FLAGS_cn0_samples) if (d_cn0_estimation_counter < FLAGS_cn0_samples)
@ -435,7 +435,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
@ -448,7 +448,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
// Tracking_timestamp_secs is aligned with the PRN start sample // Tracking_timestamp_secs is aligned with the PRN start sample
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples);
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; // rounding error < 1 sample
current_synchro_data.Carrier_phase_rads = static_cast<double>(d_acc_carrier_phase_rad); current_synchro_data.Carrier_phase_rads = static_cast<double>(d_acc_carrier_phase_rad);
current_synchro_data.Carrier_Doppler_hz = static_cast<double>(d_carrier_doppler_hz); current_synchro_data.Carrier_Doppler_hz = static_cast<double>(d_carrier_doppler_hz);
current_synchro_data.CN0_dB_hz = static_cast<double>(d_CN0_SNV_dB_Hz); current_synchro_data.CN0_dB_hz = static_cast<double>(d_CN0_SNV_dB_Hz);
@ -461,11 +461,11 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
*d_Prompt = gr_complex(0, 0); *d_Prompt = gr_complex(0, 0);
*d_Late = gr_complex(0, 0); *d_Late = gr_complex(0, 0);
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples);
//! When tracking is disabled an array of 1's is sent to maintain the TCP connection // When tracking is disabled an array of 1's is sent to maintain the TCP connection
boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> tx_variables_array = {{1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0}}; boost::array<float, NUM_TX_VARIABLES_GALILEO_E1> tx_variables_array = {{1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0}};
d_tcp_com.send_receive_tcp_packet_galileo_e1(tx_variables_array, &tcp_data); d_tcp_com.send_receive_tcp_packet_galileo_e1(tx_variables_array, &tcp_data);
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.System = {'E'}; current_synchro_data.System = {'E'};
current_synchro_data.Signal[0] = '1'; current_synchro_data.Signal[0] = '1';
current_synchro_data.Signal[1] = 'B'; current_synchro_data.Signal[1] = 'B';
@ -541,7 +541,7 @@ int Galileo_E1_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attri
} }
} }
consume_each(d_current_prn_length_samples); // this is needed in gr::block derivates consume_each(d_current_prn_length_samples); // this is needed in gr::block derivates
d_sample_counter += d_current_prn_length_samples; //count for the processed samples d_sample_counter += d_current_prn_length_samples; // count for the processed samples
if (d_enable_tracking) if (d_enable_tracking)
{ {

View File

@ -157,11 +157,11 @@ private:
float d_control_id; float d_control_id;
Tcp_Communication d_tcp_com; Tcp_Communication d_tcp_com;
//PRN period in samples // PRN period in samples
int32_t d_current_prn_length_samples; int32_t d_current_prn_length_samples;
int32_t d_next_prn_length_samples; int32_t d_next_prn_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -185,4 +185,4 @@ private:
std::string sys; std::string sys;
}; };
#endif //GNSS_SDR_GALILEO_E1_TCP_CONNECTOR_TRACKING_CC_H #endif // GNSS_SDR_GALILEO_E1_TCP_CONNECTOR_TRACKING_CC_H

View File

@ -83,16 +83,16 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
void glonass_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg) void glonass_l1_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); // pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) // avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(std::move(msg)); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
@ -160,7 +160,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc::glonass_l1_ca_dll_pll_c_aid_tracking_cc
multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_chips = GLONASS_L1_CA_CODE_RATE_HZ; d_code_freq_chips = GLONASS_L1_CA_CODE_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -169,7 +169,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc::glonass_l1_ca_dll_pll_c_aid_tracking_cc
d_rem_carrier_phase_rad = 0.0; d_rem_carrier_phase_rad = 0.0;
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; //(from trk to tlm) d_sample_counter = 0ULL; // (from trk to tlm)
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
d_pull_in = false; d_pull_in = false;
@ -212,7 +212,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_cc::glonass_l1_ca_dll_pll_c_aid_tracking_cc
d_glonass_freq_ch = 0; d_glonass_freq_ch = 0;
//set_min_output_buffer((int64_t)300); // set_min_output_buffer((int64_t)300);
} }
@ -227,7 +227,7 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
@ -731,24 +731,24 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
double K_prn_samples = round(T_prn_samples); double K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples; double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in); d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); // (code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in);
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI; d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI;
// UPDATE ACCUMULATED CARRIER PHASE // UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in)); CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad] // remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI); d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI);
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips] // remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in)); d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### // ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
@ -781,7 +781,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -825,7 +825,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
current_synchro_data.System = {'R'}; current_synchro_data.System = {'R'};
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples);
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
if (d_dump) if (d_dump)
@ -896,7 +896,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
} }
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples d_sample_counter += d_correlation_length_samples; // count for the processed samples
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
} }

View File

@ -42,7 +42,7 @@
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "tracking_2nd_DLL_filter.h" #include "tracking_2nd_DLL_filter.h"
#include "tracking_FLL_PLL_filter.h" #include "tracking_FLL_PLL_filter.h"
//#include "tracking_loop_filter.h" // #include "tracking_loop_filter.h"
#include "cpu_multicorrelator.h" #include "cpu_multicorrelator.h"
#include <gnuradio/block.h> #include <gnuradio/block.h>
#include <pmt/pmt.h> #include <pmt/pmt.h>
@ -135,7 +135,7 @@ private:
int32_t d_rem_code_phase_integer_samples; int32_t d_rem_code_phase_integer_samples;
// PLL and DLL filter library // PLL and DLL filter library
//Tracking_2nd_DLL_filter d_code_loop_filter; // Tracking_2nd_DLL_filter d_code_loop_filter;
Tracking_2nd_DLL_filter d_code_loop_filter; Tracking_2nd_DLL_filter d_code_loop_filter;
Tracking_FLL_PLL_filter d_carrier_loop_filter; Tracking_FLL_PLL_filter d_carrier_loop_filter;
@ -172,10 +172,10 @@ private:
bool d_preamble_synchronized; bool d_preamble_synchronized;
void msg_handler_preamble_index(pmt::pmt_t msg); void msg_handler_preamble_index(pmt::pmt_t msg);
//Integration period in samples // Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -201,4 +201,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H #endif // GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H

View File

@ -81,16 +81,16 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
void glonass_l1_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pmt_t msg) void glonass_l1_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); // pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) // avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(std::move(msg)); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
@ -98,6 +98,7 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pm
} }
} }
glonass_l1_ca_dll_pll_c_aid_tracking_sc::glonass_l1_ca_dll_pll_c_aid_tracking_sc( glonass_l1_ca_dll_pll_c_aid_tracking_sc::glonass_l1_ca_dll_pll_c_aid_tracking_sc(
int64_t fs_in, int64_t fs_in,
uint32_t vector_length, uint32_t vector_length,
@ -167,7 +168,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_sc::glonass_l1_ca_dll_pll_c_aid_tracking_sc
d_rem_carrier_phase_rad = 0.0; d_rem_carrier_phase_rad = 0.0;
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; //(from trk to tlm) d_sample_counter = 0ULL; // (from trk to tlm)
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
d_pull_in = false; d_pull_in = false;
@ -208,7 +209,7 @@ glonass_l1_ca_dll_pll_c_aid_tracking_sc::glonass_l1_ca_dll_pll_c_aid_tracking_sc
d_carrier_doppler_old_hz = 0.0; d_carrier_doppler_old_hz = 0.0;
d_glonass_freq_ch = 0; d_glonass_freq_ch = 0;
//set_min_output_buffer((int64_t)300); // set_min_output_buffer((int64_t)300);
} }
@ -223,7 +224,7 @@ void glonass_l1_ca_dll_pll_c_aid_tracking_sc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
@ -693,7 +694,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
{ {
// ################## PLL ########################################################## // ################## PLL ##########################################################
// Update PLL discriminator [rads/Ti -> Secs/Ti] // Update PLL discriminator [rads/Ti -> Secs/Ti]
d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex<float>(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())) / GLONASS_TWO_PI; //prompt output d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex<float>(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())) / GLONASS_TWO_PI; // prompt output
d_carrier_doppler_old_hz = d_carrier_doppler_hz; d_carrier_doppler_old_hz = d_carrier_doppler_hz;
// Carrier discriminator filter // Carrier discriminator filter
// NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan // NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan
@ -721,24 +722,24 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
double K_prn_samples = round(T_prn_samples); double K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples; double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in); d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); // (code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in);
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI; d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI;
// UPDATE ACCUMULATED CARRIER PHASE // UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in)); CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad] // remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI); d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI);
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips] // remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in)); d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### // ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
@ -771,7 +772,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -886,7 +887,7 @@ int glonass_l1_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
} }
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples d_sample_counter += d_correlation_length_samples; // count for the processed samples
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
} }

View File

@ -126,9 +126,9 @@ private:
gr_complex* d_ca_code; gr_complex* d_ca_code;
lv_16sc_t* d_ca_code_16sc; lv_16sc_t* d_ca_code_16sc;
float* d_local_code_shift_chips; float* d_local_code_shift_chips;
//gr_complex* d_correlator_outs; // gr_complex* d_correlator_outs;
lv_16sc_t* d_correlator_outs_16sc; lv_16sc_t* d_correlator_outs_16sc;
//cpu_multicorrelator multicorrelator_cpu; // cpu_multicorrelator multicorrelator_cpu;
Cpu_Multicorrelator_16sc multicorrelator_cpu_16sc; Cpu_Multicorrelator_16sc multicorrelator_cpu_16sc;
// remaining code phase and carrier phase between tracking loops // remaining code phase and carrier phase between tracking loops
@ -174,10 +174,10 @@ private:
std::deque<lv_16sc_t> d_P_history; std::deque<lv_16sc_t> d_P_history;
std::deque<lv_16sc_t> d_L_history; std::deque<lv_16sc_t> d_L_history;
//Integration period in samples // Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -203,4 +203,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_SC_H #endif // GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_SC_H

View File

@ -77,7 +77,7 @@ void Glonass_L1_Ca_Dll_Pll_Tracking_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
@ -106,7 +106,7 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
d_code_loop_filter.set_DLL_BW(dll_bw_hz); d_code_loop_filter.set_DLL_BW(dll_bw_hz);
d_carrier_loop_filter.set_PLL_BW(pll_bw_hz); d_carrier_loop_filter.set_PLL_BW(pll_bw_hz);
//--- DLL variables -------------------------------------------------------- // --- DLL variables -------------------------------------------------------
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips) d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
// Initialization of local code replica // Initialization of local code replica
@ -128,7 +128,7 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
multicorrelator_cpu.init(2 * d_current_prn_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_current_prn_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_chips = GLONASS_L1_CA_CODE_RATE_HZ; d_code_freq_chips = GLONASS_L1_CA_CODE_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -138,7 +138,7 @@ Glonass_L1_Ca_Dll_Pll_Tracking_cc::Glonass_L1_Ca_Dll_Pll_Tracking_cc(
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; d_sample_counter = 0ULL;
//d_sample_counter_seconds = 0; // d_sample_counter_seconds = 0;
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
@ -184,7 +184,7 @@ void Glonass_L1_Ca_Dll_Pll_Tracking_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in); acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in);
// Doppler effect // Doppler effect
@ -581,19 +581,19 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); // [chips/second] code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); // [chips/second]
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips); double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS; double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS;
double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips * T_chip_seconds); //[seconds] double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips * T_chip_seconds); // [seconds]
//double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GLONASS_L1_CA_CODE_RATE_HZ; // [seconds] // double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GLONASS_L1_CA_CODE_RATE_HZ; // [seconds]
// ################## CARRIER AND CODE NCO BUFFER ALIGNMENT ####################### // ################## CARRIER AND CODE NCO BUFFER ALIGNMENT #######################
// keep alignment parameters for the next input buffer // keep alignment parameters for the next input buffer
// Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation // Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation
//double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips); // double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
//double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS; // double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS;
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in); double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in); double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
// carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_doppler_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_doppler_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_frequency_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_frequency_hz / static_cast<double>(d_fs_in);
@ -603,7 +603,7 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
// carrier phase accumulator // carrier phase accumulator
d_acc_carrier_phase_rad -= d_carrier_doppler_phase_step_rad * d_current_prn_length_samples; d_acc_carrier_phase_rad -= d_carrier_doppler_phase_step_rad * d_current_prn_length_samples;
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
// code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
// remnant code phase [chips] // remnant code phase [chips]
@ -614,7 +614,7 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES) if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES)
{ {
// fill buffer with prompt correlator output values // fill buffer with prompt correlator output values
d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; //prompt d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; // prompt
d_cn0_estimation_counter++; d_cn0_estimation_counter++;
} }
else else
@ -668,7 +668,7 @@ int Glonass_L1_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
current_synchro_data.correlation_length_ms = 1; current_synchro_data.correlation_length_ms = 1;
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
if (d_dump) if (d_dump)

View File

@ -129,7 +129,6 @@ private:
gr_complex* d_correlator_outs; gr_complex* d_correlator_outs;
Cpu_Multicorrelator multicorrelator_cpu; Cpu_Multicorrelator multicorrelator_cpu;
// tracking vars // tracking vars
double d_code_freq_chips; double d_code_freq_chips;
double d_code_phase_step_chips; double d_code_phase_step_chips;
@ -140,10 +139,10 @@ private:
double d_acc_carrier_phase_rad; double d_acc_carrier_phase_rad;
double d_code_phase_samples; double d_code_phase_samples;
//PRN period in samples // PRN period in samples
int32_t d_current_prn_length_samples; int32_t d_current_prn_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -169,4 +168,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L1_CA_DLL_PLL_TRACKING_CC_H #endif // GNSS_SDR_GLONASS_L1_CA_DLL_PLL_TRACKING_CC_H

View File

@ -80,16 +80,16 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
void glonass_l2_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg) void glonass_l2_ca_dll_pll_c_aid_tracking_cc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); // pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) // avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(std::move(msg)); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
@ -157,7 +157,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc::glonass_l2_ca_dll_pll_c_aid_tracking_cc
multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_chips = GLONASS_L2_CA_CODE_RATE_HZ; d_code_freq_chips = GLONASS_L2_CA_CODE_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -166,7 +166,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc::glonass_l2_ca_dll_pll_c_aid_tracking_cc
d_rem_carrier_phase_rad = 0.0; d_rem_carrier_phase_rad = 0.0;
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; //(from trk to tlm) d_sample_counter = 0ULL; // (from trk to tlm)
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
d_pull_in = false; d_pull_in = false;
@ -209,7 +209,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_cc::glonass_l2_ca_dll_pll_c_aid_tracking_cc
d_glonass_freq_ch = 0; d_glonass_freq_ch = 0;
//set_min_output_buffer((int64_t)300); // set_min_output_buffer((int64_t)300);
} }
@ -224,7 +224,7 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
@ -729,24 +729,24 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
double K_prn_samples = round(T_prn_samples); double K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples; double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in); d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); // (code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in);
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
//################### PLL COMMANDS ################################################# //################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI; d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI;
// UPDATE ACCUMULATED CARRIER PHASE // UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in)); CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad] // remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI); d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI);
//################### DLL COMMANDS ################################################# //################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips] // remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in)); d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### // ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
@ -779,7 +779,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -823,7 +823,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
current_synchro_data.System = {'R'}; current_synchro_data.System = {'R'};
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples);
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
if (d_dump) if (d_dump)
@ -894,7 +894,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_cc::general_work(int noutput_items __at
} }
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples d_sample_counter += d_correlation_length_samples; // count for the processed samples
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
} }

View File

@ -40,7 +40,7 @@
#include "gnss_synchro.h" #include "gnss_synchro.h"
#include "tracking_2nd_DLL_filter.h" #include "tracking_2nd_DLL_filter.h"
#include "tracking_FLL_PLL_filter.h" #include "tracking_FLL_PLL_filter.h"
//#include "tracking_loop_filter.h" // #include "tracking_loop_filter.h"
#include "cpu_multicorrelator.h" #include "cpu_multicorrelator.h"
#include <gnuradio/block.h> #include <gnuradio/block.h>
#include <pmt/pmt.h> #include <pmt/pmt.h>
@ -133,7 +133,7 @@ private:
int32_t d_rem_code_phase_integer_samples; int32_t d_rem_code_phase_integer_samples;
// PLL and DLL filter library // PLL and DLL filter library
//Tracking_2nd_DLL_filter d_code_loop_filter; // Tracking_2nd_DLL_filter d_code_loop_filter;
Tracking_2nd_DLL_filter d_code_loop_filter; Tracking_2nd_DLL_filter d_code_loop_filter;
Tracking_FLL_PLL_filter d_carrier_loop_filter; Tracking_FLL_PLL_filter d_carrier_loop_filter;
@ -170,10 +170,10 @@ private:
bool d_preamble_synchronized; bool d_preamble_synchronized;
void msg_handler_preamble_index(pmt::pmt_t msg); void msg_handler_preamble_index(pmt::pmt_t msg);
//Integration period in samples // Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -199,4 +199,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H #endif // GNSS_SDR_GLONASS_L1_CA_DLL_PLL_C_AID_TRACKING_CC_H

View File

@ -79,16 +79,16 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_sc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
void glonass_l2_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pmt_t msg) void glonass_l2_ca_dll_pll_c_aid_tracking_sc::msg_handler_preamble_index(pmt::pmt_t msg)
{ {
//pmt::print(msg); // pmt::print(msg);
DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN); DLOG(INFO) << "Extended correlation enabled for Tracking CH " << d_channel << ": Satellite " << Gnss_Satellite(systemName[sys], d_acquisition_gnss_synchro->PRN);
if (d_enable_extended_integration == false) //avoid re-setting preamble indicator if (d_enable_extended_integration == false) // avoid re-setting preamble indicator
{ {
d_preamble_timestamp_s = pmt::to_double(std::move(msg)); d_preamble_timestamp_s = pmt::to_double(std::move(msg));
d_enable_extended_integration = true; d_enable_extended_integration = true;
@ -166,7 +166,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_sc::glonass_l2_ca_dll_pll_c_aid_tracking_sc
d_rem_carrier_phase_rad = 0.0; d_rem_carrier_phase_rad = 0.0;
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; //(from trk to tlm) d_sample_counter = 0ULL; // (from trk to tlm)
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
d_pull_in = false; d_pull_in = false;
@ -207,7 +207,7 @@ glonass_l2_ca_dll_pll_c_aid_tracking_sc::glonass_l2_ca_dll_pll_c_aid_tracking_sc
d_carrier_doppler_old_hz = 0.0; d_carrier_doppler_old_hz = 0.0;
d_glonass_freq_ch = 0; d_glonass_freq_ch = 0;
//set_min_output_buffer((int64_t)300); // set_min_output_buffer((int64_t)300);
} }
@ -222,7 +222,7 @@ void glonass_l2_ca_dll_pll_c_aid_tracking_sc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
// Doppler effect // Doppler effect
@ -692,7 +692,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
{ {
// ################## PLL ########################################################## // ################## PLL ##########################################################
// Update PLL discriminator [rads/Ti -> Secs/Ti] // Update PLL discriminator [rads/Ti -> Secs/Ti]
d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex<float>(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())) / GLONASS_TWO_PI; //prompt output d_carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(std::complex<float>(d_correlator_outs_16sc[1].real(), d_correlator_outs_16sc[1].imag())) / GLONASS_TWO_PI; // prompt output
d_carrier_doppler_old_hz = d_carrier_doppler_hz; d_carrier_doppler_old_hz = d_carrier_doppler_hz;
// Carrier discriminator filter // Carrier discriminator filter
// NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan // NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan
@ -720,24 +720,24 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
double K_prn_samples = round(T_prn_samples); double K_prn_samples = round(T_prn_samples);
double K_T_prn_error_samples = K_prn_samples - T_prn_samples; double K_T_prn_error_samples = K_prn_samples - T_prn_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); //(code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in); d_rem_code_phase_samples = d_rem_code_phase_samples - K_T_prn_error_samples + code_error_filt_secs_Ti * static_cast<double>(d_fs_in); // (code_error_filt_secs_Ti + d_pll_to_dll_assist_secs_Ti) * static_cast<double>(d_fs_in);
d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples d_rem_code_phase_integer_samples = round(d_rem_code_phase_samples); // round to a discrete number of samples
d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples; d_correlation_length_samples = K_prn_samples + d_rem_code_phase_integer_samples;
d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples; d_rem_code_phase_samples = d_rem_code_phase_samples - d_rem_code_phase_integer_samples;
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI; d_acc_carrier_phase_cycles -= d_carrier_phase_step_rad * d_correlation_length_samples / GLONASS_TWO_PI;
// UPDATE ACCUMULATED CARRIER PHASE // UPDATE ACCUMULATED CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in)); CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad] // remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI); d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GLONASS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GLONASS_TWO_PI);
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips] // remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in)); d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### // ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
@ -770,7 +770,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -885,7 +885,7 @@ int glonass_l2_ca_dll_pll_c_aid_tracking_sc::general_work(int noutput_items __at
} }
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples d_sample_counter += d_correlation_length_samples; // count for the processed samples
return 1; //output tracking result ALWAYS even in the case of d_enable_tracking==false return 1; // output tracking result ALWAYS even in the case of d_enable_tracking==false
} }

View File

@ -124,9 +124,9 @@ private:
gr_complex* d_ca_code; gr_complex* d_ca_code;
lv_16sc_t* d_ca_code_16sc; lv_16sc_t* d_ca_code_16sc;
float* d_local_code_shift_chips; float* d_local_code_shift_chips;
//gr_complex* d_correlator_outs; // gr_complex* d_correlator_outs;
lv_16sc_t* d_correlator_outs_16sc; lv_16sc_t* d_correlator_outs_16sc;
//cpu_multicorrelator multicorrelator_cpu; // cpu_multicorrelator multicorrelator_cpu;
Cpu_Multicorrelator_16sc multicorrelator_cpu_16sc; Cpu_Multicorrelator_16sc multicorrelator_cpu_16sc;
// remaining code phase and carrier phase between tracking loops // remaining code phase and carrier phase between tracking loops
@ -172,10 +172,10 @@ private:
std::deque<lv_16sc_t> d_P_history; std::deque<lv_16sc_t> d_P_history;
std::deque<lv_16sc_t> d_L_history; std::deque<lv_16sc_t> d_L_history;
//Integration period in samples // Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -201,4 +201,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L2_CA_DLL_PLL_C_AID_TRACKING_SC_H #endif // GNSS_SDR_GLONASS_L2_CA_DLL_PLL_C_AID_TRACKING_SC_H

View File

@ -77,7 +77,7 @@ void Glonass_L2_Ca_Dll_Pll_Tracking_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
@ -106,7 +106,7 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
d_code_loop_filter.set_DLL_BW(dll_bw_hz); d_code_loop_filter.set_DLL_BW(dll_bw_hz);
d_carrier_loop_filter.set_PLL_BW(pll_bw_hz); d_carrier_loop_filter.set_PLL_BW(pll_bw_hz);
//--- DLL variables -------------------------------------------------------- // --- DLL variables -------------------------------------------------------
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips) d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
// Initialization of local code replica // Initialization of local code replica
@ -128,7 +128,7 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
multicorrelator_cpu.init(2 * d_current_prn_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_current_prn_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_chips = GLONASS_L2_CA_CODE_RATE_HZ; d_code_freq_chips = GLONASS_L2_CA_CODE_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -138,7 +138,7 @@ Glonass_L2_Ca_Dll_Pll_Tracking_cc::Glonass_L2_Ca_Dll_Pll_Tracking_cc(
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; d_sample_counter = 0ULL;
//d_sample_counter_seconds = 0; // d_sample_counter_seconds = 0;
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
@ -184,7 +184,7 @@ void Glonass_L2_Ca_Dll_Pll_Tracking_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in); acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in);
// Doppler effect // Doppler effect
@ -581,19 +581,19 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); // [chips/second] code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips); // [chips/second]
double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips); double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
double T_prn_seconds = T_chip_seconds * GLONASS_L2_CA_CODE_LENGTH_CHIPS; double T_prn_seconds = T_chip_seconds * GLONASS_L2_CA_CODE_LENGTH_CHIPS;
double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips * T_chip_seconds); //[seconds] double code_error_filt_secs = (T_prn_seconds * code_error_filt_chips * T_chip_seconds); // [seconds]
//double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GLONASS_L1_CA_CODE_RATE_HZ; // [seconds] // double code_error_filt_secs = (GPS_L1_CA_CODE_PERIOD * code_error_filt_chips) / GLONASS_L1_CA_CODE_RATE_HZ; // [seconds]
// ################## CARRIER AND CODE NCO BUFFER ALIGNMENT ####################### // ################## CARRIER AND CODE NCO BUFFER ALIGNMENT #######################
// keep alignment parameters for the next input buffer // keep alignment parameters for the next input buffer
// Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation // Compute the next buffer length based in the new period of the PRN sequence and the code phase error estimation
//double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips); // double T_chip_seconds = 1.0 / static_cast<double>(d_code_freq_chips);
//double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS; // double T_prn_seconds = T_chip_seconds * GLONASS_L1_CA_CODE_LENGTH_CHIPS;
double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in); double T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in); double K_blk_samples = T_prn_samples + d_rem_code_phase_samples + code_error_filt_secs * static_cast<double>(d_fs_in);
d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples d_current_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
// carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_doppler_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_doppler_phase_step_rad = GLONASS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_frequency_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GLONASS_TWO_PI * d_carrier_frequency_hz / static_cast<double>(d_fs_in);
@ -603,7 +603,7 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
// carrier phase accumulator // carrier phase accumulator
d_acc_carrier_phase_rad -= d_carrier_doppler_phase_step_rad * d_current_prn_length_samples; d_acc_carrier_phase_rad -= d_carrier_doppler_phase_step_rad * d_current_prn_length_samples;
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
// code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
// remnant code phase [chips] // remnant code phase [chips]
@ -614,7 +614,7 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES) if (d_cn0_estimation_counter < CN0_ESTIMATION_SAMPLES)
{ {
// fill buffer with prompt correlator output values // fill buffer with prompt correlator output values
d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; //prompt d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; // prompt
d_cn0_estimation_counter++; d_cn0_estimation_counter++;
} }
else else
@ -668,7 +668,7 @@ int Glonass_L2_Ca_Dll_Pll_Tracking_cc::general_work(int noutput_items __attribut
current_synchro_data.correlation_length_ms = 1; current_synchro_data.correlation_length_ms = 1;
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
if (d_dump) if (d_dump)

View File

@ -127,7 +127,6 @@ private:
gr_complex* d_correlator_outs; gr_complex* d_correlator_outs;
Cpu_Multicorrelator multicorrelator_cpu; Cpu_Multicorrelator multicorrelator_cpu;
// tracking vars // tracking vars
double d_code_freq_chips; double d_code_freq_chips;
double d_code_phase_step_chips; double d_code_phase_step_chips;
@ -138,10 +137,10 @@ private:
double d_acc_carrier_phase_rad; double d_acc_carrier_phase_rad;
double d_code_phase_samples; double d_code_phase_samples;
//PRN period in samples // PRN period in samples
int32_t d_current_prn_length_samples; int32_t d_current_prn_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -167,4 +166,4 @@ private:
int32_t save_matfile(); int32_t save_matfile();
}; };
#endif //GNSS_SDR_GLONASS_L2_CA_DLL_PLL_TRACKING_CC_H #endif // GNSS_SDR_GLONASS_L2_CA_DLL_PLL_TRACKING_CC_H

View File

@ -64,7 +64,7 @@ void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
@ -94,13 +94,13 @@ Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc(
d_code_loop_filter.set_DLL_BW(dll_bw_hz); d_code_loop_filter.set_DLL_BW(dll_bw_hz);
d_carrier_loop_filter.set_params(10.0, pll_bw_hz, 2); d_carrier_loop_filter.set_params(10.0, pll_bw_hz, 2);
//--- DLL variables -------------------------------------------------------- // --- DLL variables -------------------------------------------------------
d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips) d_early_late_spc_chips = early_late_space_chips; // Define early-late offset (in chips)
// Set GPU flags // Set GPU flags
cudaSetDeviceFlags(cudaDeviceMapHost); cudaSetDeviceFlags(cudaDeviceMapHost);
//allocate host memory // allocate host memory
//pinned memory mode - use special function to get OS-pinned memory // pinned memory mode - use special function to get OS-pinned memory
d_n_correlator_taps = 3; // Early, Prompt, and Late d_n_correlator_taps = 3; // Early, Prompt, and Late
// Get space for a vector with the C/A code replica sampled 1x/chip // Get space for a vector with the C/A code replica sampled 1x/chip
cudaHostAlloc(reinterpret_cast<void **>(&d_ca_code), (static_cast<int32_t>(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(gr_complex)), cudaHostAllocMapped || cudaHostAllocWriteCombined); cudaHostAlloc(reinterpret_cast<void **>(&d_ca_code), (static_cast<int32_t>(GPS_L1_CA_CODE_LENGTH_CHIPS) * sizeof(gr_complex)), cudaHostAllocMapped || cudaHostAllocWriteCombined);
@ -115,9 +115,9 @@ Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc(
d_local_code_shift_chips[1] = 0.0; d_local_code_shift_chips[1] = 0.0;
d_local_code_shift_chips[2] = d_early_late_spc_chips; d_local_code_shift_chips[2] = d_early_late_spc_chips;
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
multicorrelator_gpu = new cuda_multicorrelator(); multicorrelator_gpu = new cuda_multicorrelator();
//local code resampler on GPU // local code resampler on GPU
multicorrelator_gpu->init_cuda_integrated_resampler(2 * d_vector_length, GPS_L1_CA_CODE_LENGTH_CHIPS, d_n_correlator_taps); multicorrelator_gpu->init_cuda_integrated_resampler(2 * d_vector_length, GPS_L1_CA_CODE_LENGTH_CHIPS, d_n_correlator_taps);
multicorrelator_gpu->set_input_output_vectors(d_correlator_outs, in_gpu); multicorrelator_gpu->set_input_output_vectors(d_correlator_outs, in_gpu);
@ -130,7 +130,7 @@ Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc(
// sample synchronization // sample synchronization
d_sample_counter = 0ULL; d_sample_counter = 0ULL;
//d_sample_counter_seconds = 0; // d_sample_counter_seconds = 0;
d_acq_sample_stamp = 0; d_acq_sample_stamp = 0;
d_enable_tracking = false; d_enable_tracking = false;
@ -161,7 +161,7 @@ Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc(
d_rem_code_phase_chips = 0.0; d_rem_code_phase_chips = 0.0;
d_code_phase_step_chips = 0.0; d_code_phase_step_chips = 0.0;
d_carrier_phase_step_rad = 0.0; d_carrier_phase_step_rad = 0.0;
//set_min_output_buffer((int64_t)300); // set_min_output_buffer((int64_t)300);
} }
@ -176,10 +176,10 @@ void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking =" << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in); acq_trk_diff_seconds = static_cast<double>(acq_trk_diff_samples) / static_cast<double>(d_fs_in);
//doppler effect // doppler effect
// Fd=(C/(C+Vr))*F // Fd=(C/(C+Vr))*F
double radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ; double radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ;
// new chip and prn sequence periods based on acq Doppler // new chip and prn sequence periods based on acq Doppler
@ -213,7 +213,7 @@ void Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::start_tracking()
d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
// DLL/PLL filter initialization // DLL/PLL filter initialization
d_carrier_loop_filter.initialize(d_acq_carrier_doppler_hz); //The carrier loop filter implements the Doppler accumulator d_carrier_loop_filter.initialize(d_acq_carrier_doppler_hz); // The carrier loop filter implements the Doppler accumulator
d_code_loop_filter.initialize(); // initialize the code filter d_code_loop_filter.initialize(); // initialize the code filter
// generate local reference ALWAYS starting at chip 1 (1 sample per chip) // generate local reference ALWAYS starting at chip 1 (1 sample per chip)
@ -347,9 +347,9 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
current_synchro_data.correlation_length_ms = 1; current_synchro_data.correlation_length_ms = 1;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
d_sample_counter += static_cast<uint64_t>(samples_offset); //count for the processed samples d_sample_counter += static_cast<uint64_t>(samples_offset); // count for the processed samples
d_pull_in = false; d_pull_in = false;
consume_each(samples_offset); //shift input to perform alignment with local replica consume_each(samples_offset); // shift input to perform alignment with local replica
return 1; return 1;
} }
@ -364,17 +364,17 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
static_cast<float>(d_rem_code_phase_chips), static_cast<float>(d_rem_code_phase_chips),
d_correlation_length_samples, d_n_correlator_taps); d_correlation_length_samples, d_n_correlator_taps);
cudaProfilerStop(); cudaProfilerStop();
//std::cout<<"c_out[0]="<<d_correlator_outs[0]<<"c_out[1]="<<d_correlator_outs[1]<<"c_out[2]="<<d_correlator_outs[2]<<std::endl; // std::cout<<"c_out[0]="<<d_correlator_outs[0]<<"c_out[1]="<<d_correlator_outs[1]<<"c_out[2]="<<d_correlator_outs[2]<<std::endl;
// UPDATE INTEGRATION TIME // UPDATE INTEGRATION TIME
CURRENT_INTEGRATION_TIME_S = static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in); CURRENT_INTEGRATION_TIME_S = static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in);
// ################## PLL ########################################################## // ################## PLL ##########################################################
// Update PLL discriminator [rads/Ti -> Secs/Ti] // Update PLL discriminator [rads/Ti -> Secs/Ti]
carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(d_correlator_outs[1]) / GPS_TWO_PI; //prompt output carr_phase_error_secs_Ti = pll_cloop_two_quadrant_atan(d_correlator_outs[1]) / GPS_TWO_PI; // prompt output
// Carrier discriminator filter // Carrier discriminator filter
// NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan // NOTICE: The carrier loop filter includes the Carrier Doppler accumulator, as described in Kaplan
//d_carrier_doppler_hz = d_acq_carrier_doppler_hz + carr_phase_error_filt_secs_ti/INTEGRATION_TIME; // d_carrier_doppler_hz = d_acq_carrier_doppler_hz + carr_phase_error_filt_secs_ti/INTEGRATION_TIME;
// Input [s/Ti] -> output [Hz] // Input [s/Ti] -> output [Hz]
d_carrier_doppler_hz = d_carrier_loop_filter.get_carrier_error(0.0, carr_phase_error_secs_Ti, CURRENT_INTEGRATION_TIME_S); d_carrier_doppler_hz = d_carrier_loop_filter.get_carrier_error(0.0, carr_phase_error_secs_Ti, CURRENT_INTEGRATION_TIME_S);
// PLL to DLL assistance [Secs/Ti] // PLL to DLL assistance [Secs/Ti]
@ -384,9 +384,9 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
// ################## DLL ########################################################## // ################## DLL ##########################################################
// DLL discriminator // DLL discriminator
code_error_chips_Ti = dll_nc_e_minus_l_normalized(d_correlator_outs[0], d_correlator_outs[2]); //[chips/Ti] //early and late code_error_chips_Ti = dll_nc_e_minus_l_normalized(d_correlator_outs[0], d_correlator_outs[2]); // [chips/Ti] // early and late
// Code discriminator filter // Code discriminator filter
code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips_Ti); //input [chips/Ti] -> output [chips/second] code_error_filt_chips = d_code_loop_filter.get_code_nco(code_error_chips_Ti); // input [chips/Ti] -> output [chips/second]
code_error_filt_secs_Ti = code_error_filt_chips * CURRENT_INTEGRATION_TIME_S / d_code_freq_chips; // [s/Ti] code_error_filt_secs_Ti = code_error_filt_chips * CURRENT_INTEGRATION_TIME_S / d_code_freq_chips; // [s/Ti]
// DLL code error estimation [s/Ti] // DLL code error estimation [s/Ti]
// TODO: PLL carrier aid to DLL is disabled. Re-enable it and measure performance // TODO: PLL carrier aid to DLL is disabled. Re-enable it and measure performance
@ -404,32 +404,32 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in); T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
K_blk_samples = T_prn_samples + d_rem_code_phase_samples - dll_code_error_secs_Ti * static_cast<double>(d_fs_in); K_blk_samples = T_prn_samples + d_rem_code_phase_samples - dll_code_error_secs_Ti * static_cast<double>(d_fs_in);
d_correlation_length_samples = round(K_blk_samples); //round to a discrete samples d_correlation_length_samples = round(K_blk_samples); // round to a discrete samples
d_rem_code_phase_samples = K_blk_samples - static_cast<double>(d_correlation_length_samples); //rounding error < 1 sample d_rem_code_phase_samples = K_blk_samples - static_cast<double>(d_correlation_length_samples); // rounding error < 1 sample
// UPDATE REMNANT CARRIER PHASE // UPDATE REMNANT CARRIER PHASE
CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in)); CORRECTED_INTEGRATION_TIME_S = (static_cast<double>(d_correlation_length_samples) / static_cast<double>(d_fs_in));
//remnant carrier phase [rad] // remnant carrier phase [rad]
d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GPS_TWO_PI); d_rem_carrier_phase_rad = fmod(d_rem_carrier_phase_rad + GPS_TWO_PI * d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S, GPS_TWO_PI);
// UPDATE CARRIER PHASE ACCUULATOR // UPDATE CARRIER PHASE ACCUULATOR
//carrier phase accumulator prior to update the PLL estimators (accumulated carrier in this loop depends on the old estimations!) // carrier phase accumulator prior to update the PLL estimators (accumulated carrier in this loop depends on the old estimations!)
d_acc_carrier_phase_cycles -= d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S; d_acc_carrier_phase_cycles -= d_carrier_doppler_hz * CORRECTED_INTEGRATION_TIME_S;
//################### PLL COMMANDS ################################################# // ################### PLL COMMANDS #################################################
//carrier phase step (NCO phase increment per sample) [rads/sample] // carrier phase step (NCO phase increment per sample) [rads/sample]
d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in); d_carrier_phase_step_rad = GPS_TWO_PI * d_carrier_doppler_hz / static_cast<double>(d_fs_in);
//################### DLL COMMANDS ################################################# // ################### DLL COMMANDS #################################################
//code phase step (Code resampler phase increment per sample) [chips/sample] // code phase step (Code resampler phase increment per sample) [chips/sample]
d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in); d_code_phase_step_chips = d_code_freq_chips / static_cast<double>(d_fs_in);
//remnant code phase [chips] // remnant code phase [chips]
d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in)); d_rem_code_phase_chips = d_rem_code_phase_samples * (d_code_freq_chips / static_cast<double>(d_fs_in));
// ####### CN0 ESTIMATION AND LOCK DETECTORS ####################################### // ####### CN0 ESTIMATION AND LOCK DETECTORS #######################################
if (d_cn0_estimation_counter < FLAGS_cn0_samples) if (d_cn0_estimation_counter < FLAGS_cn0_samples)
{ {
// fill buffer with prompt correlator output values // fill buffer with prompt correlator output values
d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; //prompt d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; // prompt
d_cn0_estimation_counter++; d_cn0_estimation_counter++;
} }
else else
@ -452,7 +452,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -481,7 +481,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples);
} }
//assign the GNURadio block output data // assign the GNU Radio block output data
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
@ -551,7 +551,7 @@ int Gps_L1_Ca_Dll_Pll_Tracking_GPU_cc::general_work(int noutput_items __attribut
} }
consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates consume_each(d_correlation_length_samples); // this is necessary in gr::block derivates
d_sample_counter += d_correlation_length_samples; //count for the processed samples d_sample_counter += d_correlation_length_samples; // count for the processed samples
if (d_enable_tracking) if (d_enable_tracking)
{ {

View File

@ -115,7 +115,7 @@ private:
double d_early_late_spc_chips; double d_early_late_spc_chips;
int32_t d_n_correlator_taps; int32_t d_n_correlator_taps;
//GPU HOST PINNED MEMORY IN/OUT VECTORS // GPU HOST PINNED MEMORY IN/OUT VECTORS
gr_complex *in_gpu; gr_complex *in_gpu;
float *d_local_code_shift_chips; float *d_local_code_shift_chips;
gr_complex *d_correlator_outs; gr_complex *d_correlator_outs;
@ -126,7 +126,6 @@ private:
gr_complex *d_Prompt; gr_complex *d_Prompt;
gr_complex *d_Late; gr_complex *d_Late;
// remaining code phase and carrier phase between tracking loops // remaining code phase and carrier phase between tracking loops
double d_rem_code_phase_samples; double d_rem_code_phase_samples;
double d_rem_code_phase_chips; double d_rem_code_phase_chips;
@ -149,10 +148,10 @@ private:
double d_code_phase_samples; double d_code_phase_samples;
double d_pll_to_dll_assist_secs_Ti; double d_pll_to_dll_assist_secs_Ti;
//Integration period in samples // Integration period in samples
int32_t d_correlation_length_samples; int32_t d_correlation_length_samples;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -176,4 +175,4 @@ private:
std::string sys; std::string sys;
}; };
#endif //GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_GPU_CC_H #endif // GNSS_SDR_GPS_L1_CA_DLL_PLL_TRACKING_GPU_CC_H

View File

@ -264,6 +264,7 @@ Gps_L1_Ca_Kf_Tracking_cc::Gps_L1_Ca_Kf_Tracking_cc(
bayes_estimator.init(arma::zeros(1, 1), bayes_kappa, bayes_nu, (kf_H * kf_P_x_ini * kf_H.t() + kf_R) * (bayes_nu + 2)); bayes_estimator.init(arma::zeros(1, 1), bayes_kappa, bayes_nu, (kf_H * kf_P_x_ini * kf_H.t() + kf_R) * (bayes_nu + 2));
} }
void Gps_L1_Ca_Kf_Tracking_cc::start_tracking() void Gps_L1_Ca_Kf_Tracking_cc::start_tracking()
{ {
/* /*
@ -283,7 +284,7 @@ void Gps_L1_Ca_Kf_Tracking_cc::start_tracking()
int64_t acq_trk_diff_samples; int64_t acq_trk_diff_samples;
double acq_trk_diff_seconds; double acq_trk_diff_seconds;
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); //-d_vector_length; acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); // -d_vector_length;
DLOG(INFO) << "Number of samples between Acquisition and Tracking = " << acq_trk_diff_samples; DLOG(INFO) << "Number of samples between Acquisition and Tracking = " << acq_trk_diff_samples;
acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in); acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in);
// Doppler effect Fd = (C / (C + Vr)) * F // Doppler effect Fd = (C / (C + Vr)) * F
@ -703,8 +704,8 @@ int Gps_L1_Ca_Kf_Tracking_cc::general_work(int noutput_items __attribute__((unus
// ################## Kalman Carrier Tracking ###################################### // ################## Kalman Carrier Tracking ######################################
// Kalman state prediction (time update) // Kalman state prediction (time update)
kf_x_pre = kf_F * kf_x; //state prediction kf_x_pre = kf_F * kf_x; // state prediction
kf_P_x_pre = kf_F * kf_P_x * kf_F.t() + kf_Q; //state error covariance prediction kf_P_x_pre = kf_F * kf_P_x * kf_F.t() + kf_Q; // state error covariance prediction
// Update discriminator [rads/Ti] // Update discriminator [rads/Ti]
d_carr_phase_error_rad = pll_cloop_two_quadrant_atan(d_correlator_outs[1]); // prompt output d_carr_phase_error_rad = pll_cloop_two_quadrant_atan(d_correlator_outs[1]); // prompt output
@ -786,7 +787,7 @@ int Gps_L1_Ca_Kf_Tracking_cc::general_work(int noutput_items __attribute__((unus
if (d_cn0_estimation_counter < FLAGS_cn0_samples) if (d_cn0_estimation_counter < FLAGS_cn0_samples)
{ {
// fill buffer with prompt correlator output values // fill buffer with prompt correlator output values
d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; //prompt d_Prompt_buffer[d_cn0_estimation_counter] = d_correlator_outs[1]; // prompt
d_cn0_estimation_counter++; d_cn0_estimation_counter++;
} }
else else
@ -799,10 +800,10 @@ int Gps_L1_Ca_Kf_Tracking_cc::general_work(int noutput_items __attribute__((unus
// Loss of lock detection // Loss of lock detection
if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < FLAGS_cn0_min) if (d_carrier_lock_test < d_carrier_lock_threshold or d_CN0_SNV_dB_Hz < FLAGS_cn0_min)
{ {
//if (d_channel == 1) // if (d_channel == 1)
//std::cout << "Carrier Lock Test Fail in channel " << d_channel << ": " << d_carrier_lock_test << " < " << d_carrier_lock_threshold << "," << nfail++ << std::endl; // std::cout << "Carrier Lock Test Fail in channel " << d_channel << ": " << d_carrier_lock_test << " < " << d_carrier_lock_threshold << "," << nfail++ << std::endl;
d_carrier_lock_fail_counter++; d_carrier_lock_fail_counter++;
//nfail++; // nfail++;
} }
else else
{ {

View File

@ -72,7 +72,7 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::forecast(int noutput_items,
{ {
if (noutput_items != 0) if (noutput_items != 0)
{ {
ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; //set the required available samples in each call ninput_items_required[0] = static_cast<int32_t>(d_vector_length) * 2; // set the required available samples in each call
} }
} }
@ -129,7 +129,7 @@ Gps_L1_Ca_Tcp_Connector_Tracking_cc::Gps_L1_Ca_Tcp_Connector_Tracking_cc(
multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps); multicorrelator_cpu.init(2 * d_correlation_length_samples, d_n_correlator_taps);
//--- Perform initializations ------------------------------ // --- Perform initializations ------------------------------
// define initial code frequency basis of NCO // define initial code frequency basis of NCO
d_code_freq_hz = GPS_L1_CA_CODE_RATE_HZ; d_code_freq_hz = GPS_L1_CA_CODE_RATE_HZ;
// define residual code phase (in chips) // define residual code phase (in chips)
@ -189,7 +189,7 @@ void Gps_L1_Ca_Tcp_Connector_Tracking_cc::start_tracking()
acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp); acq_trk_diff_samples = static_cast<int64_t>(d_sample_counter) - static_cast<int64_t>(d_acq_sample_stamp);
std::cout << "acq_trk_diff_samples=" << acq_trk_diff_samples << std::endl; std::cout << "acq_trk_diff_samples=" << acq_trk_diff_samples << std::endl;
acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in); acq_trk_diff_seconds = static_cast<float>(acq_trk_diff_samples) / static_cast<float>(d_fs_in);
//doppler effect // doppler effect
// Fd=(C/(C+Vr))*F // Fd=(C/(C+Vr))*F
float radial_velocity; float radial_velocity;
radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ; radial_velocity = (GPS_L1_FREQ_HZ + d_acq_carrier_doppler_hz) / GPS_L1_FREQ_HZ;
@ -362,9 +362,9 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
current_synchro_data.fs = d_fs_in; current_synchro_data.fs = d_fs_in;
*out[0] = current_synchro_data; *out[0] = current_synchro_data;
d_sample_counter_seconds = d_sample_counter_seconds + (static_cast<double>(samples_offset) / static_cast<double>(d_fs_in)); d_sample_counter_seconds = d_sample_counter_seconds + (static_cast<double>(samples_offset) / static_cast<double>(d_fs_in));
d_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset); //count for the processed samples d_sample_counter = d_sample_counter + static_cast<uint64_t>(samples_offset); // count for the processed samples
d_pull_in = false; d_pull_in = false;
consume_each(samples_offset); //shift input to perform alignment with local replica consume_each(samples_offset); // shift input to perform alignment with local replica
return 1; return 1;
} }
@ -386,10 +386,10 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
d_code_phase_step_chips, d_code_phase_step_chips,
d_current_prn_length_samples); d_current_prn_length_samples);
//! Variable used for control // Variable used for control
d_control_id++; d_control_id++;
//! Send and receive a TCP packet // Send and receive a TCP packet
boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> tx_variables_array = {{d_control_id, boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> tx_variables_array = {{d_control_id,
(*d_Early).real(), (*d_Early).real(),
(*d_Early).imag(), (*d_Early).imag(),
@ -401,7 +401,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
1}}; 1}};
d_tcp_com.send_receive_tcp_packet_gps_l1_ca(tx_variables_array, &tcp_data); d_tcp_com.send_receive_tcp_packet_gps_l1_ca(tx_variables_array, &tcp_data);
//! Recover the tracking data // Recover the tracking data
code_error = tcp_data.proc_pack_code_error; code_error = tcp_data.proc_pack_code_error;
carr_error = tcp_data.proc_pack_carr_error; carr_error = tcp_data.proc_pack_carr_error;
// Modify carrier freq based on NCO command // Modify carrier freq based on NCO command
@ -412,7 +412,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
// Update the phasestep based on code freq (variable) and // Update the phasestep based on code freq (variable) and
// sampling frequency (fixed) // sampling frequency (fixed)
d_code_phase_step_chips = d_code_freq_hz / static_cast<float>(d_fs_in); //[chips] d_code_phase_step_chips = d_code_freq_hz / static_cast<float>(d_fs_in); // [chips]
// variable code PRN sample block size // variable code PRN sample block size
double T_chip_seconds; double T_chip_seconds;
double T_prn_seconds; double T_prn_seconds;
@ -422,7 +422,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS; T_prn_seconds = T_chip_seconds * GPS_L1_CA_CODE_LENGTH_CHIPS;
T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in); T_prn_samples = T_prn_seconds * static_cast<double>(d_fs_in);
d_rem_code_phase_samples = d_next_rem_code_phase_samples; d_rem_code_phase_samples = d_next_rem_code_phase_samples;
K_blk_samples = T_prn_samples + d_rem_code_phase_samples; //-code_error*(double)d_fs_in; K_blk_samples = T_prn_samples + d_rem_code_phase_samples; // -code_error*(double)d_fs_in;
// Update the current PRN delay (code phase in samples) // Update the current PRN delay (code phase in samples)
double T_prn_true_seconds = GPS_L1_CA_CODE_LENGTH_CHIPS / GPS_L1_CA_CODE_RATE_HZ; double T_prn_true_seconds = GPS_L1_CA_CODE_LENGTH_CHIPS / GPS_L1_CA_CODE_RATE_HZ;
@ -434,8 +434,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
} }
d_code_phase_samples = fmod(d_code_phase_samples, T_prn_true_samples); d_code_phase_samples = fmod(d_code_phase_samples, T_prn_true_samples);
d_next_prn_length_samples = round(K_blk_samples); //round to a discrete samples d_next_prn_length_samples = round(K_blk_samples); // round to a discrete number of samples
d_next_rem_code_phase_samples = K_blk_samples - d_next_prn_length_samples; //rounding error d_next_rem_code_phase_samples = K_blk_samples - d_next_prn_length_samples; // rounding error
/*! /*!
* \todo Improve the lock detection algorithm! * \todo Improve the lock detection algorithm!
@ -469,7 +469,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
{ {
std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl; std::cout << "Loss of lock in channel " << d_channel << "!" << std::endl;
LOG(INFO) << "Loss of lock in channel " << d_channel << "!"; LOG(INFO) << "Loss of lock in channel " << d_channel << "!";
this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); //3 -> loss of lock this->message_port_pub(pmt::mp("events"), pmt::from_long(3)); // 3 -> loss of lock
d_carrier_lock_fail_counter = 0; d_carrier_lock_fail_counter = 0;
d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine d_enable_tracking = false; // TODO: check if disabling tracking is consistent with the channel state machine
} }
@ -479,8 +479,8 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
current_synchro_data.Prompt_I = static_cast<double>((*d_Prompt).real()); current_synchro_data.Prompt_I = static_cast<double>((*d_Prompt).real());
current_synchro_data.Prompt_Q = static_cast<double>((*d_Prompt).imag()); current_synchro_data.Prompt_Q = static_cast<double>((*d_Prompt).imag());
//compute remnant code phase samples AFTER the Tracking timestamp // compute remnant code phase samples AFTER the Tracking timestamp
d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; //rounding error < 1 sample d_rem_code_phase_samples = K_blk_samples - d_current_prn_length_samples; // rounding error < 1 sample
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_current_prn_length_samples);
current_synchro_data.Code_phase_samples = d_rem_code_phase_samples; current_synchro_data.Code_phase_samples = d_rem_code_phase_samples;
current_synchro_data.Carrier_phase_rads = static_cast<double>(d_acc_carrier_phase_rad); current_synchro_data.Carrier_phase_rads = static_cast<double>(d_acc_carrier_phase_rad);
@ -496,7 +496,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
*d_Late = gr_complex(0, 0); *d_Late = gr_complex(0, 0);
// GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder // GNSS_SYNCHRO OBJECT to interchange data between tracking->telemetry_decoder
current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples); current_synchro_data.Tracking_sample_counter = d_sample_counter + static_cast<uint64_t>(d_correlation_length_samples);
//! When tracking is disabled an array of 1's is sent to maintain the TCP connection // When tracking is disabled an array of 1's is sent to maintain the TCP connection
boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> tx_variables_array = {{1, 1, 1, 1, 1, 1, 1, 1, 0}}; boost::array<float, NUM_TX_VARIABLES_GPS_L1_CA> tx_variables_array = {{1, 1, 1, 1, 1, 1, 1, 1, 0}};
d_tcp_com.send_receive_tcp_packet_gps_l1_ca(tx_variables_array, &tcp_data); d_tcp_com.send_receive_tcp_packet_gps_l1_ca(tx_variables_array, &tcp_data);
} }
@ -579,7 +579,7 @@ int Gps_L1_Ca_Tcp_Connector_Tracking_cc::general_work(int noutput_items __attrib
consume_each(d_current_prn_length_samples); // this is necessary in gr::block derivates consume_each(d_current_prn_length_samples); // this is necessary in gr::block derivates
d_sample_counter_seconds = d_sample_counter_seconds + (static_cast<double>(d_current_prn_length_samples) / static_cast<double>(d_fs_in)); d_sample_counter_seconds = d_sample_counter_seconds + (static_cast<double>(d_current_prn_length_samples) / static_cast<double>(d_fs_in));
d_sample_counter += d_current_prn_length_samples; //count for the processed samples d_sample_counter += d_current_prn_length_samples; // count for the processed samples
if (d_enable_tracking) if (d_enable_tracking)
{ {

View File

@ -142,12 +142,12 @@ private:
float d_control_id; float d_control_id;
Tcp_Communication d_tcp_com; Tcp_Communication d_tcp_com;
//PRN period in samples // PRN period in samples
int32_t d_current_prn_length_samples; int32_t d_current_prn_length_samples;
int32_t d_next_prn_length_samples; int32_t d_next_prn_length_samples;
double d_sample_counter_seconds; double d_sample_counter_seconds;
//processing samples counters // processing samples counters
uint64_t d_sample_counter; uint64_t d_sample_counter;
uint64_t d_acq_sample_stamp; uint64_t d_acq_sample_stamp;
@ -171,4 +171,4 @@ private:
std::string sys; std::string sys;
}; };
#endif //GNSS_SDR_GPS_L1_CA_TCP_CONNECTOR_TRACKING_CC_H #endif // GNSS_SDR_GPS_L1_CA_TCP_CONNECTOR_TRACKING_CC_H

Some files were not shown because too many files have changed in this diff Show More